+// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
+//
+// Changelog:
+// 2021-09-27 - split implementations out of header files, finally
+// 2019-07-08 - Added Auto Calibration routine
+// ... - ongoing debug release
+
+// NOTE: THIS IS ONLY A PARIAL RELEASE. THIS DEVICE CLASS IS CURRENTLY UNDERGOING ACTIVE
+// DEVELOPMENT AND IS STILL MISSING SOME IMPORTANT FEATURES. PLEASE KEEP THIS IN MIND IF
+// YOU DECIDE TO USE THIS PARTICULAR CODE FOR ANYTHING.
+
+/* ============================================
+I2Cdev device library code is placed under the MIT license
+Copyright (c) 2012 Jeff Rowberg
+
+Permission is hereby granted, free of charge, to any person obtaining a copy
+of this software and associated documentation files (the "Software"), to deal
+in the Software without restriction, including without limitation the rights
+to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+copies of the Software, and to permit persons to whom the Software is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in
+all copies or substantial portions of the Software.
+
+THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+THE SOFTWARE.
+===============================================
+*/
+
+#include "Arduino.h"
+#include "MPU6050.h"
+#if defined(ARDUINO_ARCH_MBED)
+#include "api/deprecated-avr-comp/avr/dtostrf.c.impl"
+#endif
+
+#ifndef DEBUG
+// #define DEBUG 0 // Uncomment to enable debug output
+#endif
+
+/** Specific address constructor.
+ * @param address I2C address, uses default I2C address if none is specified
+ * @see MPU6050_DEFAULT_ADDRESS
+ * @see MPU6050_ADDRESS_AD0_LOW
+ * @see MPU6050_ADDRESS_AD0_HIGH
+ */
+MPU6050_Base::MPU6050_Base(uint8_t address, void *wireObj):devAddr(address), wireObj(wireObj) {
+}
+
+/** Power on and prepare for general usage.
+ * This will activate the device and take it out of sleep mode (which must be done
+ * after start-up). This function also sets both the accelerometer and the gyroscope
+ * to their most sensitive settings, namely +/- 2g and +/- 250 degrees/sec, and sets
+ * the clock source to use the X Gyro for reference, which is slightly better than
+ * the default internal clock source.
+ */
+void MPU6050_Base::initialize() {
+ setClockSource(MPU6050_CLOCK_PLL_XGYRO);
+
+ setFullScaleGyroRange(MPU6050_GYRO_FS_250);
+ gyroscopeResolution = 250.0 / 16384.0;
+
+ setFullScaleAccelRange(MPU6050_ACCEL_FS_2);
+ accelerationResolution = 2.0 / 16384.0;
+
+ setSleepEnabled(false); // thanks to Jack Elston for pointing this one out!
+}
+
+/** Power on and prepare for general usage.
+ * This will activate the device and take it out of sleep mode (which must be done
+ * after start-up). This function also sets both the accelerometer and the gyroscope
+ * to selected settings based on user perference. selection can be one of ,
+ *
+ * Accelerometer: ACCEL_FS::A2G, ACCEL_FS::A4G, ACCEL_FS::A8G, ACCEL_FS::A16G,
+ * Gyroscope: GYRO_FS::G250DPS, GYRO_FS::G500DPS, GYRO_FS::G1000DPS, GYRO_FS::G2000DPS,
+ *
+ * the clock source to use the X Gyro for reference, which is slightly better than
+ * the default internal clock source.
+ */
+void MPU6050_Base::initialize(ACCEL_FS accelRange, GYRO_FS gyroRange) {
+ setClockSource(MPU6050_CLOCK_PLL_XGYRO);
+
+ switch (accelRange)
+ {
+ case ACCEL_FS::A2G:
+ setFullScaleAccelRange(MPU6050_ACCEL_FS_2);
+ accelerationResolution = 2.0 / 16384.0;
+
+ case ACCEL_FS::A4G:
+ setFullScaleAccelRange(MPU6050_ACCEL_FS_4);
+ accelerationResolution = 4.0 / 16384.0;
+
+ case ACCEL_FS::A8G:
+ setFullScaleAccelRange(MPU6050_ACCEL_FS_8);
+ accelerationResolution = 8.0 / 16384.0;
+
+ case ACCEL_FS::A16G:
+ setFullScaleAccelRange(MPU6050_ACCEL_FS_16);
+ accelerationResolution = 16.0 / 16384.0;
+ }
+
+ switch (gyroRange)
+ {
+ case GYRO_FS::G250DPS:
+ setFullScaleGyroRange(MPU6050_GYRO_FS_250);
+ gyroscopeResolution = 250.0 / 16384.0;
+
+ case GYRO_FS::G500DPS:
+ setFullScaleGyroRange(MPU6050_GYRO_FS_500);
+ gyroscopeResolution = 500.0 / 16384.0;
+
+ case GYRO_FS::G1000DPS:
+ setFullScaleGyroRange(MPU6050_GYRO_FS_1000);
+ gyroscopeResolution = 1000.0 / 16384.0;
+
+ case GYRO_FS::G2000DPS:
+ setFullScaleGyroRange(MPU6050_GYRO_FS_2000);
+ gyroscopeResolution = 2000.0 / 16384.0;
+ }
+
+ setSleepEnabled(false); // thanks to Jack Elston for pointing this one out!
+}
+
+/** Get the accelration resolution.
+ */
+float MPU6050_Base::get_acce_resolution() {
+ return accelerationResolution;
+}
+
+/** Get the gyroscope resolution.
+ */
+float MPU6050_Base::get_gyro_resolution() {
+ return gyroscopeResolution;
+}
+
+/** Verify the I2C connection.
+ * Make sure the device is connected and responds as expected.
+ * @return True if connection is valid, false otherwise
+ */
+bool MPU6050_Base::testConnection() {
+ uint8_t deviceId = getDeviceID();
+ return (deviceId == 0x34) || (deviceId == 0xC);
+}
+
+// AUX_VDDIO register (InvenSense demo code calls this RA_*G_OFFS_TC)
+
+/** Get the auxiliary I2C supply voltage level.
+ * When set to 1, the auxiliary I2C bus high logic level is VDD. When cleared to
+ * 0, the auxiliary I2C bus high logic level is VLOGIC. This does not apply to
+ * the MPU-6000, which does not have a VLOGIC pin.
+ * @return I2C supply voltage level (0=VLOGIC, 1=VDD)
+ */
+uint8_t MPU6050_Base::getAuxVDDIOLevel() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_YG_OFFS_TC, MPU6050_TC_PWR_MODE_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set the auxiliary I2C supply voltage level.
+ * When set to 1, the auxiliary I2C bus high logic level is VDD. When cleared to
+ * 0, the auxiliary I2C bus high logic level is VLOGIC. This does not apply to
+ * the MPU-6000, which does not have a VLOGIC pin.
+ * @param level I2C supply voltage level (0=VLOGIC, 1=VDD)
+ */
+void MPU6050_Base::setAuxVDDIOLevel(uint8_t level) {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_YG_OFFS_TC, MPU6050_TC_PWR_MODE_BIT, level, wireObj);
+}
+
+// SMPLRT_DIV register
+
+/** Get gyroscope output rate divider.
+ * The sensor register output, FIFO output, DMP sampling, Motion detection, Zero
+ * Motion detection, and Free Fall detection are all based on the Sample Rate.
+ * The Sample Rate is generated by dividing the gyroscope output rate by
+ * SMPLRT_DIV:
+ *
+ * Sample Rate = Gyroscope Output Rate / (1 + SMPLRT_DIV)
+ *
+ * where Gyroscope Output Rate = 8kHz when the DLPF is disabled (DLPF_CFG = 0 or
+ * 7), and 1kHz when the DLPF is enabled (see Register 26).
+ *
+ * Note: The accelerometer output rate is 1kHz. This means that for a Sample
+ * Rate greater than 1kHz, the same accelerometer sample may be output to the
+ * FIFO, DMP, and sensor registers more than once.
+ *
+ * For a diagram of the gyroscope and accelerometer signal paths, see Section 8
+ * of the MPU-6000/MPU-6050 Product Specification document.
+ *
+ * @return Current sample rate
+ * @see MPU6050_RA_SMPLRT_DIV
+ */
+uint8_t MPU6050_Base::getRate() {
+ I2Cdev::readByte(devAddr, MPU6050_RA_SMPLRT_DIV, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set gyroscope sample rate divider.
+ * @param rate New sample rate divider
+ * @see getRate()
+ * @see MPU6050_RA_SMPLRT_DIV
+ */
+void MPU6050_Base::setRate(uint8_t rate) {
+ I2Cdev::writeByte(devAddr, MPU6050_RA_SMPLRT_DIV, rate, wireObj);
+}
+
+// CONFIG register
+
+/** Get external FSYNC configuration.
+ * Configures the external Frame Synchronization (FSYNC) pin sampling. An
+ * external signal connected to the FSYNC pin can be sampled by configuring
+ * EXT_SYNC_SET. Signal changes to the FSYNC pin are latched so that short
+ * strobes may be captured. The latched FSYNC signal will be sampled at the
+ * Sampling Rate, as defined in register 25. After sampling, the latch will
+ * reset to the current FSYNC signal state.
+ *
+ * The sampled value will be reported in place of the least significant bit in
+ * a sensor data register determined by the value of EXT_SYNC_SET according to
+ * the following table.
+ *
+ *
+ * EXT_SYNC_SET | FSYNC Bit Location
+ * -------------+-------------------
+ * 0 | Input disabled
+ * 1 | TEMP_OUT_L[0]
+ * 2 | GYRO_XOUT_L[0]
+ * 3 | GYRO_YOUT_L[0]
+ * 4 | GYRO_ZOUT_L[0]
+ * 5 | ACCEL_XOUT_L[0]
+ * 6 | ACCEL_YOUT_L[0]
+ * 7 | ACCEL_ZOUT_L[0]
+ *
+ *
+ * @return FSYNC configuration value
+ */
+uint8_t MPU6050_Base::getExternalFrameSync() {
+ I2Cdev::readBits(devAddr, MPU6050_RA_CONFIG, MPU6050_CFG_EXT_SYNC_SET_BIT, MPU6050_CFG_EXT_SYNC_SET_LENGTH, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set external FSYNC configuration.
+ * @see getExternalFrameSync()
+ * @see MPU6050_RA_CONFIG
+ * @param sync New FSYNC configuration value
+ */
+void MPU6050_Base::setExternalFrameSync(uint8_t sync) {
+ I2Cdev::writeBits(devAddr, MPU6050_RA_CONFIG, MPU6050_CFG_EXT_SYNC_SET_BIT, MPU6050_CFG_EXT_SYNC_SET_LENGTH, sync, wireObj);
+}
+/** Get digital low-pass filter configuration.
+ * The DLPF_CFG parameter sets the digital low pass filter configuration. It
+ * also determines the internal sampling rate used by the device as shown in
+ * the table below.
+ *
+ * Note: The accelerometer output rate is 1kHz. This means that for a Sample
+ * Rate greater than 1kHz, the same accelerometer sample may be output to the
+ * FIFO, DMP, and sensor registers more than once.
+ *
+ *
+ * | ACCELEROMETER | GYROSCOPE
+ * DLPF_CFG | Bandwidth | Delay | Bandwidth | Delay | Sample Rate
+ * ---------+-----------+--------+-----------+--------+-------------
+ * 0 | 260Hz | 0ms | 256Hz | 0.98ms | 8kHz
+ * 1 | 184Hz | 2.0ms | 188Hz | 1.9ms | 1kHz
+ * 2 | 94Hz | 3.0ms | 98Hz | 2.8ms | 1kHz
+ * 3 | 44Hz | 4.9ms | 42Hz | 4.8ms | 1kHz
+ * 4 | 21Hz | 8.5ms | 20Hz | 8.3ms | 1kHz
+ * 5 | 10Hz | 13.8ms | 10Hz | 13.4ms | 1kHz
+ * 6 | 5Hz | 19.0ms | 5Hz | 18.6ms | 1kHz
+ * 7 | -- Reserved -- | -- Reserved -- | Reserved
+ *
+ *
+ * @return DLFP configuration
+ * @see MPU6050_RA_CONFIG
+ * @see MPU6050_CFG_DLPF_CFG_BIT
+ * @see MPU6050_CFG_DLPF_CFG_LENGTH
+ */
+uint8_t MPU6050_Base::getDLPFMode() {
+ I2Cdev::readBits(devAddr, MPU6050_RA_CONFIG, MPU6050_CFG_DLPF_CFG_BIT, MPU6050_CFG_DLPF_CFG_LENGTH, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set digital low-pass filter configuration.
+ * @param mode New DLFP configuration setting
+ * @see getDLPFBandwidth()
+ * @see MPU6050_DLPF_BW_256
+ * @see MPU6050_RA_CONFIG
+ * @see MPU6050_CFG_DLPF_CFG_BIT
+ * @see MPU6050_CFG_DLPF_CFG_LENGTH
+ */
+void MPU6050_Base::setDLPFMode(uint8_t mode) {
+ I2Cdev::writeBits(devAddr, MPU6050_RA_CONFIG, MPU6050_CFG_DLPF_CFG_BIT, MPU6050_CFG_DLPF_CFG_LENGTH, mode, wireObj);
+}
+
+// GYRO_CONFIG register
+
+/** Get full-scale gyroscope range.
+ * The FS_SEL parameter allows setting the full-scale range of the gyro sensors,
+ * as described in the table below.
+ *
+ *
+ * 0 = +/- 250 degrees/sec
+ * 1 = +/- 500 degrees/sec
+ * 2 = +/- 1000 degrees/sec
+ * 3 = +/- 2000 degrees/sec
+ *
+ *
+ * @return Current full-scale gyroscope range setting
+ * @see MPU6050_GYRO_FS_250
+ * @see MPU6050_RA_GYRO_CONFIG
+ * @see MPU6050_GCONFIG_FS_SEL_BIT
+ * @see MPU6050_GCONFIG_FS_SEL_LENGTH
+ */
+uint8_t MPU6050_Base::getFullScaleGyroRange() {
+ I2Cdev::readBits(devAddr, MPU6050_RA_GYRO_CONFIG, MPU6050_GCONFIG_FS_SEL_BIT, MPU6050_GCONFIG_FS_SEL_LENGTH, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set full-scale gyroscope range.
+ * @param range New full-scale gyroscope range value
+ * @see getFullScaleRange()
+ * @see MPU6050_GYRO_FS_250
+ * @see MPU6050_RA_GYRO_CONFIG
+ * @see MPU6050_GCONFIG_FS_SEL_BIT
+ * @see MPU6050_GCONFIG_FS_SEL_LENGTH
+ */
+void MPU6050_Base::setFullScaleGyroRange(uint8_t range) {
+ I2Cdev::writeBits(devAddr, MPU6050_RA_GYRO_CONFIG, MPU6050_GCONFIG_FS_SEL_BIT, MPU6050_GCONFIG_FS_SEL_LENGTH, range, wireObj);
+}
+
+// SELF TEST FACTORY TRIM VALUES
+
+/** Get self-test factory trim value for accelerometer X axis.
+ * @return factory trim value
+ * @see MPU6050_RA_SELF_TEST_X
+ */
+uint8_t MPU6050_Base::getAccelXSelfTestFactoryTrim() {
+ I2Cdev::readByte(devAddr, MPU6050_RA_SELF_TEST_X, &buffer[0], I2Cdev::readTimeout, wireObj);
+ I2Cdev::readByte(devAddr, MPU6050_RA_SELF_TEST_A, &buffer[1], I2Cdev::readTimeout, wireObj);
+ return (buffer[0]>>3) | ((buffer[1]>>4) & 0x03);
+}
+
+/** Get self-test factory trim value for accelerometer Y axis.
+ * @return factory trim value
+ * @see MPU6050_RA_SELF_TEST_Y
+ */
+uint8_t MPU6050_Base::getAccelYSelfTestFactoryTrim() {
+ I2Cdev::readByte(devAddr, MPU6050_RA_SELF_TEST_Y, &buffer[0], I2Cdev::readTimeout, wireObj);
+ I2Cdev::readByte(devAddr, MPU6050_RA_SELF_TEST_A, &buffer[1], I2Cdev::readTimeout, wireObj);
+ return (buffer[0]>>3) | ((buffer[1]>>2) & 0x03);
+}
+
+/** Get self-test factory trim value for accelerometer Z axis.
+ * @return factory trim value
+ * @see MPU6050_RA_SELF_TEST_Z
+ */
+uint8_t MPU6050_Base::getAccelZSelfTestFactoryTrim() {
+ I2Cdev::readBytes(devAddr, MPU6050_RA_SELF_TEST_Z, 2, buffer, I2Cdev::readTimeout, wireObj);
+ return (buffer[0]>>3) | (buffer[1] & 0x03);
+}
+
+/** Get self-test factory trim value for gyro X axis.
+ * @return factory trim value
+ * @see MPU6050_RA_SELF_TEST_X
+ */
+uint8_t MPU6050_Base::getGyroXSelfTestFactoryTrim() {
+ I2Cdev::readByte(devAddr, MPU6050_RA_SELF_TEST_X, buffer, I2Cdev::readTimeout, wireObj);
+ return (buffer[0] & 0x1F);
+}
+
+/** Get self-test factory trim value for gyro Y axis.
+ * @return factory trim value
+ * @see MPU6050_RA_SELF_TEST_Y
+ */
+uint8_t MPU6050_Base::getGyroYSelfTestFactoryTrim() {
+ I2Cdev::readByte(devAddr, MPU6050_RA_SELF_TEST_Y, buffer, I2Cdev::readTimeout, wireObj);
+ return (buffer[0] & 0x1F);
+}
+
+/** Get self-test factory trim value for gyro Z axis.
+ * @return factory trim value
+ * @see MPU6050_RA_SELF_TEST_Z
+ */
+uint8_t MPU6050_Base::getGyroZSelfTestFactoryTrim() {
+ I2Cdev::readByte(devAddr, MPU6050_RA_SELF_TEST_Z, buffer, I2Cdev::readTimeout, wireObj);
+ return (buffer[0] & 0x1F);
+}
+
+// ACCEL_CONFIG register
+
+/** Get self-test enabled setting for accelerometer X axis.
+ * @return Self-test enabled value
+ * @see MPU6050_RA_ACCEL_CONFIG
+ */
+bool MPU6050_Base::getAccelXSelfTest() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_XA_ST_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Get self-test enabled setting for accelerometer X axis.
+ * @param enabled Self-test enabled value
+ * @see MPU6050_RA_ACCEL_CONFIG
+ */
+void MPU6050_Base::setAccelXSelfTest(bool enabled) {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_XA_ST_BIT, enabled, wireObj);
+}
+/** Get self-test enabled value for accelerometer Y axis.
+ * @return Self-test enabled value
+ * @see MPU6050_RA_ACCEL_CONFIG
+ */
+bool MPU6050_Base::getAccelYSelfTest() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_YA_ST_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Get self-test enabled value for accelerometer Y axis.
+ * @param enabled Self-test enabled value
+ * @see MPU6050_RA_ACCEL_CONFIG
+ */
+void MPU6050_Base::setAccelYSelfTest(bool enabled) {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_YA_ST_BIT, enabled, wireObj);
+}
+/** Get self-test enabled value for accelerometer Z axis.
+ * @return Self-test enabled value
+ * @see MPU6050_RA_ACCEL_CONFIG
+ */
+bool MPU6050_Base::getAccelZSelfTest() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_ZA_ST_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set self-test enabled value for accelerometer Z axis.
+ * @param enabled Self-test enabled value
+ * @see MPU6050_RA_ACCEL_CONFIG
+ */
+void MPU6050_Base::setAccelZSelfTest(bool enabled) {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_ZA_ST_BIT, enabled, wireObj);
+}
+/** Get full-scale accelerometer range.
+ * The FS_SEL parameter allows setting the full-scale range of the accelerometer
+ * sensors, as described in the table below.
+ *
+ *
+ * 0 = +/- 2g
+ * 1 = +/- 4g
+ * 2 = +/- 8g
+ * 3 = +/- 16g
+ *
+ *
+ * @return Current full-scale accelerometer range setting
+ * @see MPU6050_ACCEL_FS_2
+ * @see MPU6050_RA_ACCEL_CONFIG
+ * @see MPU6050_ACONFIG_AFS_SEL_BIT
+ * @see MPU6050_ACONFIG_AFS_SEL_LENGTH
+ */
+uint8_t MPU6050_Base::getFullScaleAccelRange() {
+ I2Cdev::readBits(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_AFS_SEL_BIT, MPU6050_ACONFIG_AFS_SEL_LENGTH, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set full-scale accelerometer range.
+ * @param range New full-scale accelerometer range setting
+ * @see getFullScaleAccelRange()
+ */
+void MPU6050_Base::setFullScaleAccelRange(uint8_t range) {
+ I2Cdev::writeBits(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_AFS_SEL_BIT, MPU6050_ACONFIG_AFS_SEL_LENGTH, range, wireObj);
+}
+/** Get the high-pass filter configuration.
+ * The DHPF is a filter module in the path leading to motion detectors (Free
+ * Fall, Motion threshold, and Zero Motion). The high pass filter output is not
+ * available to the data registers (see Figure in Section 8 of the MPU-6000/
+ * MPU-6050 Product Specification document).
+ *
+ * The high pass filter has three modes:
+ *
+ *
+ * Reset: The filter output settles to zero within one sample. This
+ * effectively disables the high pass filter. This mode may be toggled
+ * to quickly settle the filter.
+ *
+ * On: The high pass filter will pass signals above the cut off frequency.
+ *
+ * Hold: When triggered, the filter holds the present sample. The filter
+ * output will be the difference between the input sample and the held
+ * sample.
+ *
+ *
+ *
+ * ACCEL_HPF | Filter Mode | Cut-off Frequency
+ * ----------+-------------+------------------
+ * 0 | Reset | None
+ * 1 | On | 5Hz
+ * 2 | On | 2.5Hz
+ * 3 | On | 1.25Hz
+ * 4 | On | 0.63Hz
+ * 7 | Hold | None
+ *
+ *
+ * @return Current high-pass filter configuration
+ * @see MPU6050_DHPF_RESET
+ * @see MPU6050_RA_ACCEL_CONFIG
+ */
+uint8_t MPU6050_Base::getDHPFMode() {
+ I2Cdev::readBits(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_ACCEL_HPF_BIT, MPU6050_ACONFIG_ACCEL_HPF_LENGTH, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set the high-pass filter configuration.
+ * @param bandwidth New high-pass filter configuration
+ * @see setDHPFMode()
+ * @see MPU6050_DHPF_RESET
+ * @see MPU6050_RA_ACCEL_CONFIG
+ */
+void MPU6050_Base::setDHPFMode(uint8_t bandwidth) {
+ I2Cdev::writeBits(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_ACCEL_HPF_BIT, MPU6050_ACONFIG_ACCEL_HPF_LENGTH, bandwidth, wireObj);
+}
+
+// FF_THR register
+
+/** Get free-fall event acceleration threshold.
+ * This register configures the detection threshold for Free Fall event
+ * detection. The unit of FF_THR is 1LSB = 2mg. Free Fall is detected when the
+ * absolute value of the accelerometer measurements for the three axes are each
+ * less than the detection threshold. This condition increments the Free Fall
+ * duration counter (Register 30). The Free Fall interrupt is triggered when the
+ * Free Fall duration counter reaches the time specified in FF_DUR.
+ *
+ * For more details on the Free Fall detection interrupt, see Section 8.2 of the
+ * MPU-6000/MPU-6050 Product Specification document as well as Registers 56 and
+ * 58 of this document.
+ *
+ * @return Current free-fall acceleration threshold value (LSB = 2mg)
+ * @see MPU6050_RA_FF_THR
+ */
+uint8_t MPU6050_Base::getFreefallDetectionThreshold() {
+ I2Cdev::readByte(devAddr, MPU6050_RA_FF_THR, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Get free-fall event acceleration threshold.
+ * @param threshold New free-fall acceleration threshold value (LSB = 2mg)
+ * @see getFreefallDetectionThreshold()
+ * @see MPU6050_RA_FF_THR
+ */
+void MPU6050_Base::setFreefallDetectionThreshold(uint8_t threshold) {
+ I2Cdev::writeByte(devAddr, MPU6050_RA_FF_THR, threshold, wireObj);
+}
+
+// FF_DUR register
+
+/** Get free-fall event duration threshold.
+ * This register configures the duration counter threshold for Free Fall event
+ * detection. The duration counter ticks at 1kHz, therefore FF_DUR has a unit
+ * of 1 LSB = 1 ms.
+ *
+ * The Free Fall duration counter increments while the absolute value of the
+ * accelerometer measurements are each less than the detection threshold
+ * (Register 29). The Free Fall interrupt is triggered when the Free Fall
+ * duration counter reaches the time specified in this register.
+ *
+ * For more details on the Free Fall detection interrupt, see Section 8.2 of
+ * the MPU-6000/MPU-6050 Product Specification document as well as Registers 56
+ * and 58 of this document.
+ *
+ * @return Current free-fall duration threshold value (LSB = 1ms)
+ * @see MPU6050_RA_FF_DUR
+ */
+uint8_t MPU6050_Base::getFreefallDetectionDuration() {
+ I2Cdev::readByte(devAddr, MPU6050_RA_FF_DUR, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Get free-fall event duration threshold.
+ * @param duration New free-fall duration threshold value (LSB = 1ms)
+ * @see getFreefallDetectionDuration()
+ * @see MPU6050_RA_FF_DUR
+ */
+void MPU6050_Base::setFreefallDetectionDuration(uint8_t duration) {
+ I2Cdev::writeByte(devAddr, MPU6050_RA_FF_DUR, duration, wireObj);
+}
+
+// MOT_THR register
+
+/** Get motion detection event acceleration threshold.
+ * This register configures the detection threshold for Motion interrupt
+ * generation. The unit of MOT_THR is 1LSB = 2mg. Motion is detected when the
+ * absolute value of any of the accelerometer measurements exceeds this Motion
+ * detection threshold. This condition increments the Motion detection duration
+ * counter (Register 32). The Motion detection interrupt is triggered when the
+ * Motion Detection counter reaches the time count specified in MOT_DUR
+ * (Register 32).
+ *
+ * The Motion interrupt will indicate the axis and polarity of detected motion
+ * in MOT_DETECT_STATUS (Register 97).
+ *
+ * For more details on the Motion detection interrupt, see Section 8.3 of the
+ * MPU-6000/MPU-6050 Product Specification document as well as Registers 56 and
+ * 58 of this document.
+ *
+ * @return Current motion detection acceleration threshold value (LSB = 2mg)
+ * @see MPU6050_RA_MOT_THR
+ */
+uint8_t MPU6050_Base::getMotionDetectionThreshold() {
+ I2Cdev::readByte(devAddr, MPU6050_RA_MOT_THR, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set motion detection event acceleration threshold.
+ * @param threshold New motion detection acceleration threshold value (LSB = 2mg)
+ * @see getMotionDetectionThreshold()
+ * @see MPU6050_RA_MOT_THR
+ */
+void MPU6050_Base::setMotionDetectionThreshold(uint8_t threshold) {
+ I2Cdev::writeByte(devAddr, MPU6050_RA_MOT_THR, threshold, wireObj);
+}
+
+// MOT_DUR register
+
+/** Get motion detection event duration threshold.
+ * This register configures the duration counter threshold for Motion interrupt
+ * generation. The duration counter ticks at 1 kHz, therefore MOT_DUR has a unit
+ * of 1LSB = 1ms. The Motion detection duration counter increments when the
+ * absolute value of any of the accelerometer measurements exceeds the Motion
+ * detection threshold (Register 31). The Motion detection interrupt is
+ * triggered when the Motion detection counter reaches the time count specified
+ * in this register.
+ *
+ * For more details on the Motion detection interrupt, see Section 8.3 of the
+ * MPU-6000/MPU-6050 Product Specification document.
+ *
+ * @return Current motion detection duration threshold value (LSB = 1ms)
+ * @see MPU6050_RA_MOT_DUR
+ */
+uint8_t MPU6050_Base::getMotionDetectionDuration() {
+ I2Cdev::readByte(devAddr, MPU6050_RA_MOT_DUR, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set motion detection event duration threshold.
+ * @param duration New motion detection duration threshold value (LSB = 1ms)
+ * @see getMotionDetectionDuration()
+ * @see MPU6050_RA_MOT_DUR
+ */
+void MPU6050_Base::setMotionDetectionDuration(uint8_t duration) {
+ I2Cdev::writeByte(devAddr, MPU6050_RA_MOT_DUR, duration, wireObj);
+}
+
+// ZRMOT_THR register
+
+/** Get zero motion detection event acceleration threshold.
+ * This register configures the detection threshold for Zero Motion interrupt
+ * generation. The unit of ZRMOT_THR is 1LSB = 2mg. Zero Motion is detected when
+ * the absolute value of the accelerometer measurements for the 3 axes are each
+ * less than the detection threshold. This condition increments the Zero Motion
+ * duration counter (Register 34). The Zero Motion interrupt is triggered when
+ * the Zero Motion duration counter reaches the time count specified in
+ * ZRMOT_DUR (Register 34).
+ *
+ * Unlike Free Fall or Motion detection, Zero Motion detection triggers an
+ * interrupt both when Zero Motion is first detected and when Zero Motion is no
+ * longer detected.
+ *
+ * When a zero motion event is detected, a Zero Motion Status will be indicated
+ * in the MOT_DETECT_STATUS register (Register 97). When a motion-to-zero-motion
+ * condition is detected, the status bit is set to 1. When a zero-motion-to-
+ * motion condition is detected, the status bit is set to 0.
+ *
+ * For more details on the Zero Motion detection interrupt, see Section 8.4 of
+ * the MPU-6000/MPU-6050 Product Specification document as well as Registers 56
+ * and 58 of this document.
+ *
+ * @return Current zero motion detection acceleration threshold value (LSB = 2mg)
+ * @see MPU6050_RA_ZRMOT_THR
+ */
+uint8_t MPU6050_Base::getZeroMotionDetectionThreshold() {
+ I2Cdev::readByte(devAddr, MPU6050_RA_ZRMOT_THR, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set zero motion detection event acceleration threshold.
+ * @param threshold New zero motion detection acceleration threshold value (LSB = 2mg)
+ * @see getZeroMotionDetectionThreshold()
+ * @see MPU6050_RA_ZRMOT_THR
+ */
+void MPU6050_Base::setZeroMotionDetectionThreshold(uint8_t threshold) {
+ I2Cdev::writeByte(devAddr, MPU6050_RA_ZRMOT_THR, threshold, wireObj);
+}
+
+// ZRMOT_DUR register
+
+/** Get zero motion detection event duration threshold.
+ * This register configures the duration counter threshold for Zero Motion
+ * interrupt generation. The duration counter ticks at 16 Hz, therefore
+ * ZRMOT_DUR has a unit of 1 LSB = 64 ms. The Zero Motion duration counter
+ * increments while the absolute value of the accelerometer measurements are
+ * each less than the detection threshold (Register 33). The Zero Motion
+ * interrupt is triggered when the Zero Motion duration counter reaches the time
+ * count specified in this register.
+ *
+ * For more details on the Zero Motion detection interrupt, see Section 8.4 of
+ * the MPU-6000/MPU-6050 Product Specification document, as well as Registers 56
+ * and 58 of this document.
+ *
+ * @return Current zero motion detection duration threshold value (LSB = 64ms)
+ * @see MPU6050_RA_ZRMOT_DUR
+ */
+uint8_t MPU6050_Base::getZeroMotionDetectionDuration() {
+ I2Cdev::readByte(devAddr, MPU6050_RA_ZRMOT_DUR, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set zero motion detection event duration threshold.
+ * @param duration New zero motion detection duration threshold value (LSB = 1ms)
+ * @see getZeroMotionDetectionDuration()
+ * @see MPU6050_RA_ZRMOT_DUR
+ */
+void MPU6050_Base::setZeroMotionDetectionDuration(uint8_t duration) {
+ I2Cdev::writeByte(devAddr, MPU6050_RA_ZRMOT_DUR, duration, wireObj);
+}
+
+// FIFO_EN register
+
+/** Get temperature FIFO enabled value.
+ * When set to 1, this bit enables TEMP_OUT_H and TEMP_OUT_L (Registers 65 and
+ * 66) to be written into the FIFO buffer.
+ * @return Current temperature FIFO enabled value
+ * @see MPU6050_RA_FIFO_EN
+ */
+bool MPU6050_Base::getTempFIFOEnabled() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_TEMP_FIFO_EN_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set temperature FIFO enabled value.
+ * @param enabled New temperature FIFO enabled value
+ * @see getTempFIFOEnabled()
+ * @see MPU6050_RA_FIFO_EN
+ */
+void MPU6050_Base::setTempFIFOEnabled(bool enabled) {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_TEMP_FIFO_EN_BIT, enabled, wireObj);
+}
+/** Get gyroscope X-axis FIFO enabled value.
+ * When set to 1, this bit enables GYRO_XOUT_H and GYRO_XOUT_L (Registers 67 and
+ * 68) to be written into the FIFO buffer.
+ * @return Current gyroscope X-axis FIFO enabled value
+ * @see MPU6050_RA_FIFO_EN
+ */
+bool MPU6050_Base::getXGyroFIFOEnabled() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_XG_FIFO_EN_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set gyroscope X-axis FIFO enabled value.
+ * @param enabled New gyroscope X-axis FIFO enabled value
+ * @see getXGyroFIFOEnabled()
+ * @see MPU6050_RA_FIFO_EN
+ */
+void MPU6050_Base::setXGyroFIFOEnabled(bool enabled) {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_XG_FIFO_EN_BIT, enabled, wireObj);
+}
+/** Get gyroscope Y-axis FIFO enabled value.
+ * When set to 1, this bit enables GYRO_YOUT_H and GYRO_YOUT_L (Registers 69 and
+ * 70) to be written into the FIFO buffer.
+ * @return Current gyroscope Y-axis FIFO enabled value
+ * @see MPU6050_RA_FIFO_EN
+ */
+bool MPU6050_Base::getYGyroFIFOEnabled() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_YG_FIFO_EN_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set gyroscope Y-axis FIFO enabled value.
+ * @param enabled New gyroscope Y-axis FIFO enabled value
+ * @see getYGyroFIFOEnabled()
+ * @see MPU6050_RA_FIFO_EN
+ */
+void MPU6050_Base::setYGyroFIFOEnabled(bool enabled) {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_YG_FIFO_EN_BIT, enabled, wireObj);
+}
+/** Get gyroscope Z-axis FIFO enabled value.
+ * When set to 1, this bit enables GYRO_ZOUT_H and GYRO_ZOUT_L (Registers 71 and
+ * 72) to be written into the FIFO buffer.
+ * @return Current gyroscope Z-axis FIFO enabled value
+ * @see MPU6050_RA_FIFO_EN
+ */
+bool MPU6050_Base::getZGyroFIFOEnabled() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_ZG_FIFO_EN_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set gyroscope Z-axis FIFO enabled value.
+ * @param enabled New gyroscope Z-axis FIFO enabled value
+ * @see getZGyroFIFOEnabled()
+ * @see MPU6050_RA_FIFO_EN
+ */
+void MPU6050_Base::setZGyroFIFOEnabled(bool enabled) {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_ZG_FIFO_EN_BIT, enabled, wireObj);
+}
+/** Get accelerometer FIFO enabled value.
+ * When set to 1, this bit enables ACCEL_XOUT_H, ACCEL_XOUT_L, ACCEL_YOUT_H,
+ * ACCEL_YOUT_L, ACCEL_ZOUT_H, and ACCEL_ZOUT_L (Registers 59 to 64) to be
+ * written into the FIFO buffer.
+ * @return Current accelerometer FIFO enabled value
+ * @see MPU6050_RA_FIFO_EN
+ */
+bool MPU6050_Base::getAccelFIFOEnabled() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_ACCEL_FIFO_EN_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set accelerometer FIFO enabled value.
+ * @param enabled New accelerometer FIFO enabled value
+ * @see getAccelFIFOEnabled()
+ * @see MPU6050_RA_FIFO_EN
+ */
+void MPU6050_Base::setAccelFIFOEnabled(bool enabled) {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_ACCEL_FIFO_EN_BIT, enabled, wireObj);
+}
+/** Get Slave 2 FIFO enabled value.
+ * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96)
+ * associated with Slave 2 to be written into the FIFO buffer.
+ * @return Current Slave 2 FIFO enabled value
+ * @see MPU6050_RA_FIFO_EN
+ */
+bool MPU6050_Base::getSlave2FIFOEnabled() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV2_FIFO_EN_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set Slave 2 FIFO enabled value.
+ * @param enabled New Slave 2 FIFO enabled value
+ * @see getSlave2FIFOEnabled()
+ * @see MPU6050_RA_FIFO_EN
+ */
+void MPU6050_Base::setSlave2FIFOEnabled(bool enabled) {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV2_FIFO_EN_BIT, enabled, wireObj);
+}
+/** Get Slave 1 FIFO enabled value.
+ * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96)
+ * associated with Slave 1 to be written into the FIFO buffer.
+ * @return Current Slave 1 FIFO enabled value
+ * @see MPU6050_RA_FIFO_EN
+ */
+bool MPU6050_Base::getSlave1FIFOEnabled() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV1_FIFO_EN_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set Slave 1 FIFO enabled value.
+ * @param enabled New Slave 1 FIFO enabled value
+ * @see getSlave1FIFOEnabled()
+ * @see MPU6050_RA_FIFO_EN
+ */
+void MPU6050_Base::setSlave1FIFOEnabled(bool enabled) {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV1_FIFO_EN_BIT, enabled, wireObj);
+}
+/** Get Slave 0 FIFO enabled value.
+ * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96)
+ * associated with Slave 0 to be written into the FIFO buffer.
+ * @return Current Slave 0 FIFO enabled value
+ * @see MPU6050_RA_FIFO_EN
+ */
+bool MPU6050_Base::getSlave0FIFOEnabled() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV0_FIFO_EN_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set Slave 0 FIFO enabled value.
+ * @param enabled New Slave 0 FIFO enabled value
+ * @see getSlave0FIFOEnabled()
+ * @see MPU6050_RA_FIFO_EN
+ */
+void MPU6050_Base::setSlave0FIFOEnabled(bool enabled) {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV0_FIFO_EN_BIT, enabled, wireObj);
+}
+
+// I2C_MST_CTRL register
+
+/** Get multi-master enabled value.
+ * Multi-master capability allows multiple I2C masters to operate on the same
+ * bus. In circuits where multi-master capability is required, set MULT_MST_EN
+ * to 1. This will increase current drawn by approximately 30uA.
+ *
+ * In circuits where multi-master capability is required, the state of the I2C
+ * bus must always be monitored by each separate I2C Master. Before an I2C
+ * Master can assume arbitration of the bus, it must first confirm that no other
+ * I2C Master has arbitration of the bus. When MULT_MST_EN is set to 1, the
+ * MPU-60X0's bus arbitration detection logic is turned on, enabling it to
+ * detect when the bus is available.
+ *
+ * @return Current multi-master enabled value
+ * @see MPU6050_RA_I2C_MST_CTRL
+ */
+bool MPU6050_Base::getMultiMasterEnabled() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_MULT_MST_EN_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set multi-master enabled value.
+ * @param enabled New multi-master enabled value
+ * @see getMultiMasterEnabled()
+ * @see MPU6050_RA_I2C_MST_CTRL
+ */
+void MPU6050_Base::setMultiMasterEnabled(bool enabled) {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_MULT_MST_EN_BIT, enabled, wireObj);
+}
+/** Get wait-for-external-sensor-data enabled value.
+ * When the WAIT_FOR_ES bit is set to 1, the Data Ready interrupt will be
+ * delayed until External Sensor data from the Slave Devices are loaded into the
+ * EXT_SENS_DATA registers. This is used to ensure that both the internal sensor
+ * data (i.e. from gyro and accel) and external sensor data have been loaded to
+ * their respective data registers (i.e. the data is synced) when the Data Ready
+ * interrupt is triggered.
+ *
+ * @return Current wait-for-external-sensor-data enabled value
+ * @see MPU6050_RA_I2C_MST_CTRL
+ */
+bool MPU6050_Base::getWaitForExternalSensorEnabled() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_WAIT_FOR_ES_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set wait-for-external-sensor-data enabled value.
+ * @param enabled New wait-for-external-sensor-data enabled value
+ * @see getWaitForExternalSensorEnabled()
+ * @see MPU6050_RA_I2C_MST_CTRL
+ */
+void MPU6050_Base::setWaitForExternalSensorEnabled(bool enabled) {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_WAIT_FOR_ES_BIT, enabled, wireObj);
+}
+/** Get Slave 3 FIFO enabled value.
+ * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96)
+ * associated with Slave 3 to be written into the FIFO buffer.
+ * @return Current Slave 3 FIFO enabled value
+ * @see MPU6050_RA_MST_CTRL
+ */
+bool MPU6050_Base::getSlave3FIFOEnabled() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_SLV_3_FIFO_EN_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set Slave 3 FIFO enabled value.
+ * @param enabled New Slave 3 FIFO enabled value
+ * @see getSlave3FIFOEnabled()
+ * @see MPU6050_RA_MST_CTRL
+ */
+void MPU6050_Base::setSlave3FIFOEnabled(bool enabled) {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_SLV_3_FIFO_EN_BIT, enabled, wireObj);
+}
+/** Get slave read/write transition enabled value.
+ * The I2C_MST_P_NSR bit configures the I2C Master's transition from one slave
+ * read to the next slave read. If the bit equals 0, there will be a restart
+ * between reads. If the bit equals 1, there will be a stop followed by a start
+ * of the following read. When a write transaction follows a read transaction,
+ * the stop followed by a start of the successive write will be always used.
+ *
+ * @return Current slave read/write transition enabled value
+ * @see MPU6050_RA_I2C_MST_CTRL
+ */
+bool MPU6050_Base::getSlaveReadWriteTransitionEnabled() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_I2C_MST_P_NSR_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set slave read/write transition enabled value.
+ * @param enabled New slave read/write transition enabled value
+ * @see getSlaveReadWriteTransitionEnabled()
+ * @see MPU6050_RA_I2C_MST_CTRL
+ */
+void MPU6050_Base::setSlaveReadWriteTransitionEnabled(bool enabled) {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_I2C_MST_P_NSR_BIT, enabled, wireObj);
+}
+/** Get I2C master clock speed.
+ * I2C_MST_CLK is a 4 bit unsigned value which configures a divider on the
+ * MPU-60X0 internal 8MHz clock. It sets the I2C master clock speed according to
+ * the following table:
+ *
+ *
+ * I2C_MST_CLK | I2C Master Clock Speed | 8MHz Clock Divider
+ * ------------+------------------------+-------------------
+ * 0 | 348kHz | 23
+ * 1 | 333kHz | 24
+ * 2 | 320kHz | 25
+ * 3 | 308kHz | 26
+ * 4 | 296kHz | 27
+ * 5 | 286kHz | 28
+ * 6 | 276kHz | 29
+ * 7 | 267kHz | 30
+ * 8 | 258kHz | 31
+ * 9 | 500kHz | 16
+ * 10 | 471kHz | 17
+ * 11 | 444kHz | 18
+ * 12 | 421kHz | 19
+ * 13 | 400kHz | 20
+ * 14 | 381kHz | 21
+ * 15 | 364kHz | 22
+ *
+ *
+ * @return Current I2C master clock speed
+ * @see MPU6050_RA_I2C_MST_CTRL
+ */
+uint8_t MPU6050_Base::getMasterClockSpeed() {
+ I2Cdev::readBits(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_I2C_MST_CLK_BIT, MPU6050_I2C_MST_CLK_LENGTH, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set I2C master clock speed.
+ * @reparam speed Current I2C master clock speed
+ * @see MPU6050_RA_I2C_MST_CTRL
+ */
+void MPU6050_Base::setMasterClockSpeed(uint8_t speed) {
+ I2Cdev::writeBits(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_I2C_MST_CLK_BIT, MPU6050_I2C_MST_CLK_LENGTH, speed, wireObj);
+}
+
+// I2C_SLV* registers (Slave 0-3)
+
+/** Get the I2C address of the specified slave (0-3).
+ * Note that Bit 7 (MSB) controls read/write mode. If Bit 7 is set, it's a read
+ * operation, and if it is cleared, then it's a write operation. The remaining
+ * bits (6-0) are the 7-bit device address of the slave device.
+ *
+ * In read mode, the result of the read is placed in the lowest available
+ * EXT_SENS_DATA register. For further information regarding the allocation of
+ * read results, please refer to the EXT_SENS_DATA register description
+ * (Registers 73 - 96).
+ *
+ * The MPU-6050 supports a total of five slaves, but Slave 4 has unique
+ * characteristics, and so it has its own functions (getSlave4* and setSlave4*).
+ *
+ * I2C data transactions are performed at the Sample Rate, as defined in
+ * Register 25. The user is responsible for ensuring that I2C data transactions
+ * to and from each enabled Slave can be completed within a single period of the
+ * Sample Rate.
+ *
+ * The I2C slave access rate can be reduced relative to the Sample Rate. This
+ * reduced access rate is determined by I2C_MST_DLY (Register 52). Whether a
+ * slave's access rate is reduced relative to the Sample Rate is determined by
+ * I2C_MST_DELAY_CTRL (Register 103).
+ *
+ * The processing order for the slaves is fixed. The sequence followed for
+ * processing the slaves is Slave 0, Slave 1, Slave 2, Slave 3 and Slave 4. If a
+ * particular Slave is disabled it will be skipped.
+ *
+ * Each slave can either be accessed at the sample rate or at a reduced sample
+ * rate. In a case where some slaves are accessed at the Sample Rate and some
+ * slaves are accessed at the reduced rate, the sequence of accessing the slaves
+ * (Slave 0 to Slave 4) is still followed. However, the reduced rate slaves will
+ * be skipped if their access rate dictates that they should not be accessed
+ * during that particular cycle. For further information regarding the reduced
+ * access rate, please refer to Register 52. Whether a slave is accessed at the
+ * Sample Rate or at the reduced rate is determined by the Delay Enable bits in
+ * Register 103.
+ *
+ * @param num Slave number (0-3)
+ * @return Current address for specified slave
+ * @see MPU6050_RA_I2C_SLV0_ADDR
+ */
+uint8_t MPU6050_Base::getSlaveAddress(uint8_t num) {
+ if (num > 3) return 0;
+ I2Cdev::readByte(devAddr, MPU6050_RA_I2C_SLV0_ADDR + num*3, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set the I2C address of the specified slave (0-3).
+ * @param num Slave number (0-3)
+ * @param address New address for specified slave
+ * @see getSlaveAddress()
+ * @see MPU6050_RA_I2C_SLV0_ADDR
+ */
+void MPU6050_Base::setSlaveAddress(uint8_t num, uint8_t address) {
+ if (num > 3) return;
+ I2Cdev::writeByte(devAddr, MPU6050_RA_I2C_SLV0_ADDR + num*3, address, wireObj);
+}
+/** Get the active internal register for the specified slave (0-3).
+ * Read/write operations for this slave will be done to whatever internal
+ * register address is stored in this MPU register.
+ *
+ * The MPU-6050 supports a total of five slaves, but Slave 4 has unique
+ * characteristics, and so it has its own functions.
+ *
+ * @param num Slave number (0-3)
+ * @return Current active register for specified slave
+ * @see MPU6050_RA_I2C_SLV0_REG
+ */
+uint8_t MPU6050_Base::getSlaveRegister(uint8_t num) {
+ if (num > 3) return 0;
+ I2Cdev::readByte(devAddr, MPU6050_RA_I2C_SLV0_REG + num*3, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set the active internal register for the specified slave (0-3).
+ * @param num Slave number (0-3)
+ * @param reg New active register for specified slave
+ * @see getSlaveRegister()
+ * @see MPU6050_RA_I2C_SLV0_REG
+ */
+void MPU6050_Base::setSlaveRegister(uint8_t num, uint8_t reg) {
+ if (num > 3) return;
+ I2Cdev::writeByte(devAddr, MPU6050_RA_I2C_SLV0_REG + num*3, reg, wireObj);
+}
+/** Get the enabled value for the specified slave (0-3).
+ * When set to 1, this bit enables Slave 0 for data transfer operations. When
+ * cleared to 0, this bit disables Slave 0 from data transfer operations.
+ * @param num Slave number (0-3)
+ * @return Current enabled value for specified slave
+ * @see MPU6050_RA_I2C_SLV0_CTRL
+ */
+bool MPU6050_Base::getSlaveEnabled(uint8_t num) {
+ if (num > 3) return 0;
+ I2Cdev::readBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_EN_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set the enabled value for the specified slave (0-3).
+ * @param num Slave number (0-3)
+ * @param enabled New enabled value for specified slave
+ * @see getSlaveEnabled()
+ * @see MPU6050_RA_I2C_SLV0_CTRL
+ */
+void MPU6050_Base::setSlaveEnabled(uint8_t num, bool enabled) {
+ if (num > 3) return;
+ I2Cdev::writeBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_EN_BIT, enabled, wireObj);
+}
+/** Get word pair byte-swapping enabled for the specified slave (0-3).
+ * When set to 1, this bit enables byte swapping. When byte swapping is enabled,
+ * the high and low bytes of a word pair are swapped. Please refer to
+ * I2C_SLV0_GRP for the pairing convention of the word pairs. When cleared to 0,
+ * bytes transferred to and from Slave 0 will be written to EXT_SENS_DATA
+ * registers in the order they were transferred.
+ *
+ * @param num Slave number (0-3)
+ * @return Current word pair byte-swapping enabled value for specified slave
+ * @see MPU6050_RA_I2C_SLV0_CTRL
+ */
+bool MPU6050_Base::getSlaveWordByteSwap(uint8_t num) {
+ if (num > 3) return 0;
+ I2Cdev::readBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_BYTE_SW_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set word pair byte-swapping enabled for the specified slave (0-3).
+ * @param num Slave number (0-3)
+ * @param enabled New word pair byte-swapping enabled value for specified slave
+ * @see getSlaveWordByteSwap()
+ * @see MPU6050_RA_I2C_SLV0_CTRL
+ */
+void MPU6050_Base::setSlaveWordByteSwap(uint8_t num, bool enabled) {
+ if (num > 3) return;
+ I2Cdev::writeBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_BYTE_SW_BIT, enabled, wireObj);
+}
+/** Get write mode for the specified slave (0-3).
+ * When set to 1, the transaction will read or write data only. When cleared to
+ * 0, the transaction will write a register address prior to reading or writing
+ * data. This should equal 0 when specifying the register address within the
+ * Slave device to/from which the ensuing data transaction will take place.
+ *
+ * @param num Slave number (0-3)
+ * @return Current write mode for specified slave (0 = register address + data, 1 = data only)
+ * @see MPU6050_RA_I2C_SLV0_CTRL
+ */
+bool MPU6050_Base::getSlaveWriteMode(uint8_t num) {
+ if (num > 3) return 0;
+ I2Cdev::readBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_REG_DIS_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set write mode for the specified slave (0-3).
+ * @param num Slave number (0-3)
+ * @param mode New write mode for specified slave (0 = register address + data, 1 = data only)
+ * @see getSlaveWriteMode()
+ * @see MPU6050_RA_I2C_SLV0_CTRL
+ */
+void MPU6050_Base::setSlaveWriteMode(uint8_t num, bool mode) {
+ if (num > 3) return;
+ I2Cdev::writeBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_REG_DIS_BIT, mode, wireObj);
+}
+/** Get word pair grouping order offset for the specified slave (0-3).
+ * This sets specifies the grouping order of word pairs received from registers.
+ * When cleared to 0, bytes from register addresses 0 and 1, 2 and 3, etc (even,
+ * then odd register addresses) are paired to form a word. When set to 1, bytes
+ * from register addresses are paired 1 and 2, 3 and 4, etc. (odd, then even
+ * register addresses) are paired to form a word.
+ *
+ * @param num Slave number (0-3)
+ * @return Current word pair grouping order offset for specified slave
+ * @see MPU6050_RA_I2C_SLV0_CTRL
+ */
+bool MPU6050_Base::getSlaveWordGroupOffset(uint8_t num) {
+ if (num > 3) return 0;
+ I2Cdev::readBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_GRP_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set word pair grouping order offset for the specified slave (0-3).
+ * @param num Slave number (0-3)
+ * @param enabled New word pair grouping order offset for specified slave
+ * @see getSlaveWordGroupOffset()
+ * @see MPU6050_RA_I2C_SLV0_CTRL
+ */
+void MPU6050_Base::setSlaveWordGroupOffset(uint8_t num, bool enabled) {
+ if (num > 3) return;
+ I2Cdev::writeBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_GRP_BIT, enabled, wireObj);
+}
+/** Get number of bytes to read for the specified slave (0-3).
+ * Specifies the number of bytes transferred to and from Slave 0. Clearing this
+ * bit to 0 is equivalent to disabling the register by writing 0 to I2C_SLV0_EN.
+ * @param num Slave number (0-3)
+ * @return Number of bytes to read for specified slave
+ * @see MPU6050_RA_I2C_SLV0_CTRL
+ */
+uint8_t MPU6050_Base::getSlaveDataLength(uint8_t num) {
+ if (num > 3) return 0;
+ I2Cdev::readBits(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_LEN_BIT, MPU6050_I2C_SLV_LEN_LENGTH, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set number of bytes to read for the specified slave (0-3).
+ * @param num Slave number (0-3)
+ * @param length Number of bytes to read for specified slave
+ * @see getSlaveDataLength()
+ * @see MPU6050_RA_I2C_SLV0_CTRL
+ */
+void MPU6050_Base::setSlaveDataLength(uint8_t num, uint8_t length) {
+ if (num > 3) return;
+ I2Cdev::writeBits(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_LEN_BIT, MPU6050_I2C_SLV_LEN_LENGTH, length, wireObj);
+}
+
+// I2C_SLV* registers (Slave 4)
+
+/** Get the I2C address of Slave 4.
+ * Note that Bit 7 (MSB) controls read/write mode. If Bit 7 is set, it's a read
+ * operation, and if it is cleared, then it's a write operation. The remaining
+ * bits (6-0) are the 7-bit device address of the slave device.
+ *
+ * @return Current address for Slave 4
+ * @see getSlaveAddress()
+ * @see MPU6050_RA_I2C_SLV4_ADDR
+ */
+uint8_t MPU6050_Base::getSlave4Address() {
+ I2Cdev::readByte(devAddr, MPU6050_RA_I2C_SLV4_ADDR, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set the I2C address of Slave 4.
+ * @param address New address for Slave 4
+ * @see getSlave4Address()
+ * @see MPU6050_RA_I2C_SLV4_ADDR
+ */
+void MPU6050_Base::setSlave4Address(uint8_t address) {
+ I2Cdev::writeByte(devAddr, MPU6050_RA_I2C_SLV4_ADDR, address, wireObj);
+}
+/** Get the active internal register for the Slave 4.
+ * Read/write operations for this slave will be done to whatever internal
+ * register address is stored in this MPU register.
+ *
+ * @return Current active register for Slave 4
+ * @see MPU6050_RA_I2C_SLV4_REG
+ */
+uint8_t MPU6050_Base::getSlave4Register() {
+ I2Cdev::readByte(devAddr, MPU6050_RA_I2C_SLV4_REG, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set the active internal register for Slave 4.
+ * @param reg New active register for Slave 4
+ * @see getSlave4Register()
+ * @see MPU6050_RA_I2C_SLV4_REG
+ */
+void MPU6050_Base::setSlave4Register(uint8_t reg) {
+ I2Cdev::writeByte(devAddr, MPU6050_RA_I2C_SLV4_REG, reg, wireObj);
+}
+/** Set new byte to write to Slave 4.
+ * This register stores the data to be written into the Slave 4. If I2C_SLV4_RW
+ * is set 1 (set to read), this register has no effect.
+ * @param data New byte to write to Slave 4
+ * @see MPU6050_RA_I2C_SLV4_DO
+ */
+void MPU6050_Base::setSlave4OutputByte(uint8_t data) {
+ I2Cdev::writeByte(devAddr, MPU6050_RA_I2C_SLV4_DO, data, wireObj);
+}
+/** Get the enabled value for the Slave 4.
+ * When set to 1, this bit enables Slave 4 for data transfer operations. When
+ * cleared to 0, this bit disables Slave 4 from data transfer operations.
+ * @return Current enabled value for Slave 4
+ * @see MPU6050_RA_I2C_SLV4_CTRL
+ */
+bool MPU6050_Base::getSlave4Enabled() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_EN_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set the enabled value for Slave 4.
+ * @param enabled New enabled value for Slave 4
+ * @see getSlave4Enabled()
+ * @see MPU6050_RA_I2C_SLV4_CTRL
+ */
+void MPU6050_Base::setSlave4Enabled(bool enabled) {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_EN_BIT, enabled, wireObj);
+}
+/** Get the enabled value for Slave 4 transaction interrupts.
+ * When set to 1, this bit enables the generation of an interrupt signal upon
+ * completion of a Slave 4 transaction. When cleared to 0, this bit disables the
+ * generation of an interrupt signal upon completion of a Slave 4 transaction.
+ * The interrupt status can be observed in Register 54.
+ *
+ * @return Current enabled value for Slave 4 transaction interrupts.
+ * @see MPU6050_RA_I2C_SLV4_CTRL
+ */
+bool MPU6050_Base::getSlave4InterruptEnabled() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_INT_EN_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set the enabled value for Slave 4 transaction interrupts.
+ * @param enabled New enabled value for Slave 4 transaction interrupts.
+ * @see getSlave4InterruptEnabled()
+ * @see MPU6050_RA_I2C_SLV4_CTRL
+ */
+void MPU6050_Base::setSlave4InterruptEnabled(bool enabled) {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_INT_EN_BIT, enabled, wireObj);
+}
+/** Get write mode for Slave 4.
+ * When set to 1, the transaction will read or write data only. When cleared to
+ * 0, the transaction will write a register address prior to reading or writing
+ * data. This should equal 0 when specifying the register address within the
+ * Slave device to/from which the ensuing data transaction will take place.
+ *
+ * @return Current write mode for Slave 4 (0 = register address + data, 1 = data only)
+ * @see MPU6050_RA_I2C_SLV4_CTRL
+ */
+bool MPU6050_Base::getSlave4WriteMode() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_REG_DIS_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set write mode for the Slave 4.
+ * @param mode New write mode for Slave 4 (0 = register address + data, 1 = data only)
+ * @see getSlave4WriteMode()
+ * @see MPU6050_RA_I2C_SLV4_CTRL
+ */
+void MPU6050_Base::setSlave4WriteMode(bool mode) {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_REG_DIS_BIT, mode, wireObj);
+}
+/** Get Slave 4 master delay value.
+ * This configures the reduced access rate of I2C slaves relative to the Sample
+ * Rate. When a slave's access rate is decreased relative to the Sample Rate,
+ * the slave is accessed every:
+ *
+ * 1 / (1 + I2C_MST_DLY) samples
+ *
+ * This base Sample Rate in turn is determined by SMPLRT_DIV (register 25) and
+ * DLPF_CFG (register 26). Whether a slave's access rate is reduced relative to
+ * the Sample Rate is determined by I2C_MST_DELAY_CTRL (register 103). For
+ * further information regarding the Sample Rate, please refer to register 25.
+ *
+ * @return Current Slave 4 master delay value
+ * @see MPU6050_RA_I2C_SLV4_CTRL
+ */
+uint8_t MPU6050_Base::getSlave4MasterDelay() {
+ I2Cdev::readBits(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_MST_DLY_BIT, MPU6050_I2C_SLV4_MST_DLY_LENGTH, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set Slave 4 master delay value.
+ * @param delay New Slave 4 master delay value
+ * @see getSlave4MasterDelay()
+ * @see MPU6050_RA_I2C_SLV4_CTRL
+ */
+void MPU6050_Base::setSlave4MasterDelay(uint8_t delay) {
+ I2Cdev::writeBits(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_MST_DLY_BIT, MPU6050_I2C_SLV4_MST_DLY_LENGTH, delay, wireObj);
+}
+/** Get last available byte read from Slave 4.
+ * This register stores the data read from Slave 4. This field is populated
+ * after a read transaction.
+ * @return Last available byte read from to Slave 4
+ * @see MPU6050_RA_I2C_SLV4_DI
+ */
+uint8_t MPU6050_Base::getSlate4InputByte() {
+ I2Cdev::readByte(devAddr, MPU6050_RA_I2C_SLV4_DI, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+
+// I2C_MST_STATUS register
+
+/** Get FSYNC interrupt status.
+ * This bit reflects the status of the FSYNC interrupt from an external device
+ * into the MPU-60X0. This is used as a way to pass an external interrupt
+ * through the MPU-60X0 to the host application processor. When set to 1, this
+ * bit will cause an interrupt if FSYNC_INT_EN is asserted in INT_PIN_CFG
+ * (Register 55).
+ * @return FSYNC interrupt status
+ * @see MPU6050_RA_I2C_MST_STATUS
+ */
+bool MPU6050_Base::getPassthroughStatus() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_PASS_THROUGH_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Get Slave 4 transaction done status.
+ * Automatically sets to 1 when a Slave 4 transaction has completed. This
+ * triggers an interrupt if the I2C_MST_INT_EN bit in the INT_ENABLE register
+ * (Register 56) is asserted and if the SLV_4_DONE_INT bit is asserted in the
+ * I2C_SLV4_CTRL register (Register 52).
+ * @return Slave 4 transaction done status
+ * @see MPU6050_RA_I2C_MST_STATUS
+ */
+bool MPU6050_Base::getSlave4IsDone() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV4_DONE_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Get master arbitration lost status.
+ * This bit automatically sets to 1 when the I2C Master has lost arbitration of
+ * the auxiliary I2C bus (an error condition). This triggers an interrupt if the
+ * I2C_MST_INT_EN bit in the INT_ENABLE register (Register 56) is asserted.
+ * @return Master arbitration lost status
+ * @see MPU6050_RA_I2C_MST_STATUS
+ */
+bool MPU6050_Base::getLostArbitration() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_LOST_ARB_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Get Slave 4 NACK status.
+ * This bit automatically sets to 1 when the I2C Master receives a NACK in a
+ * transaction with Slave 4. This triggers an interrupt if the I2C_MST_INT_EN
+ * bit in the INT_ENABLE register (Register 56) is asserted.
+ * @return Slave 4 NACK interrupt status
+ * @see MPU6050_RA_I2C_MST_STATUS
+ */
+bool MPU6050_Base::getSlave4Nack() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV4_NACK_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Get Slave 3 NACK status.
+ * This bit automatically sets to 1 when the I2C Master receives a NACK in a
+ * transaction with Slave 3. This triggers an interrupt if the I2C_MST_INT_EN
+ * bit in the INT_ENABLE register (Register 56) is asserted.
+ * @return Slave 3 NACK interrupt status
+ * @see MPU6050_RA_I2C_MST_STATUS
+ */
+bool MPU6050_Base::getSlave3Nack() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV3_NACK_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Get Slave 2 NACK status.
+ * This bit automatically sets to 1 when the I2C Master receives a NACK in a
+ * transaction with Slave 2. This triggers an interrupt if the I2C_MST_INT_EN
+ * bit in the INT_ENABLE register (Register 56) is asserted.
+ * @return Slave 2 NACK interrupt status
+ * @see MPU6050_RA_I2C_MST_STATUS
+ */
+bool MPU6050_Base::getSlave2Nack() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV2_NACK_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Get Slave 1 NACK status.
+ * This bit automatically sets to 1 when the I2C Master receives a NACK in a
+ * transaction with Slave 1. This triggers an interrupt if the I2C_MST_INT_EN
+ * bit in the INT_ENABLE register (Register 56) is asserted.
+ * @return Slave 1 NACK interrupt status
+ * @see MPU6050_RA_I2C_MST_STATUS
+ */
+bool MPU6050_Base::getSlave1Nack() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV1_NACK_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Get Slave 0 NACK status.
+ * This bit automatically sets to 1 when the I2C Master receives a NACK in a
+ * transaction with Slave 0. This triggers an interrupt if the I2C_MST_INT_EN
+ * bit in the INT_ENABLE register (Register 56) is asserted.
+ * @return Slave 0 NACK interrupt status
+ * @see MPU6050_RA_I2C_MST_STATUS
+ */
+bool MPU6050_Base::getSlave0Nack() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV0_NACK_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+
+// INT_PIN_CFG register
+
+/** Get interrupt logic level mode.
+ * Will be set 0 for active-high, 1 for active-low.
+ * @return Current interrupt mode (0=active-high, 1=active-low)
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_INT_LEVEL_BIT
+ */
+bool MPU6050_Base::getInterruptMode() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_LEVEL_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set interrupt logic level mode.
+ * @param mode New interrupt mode (0=active-high, 1=active-low)
+ * @see getInterruptMode()
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_INT_LEVEL_BIT
+ */
+void MPU6050_Base::setInterruptMode(bool mode) {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_LEVEL_BIT, mode, wireObj);
+}
+/** Get interrupt drive mode.
+ * Will be set 0 for push-pull, 1 for open-drain.
+ * @return Current interrupt drive mode (0=push-pull, 1=open-drain)
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_INT_OPEN_BIT
+ */
+bool MPU6050_Base::getInterruptDrive() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_OPEN_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set interrupt drive mode.
+ * @param drive New interrupt drive mode (0=push-pull, 1=open-drain)
+ * @see getInterruptDrive()
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_INT_OPEN_BIT
+ */
+void MPU6050_Base::setInterruptDrive(bool drive) {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_OPEN_BIT, drive, wireObj);
+}
+/** Get interrupt latch mode.
+ * Will be set 0 for 50us-pulse, 1 for latch-until-int-cleared.
+ * @return Current latch mode (0=50us-pulse, 1=latch-until-int-cleared)
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_LATCH_INT_EN_BIT
+ */
+bool MPU6050_Base::getInterruptLatch() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_LATCH_INT_EN_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set interrupt latch mode.
+ * @param latch New latch mode (0=50us-pulse, 1=latch-until-int-cleared)
+ * @see getInterruptLatch()
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_LATCH_INT_EN_BIT
+ */
+void MPU6050_Base::setInterruptLatch(bool latch) {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_LATCH_INT_EN_BIT, latch, wireObj);
+}
+/** Get interrupt latch clear mode.
+ * Will be set 0 for status-read-only, 1 for any-register-read.
+ * @return Current latch clear mode (0=status-read-only, 1=any-register-read)
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_INT_RD_CLEAR_BIT
+ */
+bool MPU6050_Base::getInterruptLatchClear() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_RD_CLEAR_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set interrupt latch clear mode.
+ * @param clear New latch clear mode (0=status-read-only, 1=any-register-read)
+ * @see getInterruptLatchClear()
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_INT_RD_CLEAR_BIT
+ */
+void MPU6050_Base::setInterruptLatchClear(bool clear) {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_RD_CLEAR_BIT, clear, wireObj);
+}
+/** Get FSYNC interrupt logic level mode.
+ * @return Current FSYNC interrupt mode (0=active-high, 1=active-low)
+ * @see getFSyncInterruptMode()
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_FSYNC_INT_LEVEL_BIT
+ */
+bool MPU6050_Base::getFSyncInterruptLevel() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_FSYNC_INT_LEVEL_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set FSYNC interrupt logic level mode.
+ * @param mode New FSYNC interrupt mode (0=active-high, 1=active-low)
+ * @see getFSyncInterruptMode()
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_FSYNC_INT_LEVEL_BIT
+ */
+void MPU6050_Base::setFSyncInterruptLevel(bool level) {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_FSYNC_INT_LEVEL_BIT, level, wireObj);
+}
+/** Get FSYNC pin interrupt enabled setting.
+ * Will be set 0 for disabled, 1 for enabled.
+ * @return Current interrupt enabled setting
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_FSYNC_INT_EN_BIT
+ */
+bool MPU6050_Base::getFSyncInterruptEnabled() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_FSYNC_INT_EN_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set FSYNC pin interrupt enabled setting.
+ * @param enabled New FSYNC pin interrupt enabled setting
+ * @see getFSyncInterruptEnabled()
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_FSYNC_INT_EN_BIT
+ */
+void MPU6050_Base::setFSyncInterruptEnabled(bool enabled) {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_FSYNC_INT_EN_BIT, enabled, wireObj);
+}
+/** Get I2C bypass enabled status.
+ * When this bit is equal to 1 and I2C_MST_EN (Register 106 bit[5]) is equal to
+ * 0, the host application processor will be able to directly access the
+ * auxiliary I2C bus of the MPU-60X0. When this bit is equal to 0, the host
+ * application processor will not be able to directly access the auxiliary I2C
+ * bus of the MPU-60X0 regardless of the state of I2C_MST_EN (Register 106
+ * bit[5]).
+ * @return Current I2C bypass enabled status
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_I2C_BYPASS_EN_BIT
+ */
+bool MPU6050_Base::getI2CBypassEnabled() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_I2C_BYPASS_EN_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set I2C bypass enabled status.
+ * When this bit is equal to 1 and I2C_MST_EN (Register 106 bit[5]) is equal to
+ * 0, the host application processor will be able to directly access the
+ * auxiliary I2C bus of the MPU-60X0. When this bit is equal to 0, the host
+ * application processor will not be able to directly access the auxiliary I2C
+ * bus of the MPU-60X0 regardless of the state of I2C_MST_EN (Register 106
+ * bit[5]).
+ * @param enabled New I2C bypass enabled status
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_I2C_BYPASS_EN_BIT
+ */
+void MPU6050_Base::setI2CBypassEnabled(bool enabled) {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_I2C_BYPASS_EN_BIT, enabled, wireObj);
+}
+/** Get reference clock output enabled status.
+ * When this bit is equal to 1, a reference clock output is provided at the
+ * CLKOUT pin. When this bit is equal to 0, the clock output is disabled. For
+ * further information regarding CLKOUT, please refer to the MPU-60X0 Product
+ * Specification document.
+ * @return Current reference clock output enabled status
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_CLKOUT_EN_BIT
+ */
+bool MPU6050_Base::getClockOutputEnabled() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_CLKOUT_EN_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set reference clock output enabled status.
+ * When this bit is equal to 1, a reference clock output is provided at the
+ * CLKOUT pin. When this bit is equal to 0, the clock output is disabled. For
+ * further information regarding CLKOUT, please refer to the MPU-60X0 Product
+ * Specification document.
+ * @param enabled New reference clock output enabled status
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_CLKOUT_EN_BIT
+ */
+void MPU6050_Base::setClockOutputEnabled(bool enabled) {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_CLKOUT_EN_BIT, enabled, wireObj);
+}
+
+// INT_ENABLE register
+
+/** Get full interrupt enabled status.
+ * Full register byte for all interrupts, for quick reading. Each bit will be
+ * set 0 for disabled, 1 for enabled.
+ * @return Current interrupt enabled status
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_FF_BIT
+ **/
+uint8_t MPU6050_Base::getIntEnabled() {
+ I2Cdev::readByte(devAddr, MPU6050_RA_INT_ENABLE, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set full interrupt enabled status.
+ * Full register byte for all interrupts, for quick reading. Each bit should be
+ * set 0 for disabled, 1 for enabled.
+ * @param enabled New interrupt enabled status
+ * @see getIntFreefallEnabled()
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_FF_BIT
+ **/
+void MPU6050_Base::setIntEnabled(uint8_t enabled) {
+ I2Cdev::writeByte(devAddr, MPU6050_RA_INT_ENABLE, enabled, wireObj);
+}
+/** Get Free Fall interrupt enabled status.
+ * Will be set 0 for disabled, 1 for enabled.
+ * @return Current interrupt enabled status
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_FF_BIT
+ **/
+bool MPU6050_Base::getIntFreefallEnabled() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_FF_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set Free Fall interrupt enabled status.
+ * @param enabled New interrupt enabled status
+ * @see getIntFreefallEnabled()
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_FF_BIT
+ **/
+void MPU6050_Base::setIntFreefallEnabled(bool enabled) {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_FF_BIT, enabled, wireObj);
+}
+/** Get Motion Detection interrupt enabled status.
+ * Will be set 0 for disabled, 1 for enabled.
+ * @return Current interrupt enabled status
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_MOT_BIT
+ **/
+bool MPU6050_Base::getIntMotionEnabled() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_MOT_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set Motion Detection interrupt enabled status.
+ * @param enabled New interrupt enabled status
+ * @see getIntMotionEnabled()
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_MOT_BIT
+ **/
+void MPU6050_Base::setIntMotionEnabled(bool enabled) {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_MOT_BIT, enabled, wireObj);
+}
+/** Get Zero Motion Detection interrupt enabled status.
+ * Will be set 0 for disabled, 1 for enabled.
+ * @return Current interrupt enabled status
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_ZMOT_BIT
+ **/
+bool MPU6050_Base::getIntZeroMotionEnabled() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_ZMOT_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set Zero Motion Detection interrupt enabled status.
+ * @param enabled New interrupt enabled status
+ * @see getIntZeroMotionEnabled()
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_ZMOT_BIT
+ **/
+void MPU6050_Base::setIntZeroMotionEnabled(bool enabled) {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_ZMOT_BIT, enabled, wireObj);
+}
+/** Get FIFO Buffer Overflow interrupt enabled status.
+ * Will be set 0 for disabled, 1 for enabled.
+ * @return Current interrupt enabled status
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_FIFO_OFLOW_BIT
+ **/
+bool MPU6050_Base::getIntFIFOBufferOverflowEnabled() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_FIFO_OFLOW_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set FIFO Buffer Overflow interrupt enabled status.
+ * @param enabled New interrupt enabled status
+ * @see getIntFIFOBufferOverflowEnabled()
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_FIFO_OFLOW_BIT
+ **/
+void MPU6050_Base::setIntFIFOBufferOverflowEnabled(bool enabled) {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_FIFO_OFLOW_BIT, enabled, wireObj);
+}
+/** Get I2C Master interrupt enabled status.
+ * This enables any of the I2C Master interrupt sources to generate an
+ * interrupt. Will be set 0 for disabled, 1 for enabled.
+ * @return Current interrupt enabled status
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_I2C_MST_INT_BIT
+ **/
+bool MPU6050_Base::getIntI2CMasterEnabled() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_I2C_MST_INT_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set I2C Master interrupt enabled status.
+ * @param enabled New interrupt enabled status
+ * @see getIntI2CMasterEnabled()
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_I2C_MST_INT_BIT
+ **/
+void MPU6050_Base::setIntI2CMasterEnabled(bool enabled) {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_I2C_MST_INT_BIT, enabled, wireObj);
+}
+/** Get Data Ready interrupt enabled setting.
+ * This event occurs each time a write operation to all of the sensor registers
+ * has been completed. Will be set 0 for disabled, 1 for enabled.
+ * @return Current interrupt enabled status
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_DATA_RDY_BIT
+ */
+bool MPU6050_Base::getIntDataReadyEnabled() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_DATA_RDY_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set Data Ready interrupt enabled status.
+ * @param enabled New interrupt enabled status
+ * @see getIntDataReadyEnabled()
+ * @see MPU6050_RA_INT_CFG
+ * @see MPU6050_INTERRUPT_DATA_RDY_BIT
+ */
+void MPU6050_Base::setIntDataReadyEnabled(bool enabled) {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_DATA_RDY_BIT, enabled, wireObj);
+}
+
+// INT_STATUS register
+
+/** Get full set of interrupt status bits.
+ * These bits clear to 0 after the register has been read. Very useful
+ * for getting multiple INT statuses, since each single bit read clears
+ * all of them because it has to read the whole byte.
+ * @return Current interrupt status
+ * @see MPU6050_RA_INT_STATUS
+ */
+uint8_t MPU6050_Base::getIntStatus() {
+ I2Cdev::readByte(devAddr, MPU6050_RA_INT_STATUS, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Get Free Fall interrupt status.
+ * This bit automatically sets to 1 when a Free Fall interrupt has been
+ * generated. The bit clears to 0 after the register has been read.
+ * @return Current interrupt status
+ * @see MPU6050_RA_INT_STATUS
+ * @see MPU6050_INTERRUPT_FF_BIT
+ */
+bool MPU6050_Base::getIntFreefallStatus() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_FF_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Get Motion Detection interrupt status.
+ * This bit automatically sets to 1 when a Motion Detection interrupt has been
+ * generated. The bit clears to 0 after the register has been read.
+ * @return Current interrupt status
+ * @see MPU6050_RA_INT_STATUS
+ * @see MPU6050_INTERRUPT_MOT_BIT
+ */
+bool MPU6050_Base::getIntMotionStatus() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_MOT_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Get Zero Motion Detection interrupt status.
+ * This bit automatically sets to 1 when a Zero Motion Detection interrupt has
+ * been generated. The bit clears to 0 after the register has been read.
+ * @return Current interrupt status
+ * @see MPU6050_RA_INT_STATUS
+ * @see MPU6050_INTERRUPT_ZMOT_BIT
+ */
+bool MPU6050_Base::getIntZeroMotionStatus() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_ZMOT_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Get FIFO Buffer Overflow interrupt status.
+ * This bit automatically sets to 1 when a Free Fall interrupt has been
+ * generated. The bit clears to 0 after the register has been read.
+ * @return Current interrupt status
+ * @see MPU6050_RA_INT_STATUS
+ * @see MPU6050_INTERRUPT_FIFO_OFLOW_BIT
+ */
+bool MPU6050_Base::getIntFIFOBufferOverflowStatus() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_FIFO_OFLOW_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Get I2C Master interrupt status.
+ * This bit automatically sets to 1 when an I2C Master interrupt has been
+ * generated. For a list of I2C Master interrupts, please refer to Register 54.
+ * The bit clears to 0 after the register has been read.
+ * @return Current interrupt status
+ * @see MPU6050_RA_INT_STATUS
+ * @see MPU6050_INTERRUPT_I2C_MST_INT_BIT
+ */
+bool MPU6050_Base::getIntI2CMasterStatus() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_I2C_MST_INT_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Get Data Ready interrupt status.
+ * This bit automatically sets to 1 when a Data Ready interrupt has been
+ * generated. The bit clears to 0 after the register has been read.
+ * @return Current interrupt status
+ * @see MPU6050_RA_INT_STATUS
+ * @see MPU6050_INTERRUPT_DATA_RDY_BIT
+ */
+bool MPU6050_Base::getIntDataReadyStatus() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_DATA_RDY_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+
+// ACCEL_*OUT_* registers
+
+/** Get raw 9-axis motion sensor readings (accel/gyro/compass).
+ * FUNCTION NOT FULLY IMPLEMENTED YET.
+ * @param ax 16-bit signed integer container for accelerometer X-axis value
+ * @param ay 16-bit signed integer container for accelerometer Y-axis value
+ * @param az 16-bit signed integer container for accelerometer Z-axis value
+ * @param gx 16-bit signed integer container for gyroscope X-axis value
+ * @param gy 16-bit signed integer container for gyroscope Y-axis value
+ * @param gz 16-bit signed integer container for gyroscope Z-axis value
+ * @param mx 16-bit signed integer container for magnetometer X-axis value
+ * @param my 16-bit signed integer container for magnetometer Y-axis value
+ * @param mz 16-bit signed integer container for magnetometer Z-axis value
+ * @see getMotion6()
+ * @see getAcceleration()
+ * @see getRotation()
+ * @see MPU6050_RA_ACCEL_XOUT_H
+ */
+void MPU6050_Base::getMotion9(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz, int16_t* mx, int16_t* my, int16_t* mz) {
+ (void)mx; // unused parameter
+ (void)my; // unused parameter
+ (void)mz; // unused parameter
+
+ getMotion6(ax, ay, az, gx, gy, gz);
+ // TODO: magnetometer integration
+}
+/** Get raw 6-axis motion sensor readings (accel/gyro).
+ * Retrieves all currently available motion sensor values.
+ * @param ax 16-bit signed integer container for accelerometer X-axis value
+ * @param ay 16-bit signed integer container for accelerometer Y-axis value
+ * @param az 16-bit signed integer container for accelerometer Z-axis value
+ * @param gx 16-bit signed integer container for gyroscope X-axis value
+ * @param gy 16-bit signed integer container for gyroscope Y-axis value
+ * @param gz 16-bit signed integer container for gyroscope Z-axis value
+ * @see getAcceleration()
+ * @see getRotation()
+ * @see MPU6050_RA_ACCEL_XOUT_H
+ */
+void MPU6050_Base::getMotion6(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz) {
+ I2Cdev::readBytes(devAddr, MPU6050_RA_ACCEL_XOUT_H, 14, buffer, I2Cdev::readTimeout, wireObj);
+ *ax = (((int16_t)buffer[0]) << 8) | buffer[1];
+ *ay = (((int16_t)buffer[2]) << 8) | buffer[3];
+ *az = (((int16_t)buffer[4]) << 8) | buffer[5];
+ *gx = (((int16_t)buffer[8]) << 8) | buffer[9];
+ *gy = (((int16_t)buffer[10]) << 8) | buffer[11];
+ *gz = (((int16_t)buffer[12]) << 8) | buffer[13];
+}
+/** Get 3-axis accelerometer readings.
+ * These registers store the most recent accelerometer measurements.
+ * Accelerometer measurements are written to these registers at the Sample Rate
+ * as defined in Register 25.
+ *
+ * The accelerometer measurement registers, along with the temperature
+ * measurement registers, gyroscope measurement registers, and external sensor
+ * data registers, are composed of two sets of registers: an internal register
+ * set and a user-facing read register set.
+ *
+ * The data within the accelerometer sensors' internal register set is always
+ * updated at the Sample Rate. Meanwhile, the user-facing read register set
+ * duplicates the internal register set's data values whenever the serial
+ * interface is idle. This guarantees that a burst read of sensor registers will
+ * read measurements from the same sampling instant. Note that if burst reads
+ * are not used, the user is responsible for ensuring a set of single byte reads
+ * correspond to a single sampling instant by checking the Data Ready interrupt.
+ *
+ * Each 16-bit accelerometer measurement has a full scale defined in ACCEL_FS
+ * (Register 28). For each full scale setting, the accelerometers' sensitivity
+ * per LSB in ACCEL_xOUT is shown in the table below:
+ *
+ *
+ * AFS_SEL | Full Scale Range | LSB Sensitivity
+ * --------+------------------+----------------
+ * 0 | +/- 2g | 16384 LSB/mg
+ * 1 | +/- 4g | 8192 LSB/mg
+ * 2 | +/- 8g | 4096 LSB/mg
+ * 3 | +/- 16g | 2048 LSB/mg
+ *
+ *
+ * @param x 16-bit signed integer container for X-axis acceleration
+ * @param y 16-bit signed integer container for Y-axis acceleration
+ * @param z 16-bit signed integer container for Z-axis acceleration
+ * @see MPU6050_RA_GYRO_XOUT_H
+ */
+void MPU6050_Base::getAcceleration(int16_t* x, int16_t* y, int16_t* z) {
+ I2Cdev::readBytes(devAddr, MPU6050_RA_ACCEL_XOUT_H, 6, buffer, I2Cdev::readTimeout, wireObj);
+ *x = (((int16_t)buffer[0]) << 8) | buffer[1];
+ *y = (((int16_t)buffer[2]) << 8) | buffer[3];
+ *z = (((int16_t)buffer[4]) << 8) | buffer[5];
+}
+/** Get X-axis accelerometer reading.
+ * @return X-axis acceleration measurement in 16-bit 2's complement format
+ * @see getMotion6()
+ * @see MPU6050_RA_ACCEL_XOUT_H
+ */
+int16_t MPU6050_Base::getAccelerationX() {
+ I2Cdev::readBytes(devAddr, MPU6050_RA_ACCEL_XOUT_H, 2, buffer, I2Cdev::readTimeout, wireObj);
+ return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+/** Get Y-axis accelerometer reading.
+ * @return Y-axis acceleration measurement in 16-bit 2's complement format
+ * @see getMotion6()
+ * @see MPU6050_RA_ACCEL_YOUT_H
+ */
+int16_t MPU6050_Base::getAccelerationY() {
+ I2Cdev::readBytes(devAddr, MPU6050_RA_ACCEL_YOUT_H, 2, buffer, I2Cdev::readTimeout, wireObj);
+ return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+/** Get Z-axis accelerometer reading.
+ * @return Z-axis acceleration measurement in 16-bit 2's complement format
+ * @see getMotion6()
+ * @see MPU6050_RA_ACCEL_ZOUT_H
+ */
+int16_t MPU6050_Base::getAccelerationZ() {
+ I2Cdev::readBytes(devAddr, MPU6050_RA_ACCEL_ZOUT_H, 2, buffer, I2Cdev::readTimeout, wireObj);
+ return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+
+// TEMP_OUT_* registers
+
+/** Get current internal temperature.
+ * @return Temperature reading in 16-bit 2's complement format
+ * @see MPU6050_RA_TEMP_OUT_H
+ */
+int16_t MPU6050_Base::getTemperature() {
+ I2Cdev::readBytes(devAddr, MPU6050_RA_TEMP_OUT_H, 2, buffer, I2Cdev::readTimeout, wireObj);
+ return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+
+// GYRO_*OUT_* registers
+
+/** Get 3-axis gyroscope readings.
+ * These gyroscope measurement registers, along with the accelerometer
+ * measurement registers, temperature measurement registers, and external sensor
+ * data registers, are composed of two sets of registers: an internal register
+ * set and a user-facing read register set.
+ * The data within the gyroscope sensors' internal register set is always
+ * updated at the Sample Rate. Meanwhile, the user-facing read register set
+ * duplicates the internal register set's data values whenever the serial
+ * interface is idle. This guarantees that a burst read of sensor registers will
+ * read measurements from the same sampling instant. Note that if burst reads
+ * are not used, the user is responsible for ensuring a set of single byte reads
+ * correspond to a single sampling instant by checking the Data Ready interrupt.
+ *
+ * Each 16-bit gyroscope measurement has a full scale defined in FS_SEL
+ * (Register 27). For each full scale setting, the gyroscopes' sensitivity per
+ * LSB in GYRO_xOUT is shown in the table below:
+ *
+ *
+ * FS_SEL | Full Scale Range | LSB Sensitivity
+ * -------+--------------------+----------------
+ * 0 | +/- 250 degrees/s | 131 LSB/deg/s
+ * 1 | +/- 500 degrees/s | 65.5 LSB/deg/s
+ * 2 | +/- 1000 degrees/s | 32.8 LSB/deg/s
+ * 3 | +/- 2000 degrees/s | 16.4 LSB/deg/s
+ *
+ *
+ * @param x 16-bit signed integer container for X-axis rotation
+ * @param y 16-bit signed integer container for Y-axis rotation
+ * @param z 16-bit signed integer container for Z-axis rotation
+ * @see getMotion6()
+ * @see MPU6050_RA_GYRO_XOUT_H
+ */
+void MPU6050_Base::getRotation(int16_t* x, int16_t* y, int16_t* z) {
+ I2Cdev::readBytes(devAddr, MPU6050_RA_GYRO_XOUT_H, 6, buffer, I2Cdev::readTimeout, wireObj);
+ *x = (((int16_t)buffer[0]) << 8) | buffer[1];
+ *y = (((int16_t)buffer[2]) << 8) | buffer[3];
+ *z = (((int16_t)buffer[4]) << 8) | buffer[5];
+}
+/** Get X-axis gyroscope reading.
+ * @return X-axis rotation measurement in 16-bit 2's complement format
+ * @see getMotion6()
+ * @see MPU6050_RA_GYRO_XOUT_H
+ */
+int16_t MPU6050_Base::getRotationX() {
+ I2Cdev::readBytes(devAddr, MPU6050_RA_GYRO_XOUT_H, 2, buffer, I2Cdev::readTimeout, wireObj);
+ return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+/** Get Y-axis gyroscope reading.
+ * @return Y-axis rotation measurement in 16-bit 2's complement format
+ * @see getMotion6()
+ * @see MPU6050_RA_GYRO_YOUT_H
+ */
+int16_t MPU6050_Base::getRotationY() {
+ I2Cdev::readBytes(devAddr, MPU6050_RA_GYRO_YOUT_H, 2, buffer, I2Cdev::readTimeout, wireObj);
+ return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+/** Get Z-axis gyroscope reading.
+ * @return Z-axis rotation measurement in 16-bit 2's complement format
+ * @see getMotion6()
+ * @see MPU6050_RA_GYRO_ZOUT_H
+ */
+int16_t MPU6050_Base::getRotationZ() {
+ I2Cdev::readBytes(devAddr, MPU6050_RA_GYRO_ZOUT_H, 2, buffer, I2Cdev::readTimeout, wireObj);
+ return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+
+// EXT_SENS_DATA_* registers
+
+/** Read single byte from external sensor data register.
+ * These registers store data read from external sensors by the Slave 0, 1, 2,
+ * and 3 on the auxiliary I2C interface. Data read by Slave 4 is stored in
+ * I2C_SLV4_DI (Register 53).
+ *
+ * External sensor data is written to these registers at the Sample Rate as
+ * defined in Register 25. This access rate can be reduced by using the Slave
+ * Delay Enable registers (Register 103).
+ *
+ * External sensor data registers, along with the gyroscope measurement
+ * registers, accelerometer measurement registers, and temperature measurement
+ * registers, are composed of two sets of registers: an internal register set
+ * and a user-facing read register set.
+ *
+ * The data within the external sensors' internal register set is always updated
+ * at the Sample Rate (or the reduced access rate) whenever the serial interface
+ * is idle. This guarantees that a burst read of sensor registers will read
+ * measurements from the same sampling instant. Note that if burst reads are not
+ * used, the user is responsible for ensuring a set of single byte reads
+ * correspond to a single sampling instant by checking the Data Ready interrupt.
+ *
+ * Data is placed in these external sensor data registers according to
+ * I2C_SLV0_CTRL, I2C_SLV1_CTRL, I2C_SLV2_CTRL, and I2C_SLV3_CTRL (Registers 39,
+ * 42, 45, and 48). When more than zero bytes are read (I2C_SLVx_LEN > 0) from
+ * an enabled slave (I2C_SLVx_EN = 1), the slave is read at the Sample Rate (as
+ * defined in Register 25) or delayed rate (if specified in Register 52 and
+ * 103). During each Sample cycle, slave reads are performed in order of Slave
+ * number. If all slaves are enabled with more than zero bytes to be read, the
+ * order will be Slave 0, followed by Slave 1, Slave 2, and Slave 3.
+ *
+ * Each enabled slave will have EXT_SENS_DATA registers associated with it by
+ * number of bytes read (I2C_SLVx_LEN) in order of slave number, starting from
+ * EXT_SENS_DATA_00. Note that this means enabling or disabling a slave may
+ * change the higher numbered slaves' associated registers. Furthermore, if
+ * fewer total bytes are being read from the external sensors as a result of
+ * such a change, then the data remaining in the registers which no longer have
+ * an associated slave device (i.e. high numbered registers) will remain in
+ * these previously allocated registers unless reset.
+ *
+ * If the sum of the read lengths of all SLVx transactions exceed the number of
+ * available EXT_SENS_DATA registers, the excess bytes will be dropped. There
+ * are 24 EXT_SENS_DATA registers and hence the total read lengths between all
+ * the slaves cannot be greater than 24 or some bytes will be lost.
+ *
+ * Note: Slave 4's behavior is distinct from that of Slaves 0-3. For further
+ * information regarding the characteristics of Slave 4, please refer to
+ * Registers 49 to 53.
+ *
+ * EXAMPLE:
+ * Suppose that Slave 0 is enabled with 4 bytes to be read (I2C_SLV0_EN = 1 and
+ * I2C_SLV0_LEN = 4) while Slave 1 is enabled with 2 bytes to be read so that
+ * I2C_SLV1_EN = 1 and I2C_SLV1_LEN = 2. In such a situation, EXT_SENS_DATA _00
+ * through _03 will be associated with Slave 0, while EXT_SENS_DATA _04 and 05
+ * will be associated with Slave 1. If Slave 2 is enabled as well, registers
+ * starting from EXT_SENS_DATA_06 will be allocated to Slave 2.
+ *
+ * If Slave 2 is disabled while Slave 3 is enabled in this same situation, then
+ * registers starting from EXT_SENS_DATA_06 will be allocated to Slave 3
+ * instead.
+ *
+ * REGISTER ALLOCATION FOR DYNAMIC DISABLE VS. NORMAL DISABLE:
+ * If a slave is disabled at any time, the space initially allocated to the
+ * slave in the EXT_SENS_DATA register, will remain associated with that slave.
+ * This is to avoid dynamic adjustment of the register allocation.
+ *
+ * The allocation of the EXT_SENS_DATA registers is recomputed only when (1) all
+ * slaves are disabled, or (2) the I2C_MST_RST bit is set (Register 106).
+ *
+ * This above is also true if one of the slaves gets NACKed and stops
+ * functioning.
+ *
+ * @param position Starting position (0-23)
+ * @return Byte read from register
+ */
+uint8_t MPU6050_Base::getExternalSensorByte(int position) {
+ I2Cdev::readByte(devAddr, MPU6050_RA_EXT_SENS_DATA_00 + position, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Read word (2 bytes) from external sensor data registers.
+ * @param position Starting position (0-21)
+ * @return Word read from register
+ * @see getExternalSensorByte()
+ */
+uint16_t MPU6050_Base::getExternalSensorWord(int position) {
+ I2Cdev::readBytes(devAddr, MPU6050_RA_EXT_SENS_DATA_00 + position, 2, buffer, I2Cdev::readTimeout, wireObj);
+ return (((uint16_t)buffer[0]) << 8) | buffer[1];
+}
+/** Read double word (4 bytes) from external sensor data registers.
+ * @param position Starting position (0-20)
+ * @return Double word read from registers
+ * @see getExternalSensorByte()
+ */
+uint32_t MPU6050_Base::getExternalSensorDWord(int position) {
+ I2Cdev::readBytes(devAddr, MPU6050_RA_EXT_SENS_DATA_00 + position, 4, buffer, I2Cdev::readTimeout, wireObj);
+ return (((uint32_t)buffer[0]) << 24) | (((uint32_t)buffer[1]) << 16) | (((uint16_t)buffer[2]) << 8) | buffer[3];
+}
+
+// MOT_DETECT_STATUS register
+
+/** Get full motion detection status register content (all bits).
+ * @return Motion detection status byte
+ * @see MPU6050_RA_MOT_DETECT_STATUS
+ */
+uint8_t MPU6050_Base::getMotionStatus() {
+ I2Cdev::readByte(devAddr, MPU6050_RA_MOT_DETECT_STATUS, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Get X-axis negative motion detection interrupt status.
+ * @return Motion detection status
+ * @see MPU6050_RA_MOT_DETECT_STATUS
+ * @see MPU6050_MOTION_MOT_XNEG_BIT
+ */
+bool MPU6050_Base::getXNegMotionDetected() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_XNEG_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Get X-axis positive motion detection interrupt status.
+ * @return Motion detection status
+ * @see MPU6050_RA_MOT_DETECT_STATUS
+ * @see MPU6050_MOTION_MOT_XPOS_BIT
+ */
+bool MPU6050_Base::getXPosMotionDetected() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_XPOS_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Get Y-axis negative motion detection interrupt status.
+ * @return Motion detection status
+ * @see MPU6050_RA_MOT_DETECT_STATUS
+ * @see MPU6050_MOTION_MOT_YNEG_BIT
+ */
+bool MPU6050_Base::getYNegMotionDetected() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_YNEG_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Get Y-axis positive motion detection interrupt status.
+ * @return Motion detection status
+ * @see MPU6050_RA_MOT_DETECT_STATUS
+ * @see MPU6050_MOTION_MOT_YPOS_BIT
+ */
+bool MPU6050_Base::getYPosMotionDetected() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_YPOS_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Get Z-axis negative motion detection interrupt status.
+ * @return Motion detection status
+ * @see MPU6050_RA_MOT_DETECT_STATUS
+ * @see MPU6050_MOTION_MOT_ZNEG_BIT
+ */
+bool MPU6050_Base::getZNegMotionDetected() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_ZNEG_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Get Z-axis positive motion detection interrupt status.
+ * @return Motion detection status
+ * @see MPU6050_RA_MOT_DETECT_STATUS
+ * @see MPU6050_MOTION_MOT_ZPOS_BIT
+ */
+bool MPU6050_Base::getZPosMotionDetected() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_ZPOS_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Get zero motion detection interrupt status.
+ * @return Motion detection status
+ * @see MPU6050_RA_MOT_DETECT_STATUS
+ * @see MPU6050_MOTION_MOT_ZRMOT_BIT
+ */
+bool MPU6050_Base::getZeroMotionDetected() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_ZRMOT_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+
+// I2C_SLV*_DO register
+
+/** Write byte to Data Output container for specified slave.
+ * This register holds the output data written into Slave when Slave is set to
+ * write mode. For further information regarding Slave control, please
+ * refer to Registers 37 to 39 and immediately following.
+ * @param num Slave number (0-3)
+ * @param data Byte to write
+ * @see MPU6050_RA_I2C_SLV0_DO
+ */
+void MPU6050_Base::setSlaveOutputByte(uint8_t num, uint8_t data) {
+ if (num > 3) return;
+ I2Cdev::writeByte(devAddr, MPU6050_RA_I2C_SLV0_DO + num, data, wireObj);
+}
+
+// I2C_MST_DELAY_CTRL register
+
+/** Get external data shadow delay enabled status.
+ * This register is used to specify the timing of external sensor data
+ * shadowing. When DELAY_ES_SHADOW is set to 1, shadowing of external
+ * sensor data is delayed until all data has been received.
+ * @return Current external data shadow delay enabled status.
+ * @see MPU6050_RA_I2C_MST_DELAY_CTRL
+ * @see MPU6050_DELAYCTRL_DELAY_ES_SHADOW_BIT
+ */
+bool MPU6050_Base::getExternalShadowDelayEnabled() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_I2C_MST_DELAY_CTRL, MPU6050_DELAYCTRL_DELAY_ES_SHADOW_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set external data shadow delay enabled status.
+ * @param enabled New external data shadow delay enabled status.
+ * @see getExternalShadowDelayEnabled()
+ * @see MPU6050_RA_I2C_MST_DELAY_CTRL
+ * @see MPU6050_DELAYCTRL_DELAY_ES_SHADOW_BIT
+ */
+void MPU6050_Base::setExternalShadowDelayEnabled(bool enabled) {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_I2C_MST_DELAY_CTRL, MPU6050_DELAYCTRL_DELAY_ES_SHADOW_BIT, enabled, wireObj);
+}
+/** Get slave delay enabled status.
+ * When a particular slave delay is enabled, the rate of access for the that
+ * slave device is reduced. When a slave's access rate is decreased relative to
+ * the Sample Rate, the slave is accessed every:
+ *
+ * 1 / (1 + I2C_MST_DLY) Samples
+ *
+ * This base Sample Rate in turn is determined by SMPLRT_DIV (register * 25)
+ * and DLPF_CFG (register 26).
+ *
+ * For further information regarding I2C_MST_DLY, please refer to register 52.
+ * For further information regarding the Sample Rate, please refer to register 25.
+ *
+ * @param num Slave number (0-4)
+ * @return Current slave delay enabled status.
+ * @see MPU6050_RA_I2C_MST_DELAY_CTRL
+ * @see MPU6050_DELAYCTRL_I2C_SLV0_DLY_EN_BIT
+ */
+bool MPU6050_Base::getSlaveDelayEnabled(uint8_t num) {
+ // MPU6050_DELAYCTRL_I2C_SLV4_DLY_EN_BIT is 4, SLV3 is 3, etc.
+ if (num > 4) return 0;
+ I2Cdev::readBit(devAddr, MPU6050_RA_I2C_MST_DELAY_CTRL, num, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set slave delay enabled status.
+ * @param num Slave number (0-4)
+ * @param enabled New slave delay enabled status.
+ * @see MPU6050_RA_I2C_MST_DELAY_CTRL
+ * @see MPU6050_DELAYCTRL_I2C_SLV0_DLY_EN_BIT
+ */
+void MPU6050_Base::setSlaveDelayEnabled(uint8_t num, bool enabled) {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_I2C_MST_DELAY_CTRL, num, enabled, wireObj);
+}
+
+// SIGNAL_PATH_RESET register
+
+/** Reset gyroscope signal path.
+ * The reset will revert the signal path analog to digital converters and
+ * filters to their power up configurations.
+ * @see MPU6050_RA_SIGNAL_PATH_RESET
+ * @see MPU6050_PATHRESET_GYRO_RESET_BIT
+ */
+void MPU6050_Base::resetGyroscopePath() {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_SIGNAL_PATH_RESET, MPU6050_PATHRESET_GYRO_RESET_BIT, true, wireObj);
+}
+/** Reset accelerometer signal path.
+ * The reset will revert the signal path analog to digital converters and
+ * filters to their power up configurations.
+ * @see MPU6050_RA_SIGNAL_PATH_RESET
+ * @see MPU6050_PATHRESET_ACCEL_RESET_BIT
+ */
+void MPU6050_Base::resetAccelerometerPath() {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_SIGNAL_PATH_RESET, MPU6050_PATHRESET_ACCEL_RESET_BIT, true, wireObj);
+}
+/** Reset temperature sensor signal path.
+ * The reset will revert the signal path analog to digital converters and
+ * filters to their power up configurations.
+ * @see MPU6050_RA_SIGNAL_PATH_RESET
+ * @see MPU6050_PATHRESET_TEMP_RESET_BIT
+ */
+void MPU6050_Base::resetTemperaturePath() {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_SIGNAL_PATH_RESET, MPU6050_PATHRESET_TEMP_RESET_BIT, true, wireObj);
+}
+
+// MOT_DETECT_CTRL register
+
+/** Get accelerometer power-on delay.
+ * The accelerometer data path provides samples to the sensor registers, Motion
+ * detection, Zero Motion detection, and Free Fall detection modules. The
+ * signal path contains filters which must be flushed on wake-up with new
+ * samples before the detection modules begin operations. The default wake-up
+ * delay, of 4ms can be lengthened by up to 3ms. This additional delay is
+ * specified in ACCEL_ON_DELAY in units of 1 LSB = 1 ms. The user may select
+ * any value above zero unless instructed otherwise by InvenSense. Please refer
+ * to Section 8 of the MPU-6000/MPU-6050 Product Specification document for
+ * further information regarding the detection modules.
+ * @return Current accelerometer power-on delay
+ * @see MPU6050_RA_MOT_DETECT_CTRL
+ * @see MPU6050_DETECT_ACCEL_ON_DELAY_BIT
+ */
+uint8_t MPU6050_Base::getAccelerometerPowerOnDelay() {
+ I2Cdev::readBits(devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_ACCEL_ON_DELAY_BIT, MPU6050_DETECT_ACCEL_ON_DELAY_LENGTH, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set accelerometer power-on delay.
+ * @param delay New accelerometer power-on delay (0-3)
+ * @see getAccelerometerPowerOnDelay()
+ * @see MPU6050_RA_MOT_DETECT_CTRL
+ * @see MPU6050_DETECT_ACCEL_ON_DELAY_BIT
+ */
+void MPU6050_Base::setAccelerometerPowerOnDelay(uint8_t delay) {
+ I2Cdev::writeBits(devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_ACCEL_ON_DELAY_BIT, MPU6050_DETECT_ACCEL_ON_DELAY_LENGTH, delay, wireObj);
+}
+/** Get Free Fall detection counter decrement configuration.
+ * Detection is registered by the Free Fall detection module after accelerometer
+ * measurements meet their respective threshold conditions over a specified
+ * number of samples. When the threshold conditions are met, the corresponding
+ * detection counter increments by 1. The user may control the rate at which the
+ * detection counter decrements when the threshold condition is not met by
+ * configuring FF_COUNT. The decrement rate can be set according to the
+ * following table:
+ *
+ *
+ * FF_COUNT | Counter Decrement
+ * ---------+------------------
+ * 0 | Reset
+ * 1 | 1
+ * 2 | 2
+ * 3 | 4
+ *
+ *
+ * When FF_COUNT is configured to 0 (reset), any non-qualifying sample will
+ * reset the counter to 0. For further information on Free Fall detection,
+ * please refer to Registers 29 to 32.
+ *
+ * @return Current decrement configuration
+ * @see MPU6050_RA_MOT_DETECT_CTRL
+ * @see MPU6050_DETECT_FF_COUNT_BIT
+ */
+uint8_t MPU6050_Base::getFreefallDetectionCounterDecrement() {
+ I2Cdev::readBits(devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_FF_COUNT_BIT, MPU6050_DETECT_FF_COUNT_LENGTH, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set Free Fall detection counter decrement configuration.
+ * @param decrement New decrement configuration value
+ * @see getFreefallDetectionCounterDecrement()
+ * @see MPU6050_RA_MOT_DETECT_CTRL
+ * @see MPU6050_DETECT_FF_COUNT_BIT
+ */
+void MPU6050_Base::setFreefallDetectionCounterDecrement(uint8_t decrement) {
+ I2Cdev::writeBits(devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_FF_COUNT_BIT, MPU6050_DETECT_FF_COUNT_LENGTH, decrement, wireObj);
+}
+/** Get Motion detection counter decrement configuration.
+ * Detection is registered by the Motion detection module after accelerometer
+ * measurements meet their respective threshold conditions over a specified
+ * number of samples. When the threshold conditions are met, the corresponding
+ * detection counter increments by 1. The user may control the rate at which the
+ * detection counter decrements when the threshold condition is not met by
+ * configuring MOT_COUNT. The decrement rate can be set according to the
+ * following table:
+ *
+ *
+ * MOT_COUNT | Counter Decrement
+ * ----------+------------------
+ * 0 | Reset
+ * 1 | 1
+ * 2 | 2
+ * 3 | 4
+ *
+ *
+ * When MOT_COUNT is configured to 0 (reset), any non-qualifying sample will
+ * reset the counter to 0. For further information on Motion detection,
+ * please refer to Registers 29 to 32.
+ *
+ */
+uint8_t MPU6050_Base::getMotionDetectionCounterDecrement() {
+ I2Cdev::readBits(devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_MOT_COUNT_BIT, MPU6050_DETECT_MOT_COUNT_LENGTH, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set Motion detection counter decrement configuration.
+ * @param decrement New decrement configuration value
+ * @see getMotionDetectionCounterDecrement()
+ * @see MPU6050_RA_MOT_DETECT_CTRL
+ * @see MPU6050_DETECT_MOT_COUNT_BIT
+ */
+void MPU6050_Base::setMotionDetectionCounterDecrement(uint8_t decrement) {
+ I2Cdev::writeBits(devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_MOT_COUNT_BIT, MPU6050_DETECT_MOT_COUNT_LENGTH, decrement, wireObj);
+}
+
+// USER_CTRL register
+
+/** Get FIFO enabled status.
+ * When this bit is set to 0, the FIFO buffer is disabled. The FIFO buffer
+ * cannot be written to or read from while disabled. The FIFO buffer's state
+ * does not change unless the MPU-60X0 is power cycled.
+ * @return Current FIFO enabled status
+ * @see MPU6050_RA_USER_CTRL
+ * @see MPU6050_USERCTRL_FIFO_EN_BIT
+ */
+bool MPU6050_Base::getFIFOEnabled() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_FIFO_EN_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set FIFO enabled status.
+ * @param enabled New FIFO enabled status
+ * @see getFIFOEnabled()
+ * @see MPU6050_RA_USER_CTRL
+ * @see MPU6050_USERCTRL_FIFO_EN_BIT
+ */
+void MPU6050_Base::setFIFOEnabled(bool enabled) {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_FIFO_EN_BIT, enabled, wireObj);
+}
+/** Get I2C Master Mode enabled status.
+ * When this mode is enabled, the MPU-60X0 acts as the I2C Master to the
+ * external sensor slave devices on the auxiliary I2C bus. When this bit is
+ * cleared to 0, the auxiliary I2C bus lines (AUX_DA and AUX_CL) are logically
+ * driven by the primary I2C bus (SDA and SCL). This is a precondition to
+ * enabling Bypass Mode. For further information regarding Bypass Mode, please
+ * refer to Register 55.
+ * @return Current I2C Master Mode enabled status
+ * @see MPU6050_RA_USER_CTRL
+ * @see MPU6050_USERCTRL_I2C_MST_EN_BIT
+ */
+bool MPU6050_Base::getI2CMasterModeEnabled() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_I2C_MST_EN_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set I2C Master Mode enabled status.
+ * @param enabled New I2C Master Mode enabled status
+ * @see getI2CMasterModeEnabled()
+ * @see MPU6050_RA_USER_CTRL
+ * @see MPU6050_USERCTRL_I2C_MST_EN_BIT
+ */
+void MPU6050_Base::setI2CMasterModeEnabled(bool enabled) {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_I2C_MST_EN_BIT, enabled, wireObj);
+}
+/** Switch from I2C to SPI mode (MPU-6000 only)
+ * If this is set, the primary SPI interface will be enabled in place of the
+ * disabled primary I2C interface.
+ */
+void MPU6050_Base::switchSPIEnabled(bool enabled) {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_I2C_IF_DIS_BIT, enabled, wireObj);
+}
+/** Reset the FIFO.
+ * This bit resets the FIFO buffer when set to 1 while FIFO_EN equals 0. This
+ * bit automatically clears to 0 after the reset has been triggered.
+ * @see MPU6050_RA_USER_CTRL
+ * @see MPU6050_USERCTRL_FIFO_RESET_BIT
+ */
+void MPU6050_Base::resetFIFO() {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_FIFO_RESET_BIT, true, wireObj);
+}
+/** Reset the I2C Master.
+ * This bit resets the I2C Master when set to 1 while I2C_MST_EN equals 0.
+ * This bit automatically clears to 0 after the reset has been triggered.
+ * @see MPU6050_RA_USER_CTRL
+ * @see MPU6050_USERCTRL_I2C_MST_RESET_BIT
+ */
+void MPU6050_Base::resetI2CMaster() {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_I2C_MST_RESET_BIT, true, wireObj);
+}
+/** Reset all sensor registers and signal paths.
+ * When set to 1, this bit resets the signal paths for all sensors (gyroscopes,
+ * accelerometers, and temperature sensor). This operation will also clear the
+ * sensor registers. This bit automatically clears to 0 after the reset has been
+ * triggered.
+ *
+ * When resetting only the signal path (and not the sensor registers), please
+ * use Register 104, SIGNAL_PATH_RESET.
+ *
+ * @see MPU6050_RA_USER_CTRL
+ * @see MPU6050_USERCTRL_SIG_COND_RESET_BIT
+ */
+void MPU6050_Base::resetSensors() {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_SIG_COND_RESET_BIT, true, wireObj);
+}
+
+// PWR_MGMT_1 register
+
+/** Trigger a full device reset.
+ * A small delay of ~50ms may be desirable after triggering a reset.
+ * @see MPU6050_RA_PWR_MGMT_1
+ * @see MPU6050_PWR1_DEVICE_RESET_BIT
+ */
+void MPU6050_Base::reset() {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_DEVICE_RESET_BIT, true, wireObj);
+}
+/** Get sleep mode status.
+ * Setting the SLEEP bit in the register puts the device into very low power
+ * sleep mode. In this mode, only the serial interface and internal registers
+ * remain active, allowing for a very low standby current. Clearing this bit
+ * puts the device back into normal mode. To save power, the individual standby
+ * selections for each of the gyros should be used if any gyro axis is not used
+ * by the application.
+ * @return Current sleep mode enabled status
+ * @see MPU6050_RA_PWR_MGMT_1
+ * @see MPU6050_PWR1_SLEEP_BIT
+ */
+bool MPU6050_Base::getSleepEnabled() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_SLEEP_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set sleep mode status.
+ * @param enabled New sleep mode enabled status
+ * @see getSleepEnabled()
+ * @see MPU6050_RA_PWR_MGMT_1
+ * @see MPU6050_PWR1_SLEEP_BIT
+ */
+void MPU6050_Base::setSleepEnabled(bool enabled) {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_SLEEP_BIT, enabled, wireObj);
+}
+/** Get wake cycle enabled status.
+ * When this bit is set to 1 and SLEEP is disabled, the MPU-60X0 will cycle
+ * between sleep mode and waking up to take a single sample of data from active
+ * sensors at a rate determined by LP_WAKE_CTRL (register 108).
+ * @return Current sleep mode enabled status
+ * @see MPU6050_RA_PWR_MGMT_1
+ * @see MPU6050_PWR1_CYCLE_BIT
+ */
+bool MPU6050_Base::getWakeCycleEnabled() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_CYCLE_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set wake cycle enabled status.
+ * @param enabled New sleep mode enabled status
+ * @see getWakeCycleEnabled()
+ * @see MPU6050_RA_PWR_MGMT_1
+ * @see MPU6050_PWR1_CYCLE_BIT
+ */
+void MPU6050_Base::setWakeCycleEnabled(bool enabled) {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_CYCLE_BIT, enabled, wireObj);
+}
+/** Get temperature sensor enabled status.
+ * Control the usage of the internal temperature sensor.
+ *
+ * Note: this register stores the *disabled* value, but for consistency with the
+ * rest of the code, the function is named and used with standard true/false
+ * values to indicate whether the sensor is enabled or disabled, respectively.
+ *
+ * @return Current temperature sensor enabled status
+ * @see MPU6050_RA_PWR_MGMT_1
+ * @see MPU6050_PWR1_TEMP_DIS_BIT
+ */
+bool MPU6050_Base::getTempSensorEnabled() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_TEMP_DIS_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0] == 0; // 1 is actually disabled here
+}
+/** Set temperature sensor enabled status.
+ * Note: this register stores the *disabled* value, but for consistency with the
+ * rest of the code, the function is named and used with standard true/false
+ * values to indicate whether the sensor is enabled or disabled, respectively.
+ *
+ * @param enabled New temperature sensor enabled status
+ * @see getTempSensorEnabled()
+ * @see MPU6050_RA_PWR_MGMT_1
+ * @see MPU6050_PWR1_TEMP_DIS_BIT
+ */
+void MPU6050_Base::setTempSensorEnabled(bool enabled) {
+ // 1 is actually disabled here
+ I2Cdev::writeBit(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_TEMP_DIS_BIT, !enabled, wireObj);
+}
+/** Get clock source setting.
+ * @return Current clock source setting
+ * @see MPU6050_RA_PWR_MGMT_1
+ * @see MPU6050_PWR1_CLKSEL_BIT
+ * @see MPU6050_PWR1_CLKSEL_LENGTH
+ */
+uint8_t MPU6050_Base::getClockSource() {
+ I2Cdev::readBits(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_CLKSEL_BIT, MPU6050_PWR1_CLKSEL_LENGTH, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set clock source setting.
+ * An internal 8MHz oscillator, gyroscope based clock, or external sources can
+ * be selected as the MPU-60X0 clock source. When the internal 8 MHz oscillator
+ * or an external source is chosen as the clock source, the MPU-60X0 can operate
+ * in low power modes with the gyroscopes disabled.
+ *
+ * Upon power up, the MPU-60X0 clock source defaults to the internal oscillator.
+ * However, it is highly recommended that the device be configured to use one of
+ * the gyroscopes (or an external clock source) as the clock reference for
+ * improved stability. The clock source can be selected according to the following table:
+ *
+ *
+ * CLK_SEL | Clock Source
+ * --------+--------------------------------------
+ * 0 | Internal oscillator
+ * 1 | PLL with X Gyro reference
+ * 2 | PLL with Y Gyro reference
+ * 3 | PLL with Z Gyro reference
+ * 4 | PLL with external 32.768kHz reference
+ * 5 | PLL with external 19.2MHz reference
+ * 6 | Reserved
+ * 7 | Stops the clock and keeps the timing generator in reset
+ *
+ *
+ * @param source New clock source setting
+ * @see getClockSource()
+ * @see MPU6050_RA_PWR_MGMT_1
+ * @see MPU6050_PWR1_CLKSEL_BIT
+ * @see MPU6050_PWR1_CLKSEL_LENGTH
+ */
+void MPU6050_Base::setClockSource(uint8_t source) {
+ I2Cdev::writeBits(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_CLKSEL_BIT, MPU6050_PWR1_CLKSEL_LENGTH, source, wireObj);
+}
+
+// PWR_MGMT_2 register
+
+/** Get wake frequency in Accel-Only Low Power Mode.
+ * The MPU-60X0 can be put into Accerlerometer Only Low Power Mode by setting
+ * PWRSEL to 1 in the Power Management 1 register (Register 107). In this mode,
+ * the device will power off all devices except for the primary I2C interface,
+ * waking only the accelerometer at fixed intervals to take a single
+ * measurement. The frequency of wake-ups can be configured with LP_WAKE_CTRL
+ * as shown below:
+ *
+ *
+ * LP_WAKE_CTRL | Wake-up Frequency
+ * -------------+------------------
+ * 0 | 1.25 Hz
+ * 1 | 2.5 Hz
+ * 2 | 20 Hz
+ * 3 | 40 Hz
+ *
+ *
+ * For further information regarding the MPU-60X0's power modes, please refer to
+ * Register 107.
+ *
+ * @return Current wake frequency
+ * @see MPU6050_RA_PWR_MGMT_2
+ */
+uint8_t MPU6050_Base::getWakeFrequency() {
+ I2Cdev::readBits(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_LP_WAKE_CTRL_BIT, MPU6050_PWR2_LP_WAKE_CTRL_LENGTH, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set wake frequency in Accel-Only Low Power Mode.
+ * @param frequency New wake frequency
+ * @see MPU6050_RA_PWR_MGMT_2
+ */
+void MPU6050_Base::setWakeFrequency(uint8_t frequency) {
+ I2Cdev::writeBits(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_LP_WAKE_CTRL_BIT, MPU6050_PWR2_LP_WAKE_CTRL_LENGTH, frequency, wireObj);
+}
+
+/** Get X-axis accelerometer standby enabled status.
+ * If enabled, the X-axis will not gather or report data (or use power).
+ * @return Current X-axis standby enabled status
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_XA_BIT
+ */
+bool MPU6050_Base::getStandbyXAccelEnabled() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_XA_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set X-axis accelerometer standby enabled status.
+ * @param New X-axis standby enabled status
+ * @see getStandbyXAccelEnabled()
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_XA_BIT
+ */
+void MPU6050_Base::setStandbyXAccelEnabled(bool enabled) {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_XA_BIT, enabled, wireObj);
+}
+/** Get Y-axis accelerometer standby enabled status.
+ * If enabled, the Y-axis will not gather or report data (or use power).
+ * @return Current Y-axis standby enabled status
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_YA_BIT
+ */
+bool MPU6050_Base::getStandbyYAccelEnabled() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_YA_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set Y-axis accelerometer standby enabled status.
+ * @param New Y-axis standby enabled status
+ * @see getStandbyYAccelEnabled()
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_YA_BIT
+ */
+void MPU6050_Base::setStandbyYAccelEnabled(bool enabled) {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_YA_BIT, enabled, wireObj);
+}
+/** Get Z-axis accelerometer standby enabled status.
+ * If enabled, the Z-axis will not gather or report data (or use power).
+ * @return Current Z-axis standby enabled status
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_ZA_BIT
+ */
+bool MPU6050_Base::getStandbyZAccelEnabled() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_ZA_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set Z-axis accelerometer standby enabled status.
+ * @param New Z-axis standby enabled status
+ * @see getStandbyZAccelEnabled()
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_ZA_BIT
+ */
+void MPU6050_Base::setStandbyZAccelEnabled(bool enabled) {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_ZA_BIT, enabled, wireObj);
+}
+/** Get X-axis gyroscope standby enabled status.
+ * If enabled, the X-axis will not gather or report data (or use power).
+ * @return Current X-axis standby enabled status
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_XG_BIT
+ */
+bool MPU6050_Base::getStandbyXGyroEnabled() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_XG_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set X-axis gyroscope standby enabled status.
+ * @param New X-axis standby enabled status
+ * @see getStandbyXGyroEnabled()
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_XG_BIT
+ */
+void MPU6050_Base::setStandbyXGyroEnabled(bool enabled) {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_XG_BIT, enabled, wireObj);
+}
+/** Get Y-axis gyroscope standby enabled status.
+ * If enabled, the Y-axis will not gather or report data (or use power).
+ * @return Current Y-axis standby enabled status
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_YG_BIT
+ */
+bool MPU6050_Base::getStandbyYGyroEnabled() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_YG_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set Y-axis gyroscope standby enabled status.
+ * @param New Y-axis standby enabled status
+ * @see getStandbyYGyroEnabled()
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_YG_BIT
+ */
+void MPU6050_Base::setStandbyYGyroEnabled(bool enabled) {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_YG_BIT, enabled, wireObj);
+}
+/** Get Z-axis gyroscope standby enabled status.
+ * If enabled, the Z-axis will not gather or report data (or use power).
+ * @return Current Z-axis standby enabled status
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_ZG_BIT
+ */
+bool MPU6050_Base::getStandbyZGyroEnabled() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_ZG_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set Z-axis gyroscope standby enabled status.
+ * @param New Z-axis standby enabled status
+ * @see getStandbyZGyroEnabled()
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_ZG_BIT
+ */
+void MPU6050_Base::setStandbyZGyroEnabled(bool enabled) {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_ZG_BIT, enabled, wireObj);
+}
+
+// FIFO_COUNT* registers
+
+/** Get current FIFO buffer size.
+ * This value indicates the number of bytes stored in the FIFO buffer. This
+ * number is in turn the number of bytes that can be read from the FIFO buffer
+ * and it is directly proportional to the number of samples available given the
+ * set of sensor data bound to be stored in the FIFO (register 35 and 36).
+ * @return Current FIFO buffer size
+ */
+uint16_t MPU6050_Base::getFIFOCount() {
+ I2Cdev::readBytes(devAddr, MPU6050_RA_FIFO_COUNTH, 2, buffer, I2Cdev::readTimeout, wireObj);
+ return (((uint16_t)buffer[0]) << 8) | buffer[1];
+}
+
+// FIFO_R_W register
+
+/** Get byte from FIFO buffer.
+ * This register is used to read and write data from the FIFO buffer. Data is
+ * written to the FIFO in order of register number (from lowest to highest). If
+ * all the FIFO enable flags (see below) are enabled and all External Sensor
+ * Data registers (Registers 73 to 96) are associated with a Slave device, the
+ * contents of registers 59 through 96 will be written in order at the Sample
+ * Rate.
+ *
+ * The contents of the sensor data registers (Registers 59 to 96) are written
+ * into the FIFO buffer when their corresponding FIFO enable flags are set to 1
+ * in FIFO_EN (Register 35). An additional flag for the sensor data registers
+ * associated with I2C Slave 3 can be found in I2C_MST_CTRL (Register 36).
+ *
+ * If the FIFO buffer has overflowed, the status bit FIFO_OFLOW_INT is
+ * automatically set to 1. This bit is located in INT_STATUS (Register 58).
+ * When the FIFO buffer has overflowed, the oldest data will be lost and new
+ * data will be written to the FIFO.
+ *
+ * If the FIFO buffer is empty, reading this register will return the last byte
+ * that was previously read from the FIFO until new data is available. The user
+ * should check FIFO_COUNT to ensure that the FIFO buffer is not read when
+ * empty.
+ *
+ * @return Byte from FIFO buffer
+ */
+uint8_t MPU6050_Base::getFIFOByte() {
+ I2Cdev::readByte(devAddr, MPU6050_RA_FIFO_R_W, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+void MPU6050_Base::getFIFOBytes(uint8_t *data, uint8_t length) {
+ if(length > 0){
+ I2Cdev::readBytes(devAddr, MPU6050_RA_FIFO_R_W, length, data, I2Cdev::readTimeout, wireObj);
+ } else {
+ *data = 0;
+ }
+}
+
+/** Get timeout to get a packet from FIFO buffer.
+ * @return Current timeout to get a packet from FIFO buffer
+ * @see MPU6050_FIFO_DEFAULT_TIMEOUT
+ */
+uint32_t MPU6050_Base::getFIFOTimeout() {
+ return fifoTimeout;
+}
+
+/** Set timeout to get a packet from FIFO buffer.
+ * @param New timeout to get a packet from FIFO buffer
+ * @see MPU6050_FIFO_DEFAULT_TIMEOUT
+ */
+void MPU6050_Base::setFIFOTimeout(uint32_t fifoTimeout) {
+ this->fifoTimeout = fifoTimeout;
+}
+
+/** Get latest byte from FIFO buffer no matter how much time has passed.
+ * === GetCurrentFIFOPacket ===
+ * ================================================================
+ * Returns 1) when nothing special was done
+ * 2) when recovering from overflow
+ * 0) when no valid data is available
+ * ================================================================ */
+ int8_t MPU6050_Base::GetCurrentFIFOPacket(uint8_t *data, uint8_t length) { // overflow proof
+ int16_t fifoC;
+ // This section of code is for when we allowed more than 1 packet to be acquired
+ uint32_t BreakTimer = micros();
+ bool packetReceived = false;
+ do {
+ if ((fifoC = getFIFOCount()) > length) {
+
+ if (fifoC > 200) { // if you waited to get the FIFO buffer to > 200 bytes it will take longer to get the last packet in the FIFO Buffer than it will take to reset the buffer and wait for the next to arrive
+ resetFIFO(); // Fixes any overflow corruption
+ fifoC = 0;
+ while (!(fifoC = getFIFOCount()) && ((micros() - BreakTimer) <= (getFIFOTimeout()))); // Get Next New Packet
+ } else { //We have more than 1 packet but less than 200 bytes of data in the FIFO Buffer
+ uint8_t Trash[I2CDEVLIB_WIRE_BUFFER_LENGTH];
+ while ((fifoC = getFIFOCount()) > length) { // Test each time just in case the MPU is writing to the FIFO Buffer
+ fifoC = fifoC - length; // Save the last packet
+ uint16_t RemoveBytes;
+ while (fifoC) { // fifo count will reach zero so this is safe
+ RemoveBytes = (fifoC < I2CDEVLIB_WIRE_BUFFER_LENGTH) ? fifoC : I2CDEVLIB_WIRE_BUFFER_LENGTH; // Buffer Length is different than the packet length this will efficiently clear the buffer
+ getFIFOBytes(Trash, (uint8_t)RemoveBytes);
+ fifoC -= RemoveBytes;
+ }
+ }
+ }
+ }
+ if (!fifoC) return 0; // Called too early no data or we timed out after FIFO Reset
+ // We have 1 packet
+ packetReceived = fifoC == length;
+ if (!packetReceived && (micros() - BreakTimer) > (getFIFOTimeout())) return 0;
+ } while (!packetReceived);
+ getFIFOBytes(data, length); //Get 1 packet
+ return 1;
+}
+
+
+/** Write byte to FIFO buffer.
+ * @see getFIFOByte()
+ * @see MPU6050_RA_FIFO_R_W
+ */
+void MPU6050_Base::setFIFOByte(uint8_t data) {
+ I2Cdev::writeByte(devAddr, MPU6050_RA_FIFO_R_W, data, wireObj);
+}
+
+// WHO_AM_I register
+
+/** Get Device ID.
+ * This register is used to verify the identity of the device (0b110100, 0x34).
+ * @return Device ID (6 bits only! should be 0x34)
+ * @see MPU6050_RA_WHO_AM_I
+ * @see MPU6050_WHO_AM_I_BIT
+ * @see MPU6050_WHO_AM_I_LENGTH
+ */
+uint8_t MPU6050_Base::getDeviceID() {
+ I2Cdev::readBits(devAddr, MPU6050_RA_WHO_AM_I, MPU6050_WHO_AM_I_BIT, MPU6050_WHO_AM_I_LENGTH, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+/** Set Device ID.
+ * Write a new ID into the WHO_AM_I register (no idea why this should ever be
+ * necessary though).
+ * @param id New device ID to set.
+ * @see getDeviceID()
+ * @see MPU6050_RA_WHO_AM_I
+ * @see MPU6050_WHO_AM_I_BIT
+ * @see MPU6050_WHO_AM_I_LENGTH
+ */
+void MPU6050_Base::setDeviceID(uint8_t id) {
+ I2Cdev::writeBits(devAddr, MPU6050_RA_WHO_AM_I, MPU6050_WHO_AM_I_BIT, MPU6050_WHO_AM_I_LENGTH, id, wireObj);
+}
+
+// ======== UNDOCUMENTED/DMP REGISTERS/METHODS ========
+
+// XG_OFFS_TC register
+
+uint8_t MPU6050_Base::getOTPBankValid() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_XG_OFFS_TC, MPU6050_TC_OTP_BNK_VLD_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+void MPU6050_Base::setOTPBankValid(bool enabled) {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_XG_OFFS_TC, MPU6050_TC_OTP_BNK_VLD_BIT, enabled, wireObj);
+}
+int8_t MPU6050_Base::getXGyroOffsetTC() {
+ I2Cdev::readBits(devAddr, MPU6050_RA_XG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+void MPU6050_Base::setXGyroOffsetTC(int8_t offset) {
+ I2Cdev::writeBits(devAddr, MPU6050_RA_XG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, offset, wireObj);
+}
+
+// YG_OFFS_TC register
+
+int8_t MPU6050_Base::getYGyroOffsetTC() {
+ I2Cdev::readBits(devAddr, MPU6050_RA_YG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+void MPU6050_Base::setYGyroOffsetTC(int8_t offset) {
+ I2Cdev::writeBits(devAddr, MPU6050_RA_YG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, offset, wireObj);
+}
+
+// ZG_OFFS_TC register
+
+int8_t MPU6050_Base::getZGyroOffsetTC() {
+ I2Cdev::readBits(devAddr, MPU6050_RA_ZG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+void MPU6050_Base::setZGyroOffsetTC(int8_t offset) {
+ I2Cdev::writeBits(devAddr, MPU6050_RA_ZG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, offset, wireObj);
+}
+
+// X_FINE_GAIN register
+
+int8_t MPU6050_Base::getXFineGain() {
+ I2Cdev::readByte(devAddr, MPU6050_RA_X_FINE_GAIN, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+void MPU6050_Base::setXFineGain(int8_t gain) {
+ I2Cdev::writeByte(devAddr, MPU6050_RA_X_FINE_GAIN, gain, wireObj);
+}
+
+// Y_FINE_GAIN register
+
+int8_t MPU6050_Base::getYFineGain() {
+ I2Cdev::readByte(devAddr, MPU6050_RA_Y_FINE_GAIN, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+void MPU6050_Base::setYFineGain(int8_t gain) {
+ I2Cdev::writeByte(devAddr, MPU6050_RA_Y_FINE_GAIN, gain, wireObj);
+}
+
+// Z_FINE_GAIN register
+
+int8_t MPU6050_Base::getZFineGain() {
+ I2Cdev::readByte(devAddr, MPU6050_RA_Z_FINE_GAIN, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+void MPU6050_Base::setZFineGain(int8_t gain) {
+ I2Cdev::writeByte(devAddr, MPU6050_RA_Z_FINE_GAIN, gain, wireObj);
+}
+
+// XA_OFFS_* registers
+
+int16_t MPU6050_Base::getXAccelOffset() {
+ uint8_t SaveAddress = ((getDeviceID() < 0x38 )? MPU6050_RA_XA_OFFS_H:0x77); // MPU6050,MPU9150 Vs MPU6500,MPU9250
+ I2Cdev::readBytes(devAddr, SaveAddress, 2, buffer, I2Cdev::readTimeout, wireObj);
+ return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+void MPU6050_Base::setXAccelOffset(int16_t offset) {
+ uint8_t SaveAddress = ((getDeviceID() < 0x38 )? MPU6050_RA_XA_OFFS_H:0x77); // MPU6050,MPU9150 Vs MPU6500,MPU9250
+ I2Cdev::writeWord(devAddr, SaveAddress, offset, wireObj);
+}
+
+// YA_OFFS_* register
+
+int16_t MPU6050_Base::getYAccelOffset() {
+ uint8_t SaveAddress = ((getDeviceID() < 0x38 )? MPU6050_RA_YA_OFFS_H:0x7A); // MPU6050,MPU9150 Vs MPU6500,MPU9250
+ I2Cdev::readBytes(devAddr, SaveAddress, 2, buffer, I2Cdev::readTimeout, wireObj);
+ return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+void MPU6050_Base::setYAccelOffset(int16_t offset) {
+ uint8_t SaveAddress = ((getDeviceID() < 0x38 )? MPU6050_RA_YA_OFFS_H:0x7A); // MPU6050,MPU9150 Vs MPU6500,MPU9250
+ I2Cdev::writeWord(devAddr, SaveAddress, offset, wireObj);
+}
+
+// ZA_OFFS_* register
+
+int16_t MPU6050_Base::getZAccelOffset() {
+ uint8_t SaveAddress = ((getDeviceID() < 0x38 )? MPU6050_RA_ZA_OFFS_H:0x7D); // MPU6050,MPU9150 Vs MPU6500,MPU9250
+ I2Cdev::readBytes(devAddr, SaveAddress, 2, buffer, I2Cdev::readTimeout, wireObj);
+ return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+void MPU6050_Base::setZAccelOffset(int16_t offset) {
+ uint8_t SaveAddress = ((getDeviceID() < 0x38 )? MPU6050_RA_ZA_OFFS_H:0x7D); // MPU6050,MPU9150 Vs MPU6500,MPU9250
+ I2Cdev::writeWord(devAddr, SaveAddress, offset, wireObj);
+}
+
+// XG_OFFS_USR* registers
+
+int16_t MPU6050_Base::getXGyroOffset() {
+ I2Cdev::readBytes(devAddr, MPU6050_RA_XG_OFFS_USRH, 2, buffer, I2Cdev::readTimeout, wireObj);
+ return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+void MPU6050_Base::setXGyroOffset(int16_t offset) {
+ I2Cdev::writeWord(devAddr, MPU6050_RA_XG_OFFS_USRH, offset, wireObj);
+}
+
+// YG_OFFS_USR* register
+
+int16_t MPU6050_Base::getYGyroOffset() {
+ I2Cdev::readBytes(devAddr, MPU6050_RA_YG_OFFS_USRH, 2, buffer, I2Cdev::readTimeout, wireObj);
+ return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+void MPU6050_Base::setYGyroOffset(int16_t offset) {
+ I2Cdev::writeWord(devAddr, MPU6050_RA_YG_OFFS_USRH, offset, wireObj);
+}
+
+// ZG_OFFS_USR* register
+
+int16_t MPU6050_Base::getZGyroOffset() {
+ I2Cdev::readBytes(devAddr, MPU6050_RA_ZG_OFFS_USRH, 2, buffer, I2Cdev::readTimeout, wireObj);
+ return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+void MPU6050_Base::setZGyroOffset(int16_t offset) {
+ I2Cdev::writeWord(devAddr, MPU6050_RA_ZG_OFFS_USRH, offset, wireObj);
+}
+
+// INT_ENABLE register (DMP functions)
+
+bool MPU6050_Base::getIntPLLReadyEnabled() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_PLL_RDY_INT_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+void MPU6050_Base::setIntPLLReadyEnabled(bool enabled) {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_PLL_RDY_INT_BIT, enabled, wireObj);
+}
+bool MPU6050_Base::getIntDMPEnabled() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_DMP_INT_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+void MPU6050_Base::setIntDMPEnabled(bool enabled) {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_DMP_INT_BIT, enabled, wireObj);
+}
+
+// DMP_INT_STATUS
+
+bool MPU6050_Base::getDMPInt5Status() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_5_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+bool MPU6050_Base::getDMPInt4Status() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_4_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+bool MPU6050_Base::getDMPInt3Status() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_3_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+bool MPU6050_Base::getDMPInt2Status() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_2_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+bool MPU6050_Base::getDMPInt1Status() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_1_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+bool MPU6050_Base::getDMPInt0Status() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_0_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+
+// INT_STATUS register (DMP functions)
+
+bool MPU6050_Base::getIntPLLReadyStatus() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_PLL_RDY_INT_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+bool MPU6050_Base::getIntDMPStatus() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_DMP_INT_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+
+// USER_CTRL register (DMP functions)
+
+bool MPU6050_Base::getDMPEnabled() {
+ I2Cdev::readBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_DMP_EN_BIT, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+void MPU6050_Base::setDMPEnabled(bool enabled) {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_DMP_EN_BIT, enabled, wireObj);
+}
+void MPU6050_Base::resetDMP() {
+ I2Cdev::writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_DMP_RESET_BIT, true, wireObj);
+}
+
+// BANK_SEL register
+
+void MPU6050_Base::setMemoryBank(uint8_t bank, bool prefetchEnabled, bool userBank) {
+ bank &= 0x1F;
+ if (userBank) bank |= 0x20;
+ if (prefetchEnabled) bank |= 0x40;
+ I2Cdev::writeByte(devAddr, MPU6050_RA_BANK_SEL, bank, wireObj);
+}
+
+// MEM_START_ADDR register
+
+void MPU6050_Base::setMemoryStartAddress(uint8_t address) {
+ I2Cdev::writeByte(devAddr, MPU6050_RA_MEM_START_ADDR, address, wireObj);
+}
+
+// MEM_R_W register
+
+uint8_t MPU6050_Base::readMemoryByte() {
+ I2Cdev::readByte(devAddr, MPU6050_RA_MEM_R_W, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+void MPU6050_Base::writeMemoryByte(uint8_t data) {
+ I2Cdev::writeByte(devAddr, MPU6050_RA_MEM_R_W, data, wireObj);
+}
+void MPU6050_Base::readMemoryBlock(uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address) {
+ setMemoryBank(bank);
+ setMemoryStartAddress(address);
+ uint8_t chunkSize;
+ for (uint16_t i = 0; i < dataSize;) {
+ // determine correct chunk size according to bank position and data size
+ chunkSize = MPU6050_DMP_MEMORY_CHUNK_SIZE;
+
+ // make sure we don't go past the data size
+ if (i + chunkSize > dataSize) chunkSize = dataSize - i;
+
+ // make sure this chunk doesn't go past the bank boundary (256 bytes)
+ if (chunkSize > 256 - address) chunkSize = 256 - address;
+
+ // read the chunk of data as specified
+ I2Cdev::readBytes(devAddr, MPU6050_RA_MEM_R_W, chunkSize, data + i, I2Cdev::readTimeout, wireObj);
+
+ // increase byte index by [chunkSize]
+ i += chunkSize;
+
+ // uint8_t automatically wraps to 0 at 256
+ address += chunkSize;
+
+ // if we aren't done, update bank (if necessary) and address
+ if (i < dataSize) {
+ if (address == 0) bank++;
+ setMemoryBank(bank);
+ setMemoryStartAddress(address);
+ }
+ }
+}
+bool MPU6050_Base::writeMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address, bool verify, bool useProgMem) {
+ setMemoryBank(bank);
+ setMemoryStartAddress(address);
+ uint8_t chunkSize;
+ uint8_t *verifyBuffer=0;
+ uint8_t *progBuffer=0;
+ uint16_t i;
+ uint8_t j;
+ if (verify) verifyBuffer = (uint8_t *)malloc(MPU6050_DMP_MEMORY_CHUNK_SIZE);
+ if (useProgMem) progBuffer = (uint8_t *)malloc(MPU6050_DMP_MEMORY_CHUNK_SIZE);
+ for (i = 0; i < dataSize;) {
+ // determine correct chunk size according to bank position and data size
+ chunkSize = MPU6050_DMP_MEMORY_CHUNK_SIZE;
+
+ // make sure we don't go past the data size
+ if (i + chunkSize > dataSize) chunkSize = dataSize - i;
+
+ // make sure this chunk doesn't go past the bank boundary (256 bytes)
+ if (chunkSize > 256 - address) chunkSize = 256 - address;
+
+ if (useProgMem) {
+ // write the chunk of data as specified
+ for (j = 0; j < chunkSize; j++) progBuffer[j] = pgm_read_byte(data + i + j);
+ } else {
+ // write the chunk of data as specified
+ progBuffer = (uint8_t *)data + i;
+ }
+
+ I2Cdev::writeBytes(devAddr, MPU6050_RA_MEM_R_W, chunkSize, progBuffer, wireObj);
+
+ // verify data if needed
+ if (verify && verifyBuffer) {
+ setMemoryBank(bank);
+ setMemoryStartAddress(address);
+ I2Cdev::readBytes(devAddr, MPU6050_RA_MEM_R_W, chunkSize, verifyBuffer, I2Cdev::readTimeout, wireObj);
+ if (memcmp(progBuffer, verifyBuffer, chunkSize) != 0) {
+ /*Serial.print("Block write verification error, bank ");
+ Serial.print(bank, DEC);
+ Serial.print(", address ");
+ Serial.print(address, DEC);
+ Serial.print("!\nExpected:");
+ for (j = 0; j < chunkSize; j++) {
+ Serial.print(" 0x");
+ if (progBuffer[j] < 16) Serial.print("0");
+ Serial.print(progBuffer[j], HEX);
+ }
+ Serial.print("\nReceived:");
+ for (uint8_t j = 0; j < chunkSize; j++) {
+ Serial.print(" 0x");
+ if (verifyBuffer[i + j] < 16) Serial.print("0");
+ Serial.print(verifyBuffer[i + j], HEX);
+ }
+ Serial.print("\n");*/
+ free(verifyBuffer);
+ if (useProgMem) free(progBuffer);
+ return false; // uh oh.
+ }
+ }
+
+ // increase byte index by [chunkSize]
+ i += chunkSize;
+
+ // uint8_t automatically wraps to 0 at 256
+ address += chunkSize;
+
+ // if we aren't done, update bank (if necessary) and address
+ if (i < dataSize) {
+ if (address == 0) bank++;
+ setMemoryBank(bank);
+ setMemoryStartAddress(address);
+ }
+ }
+ if (verify) free(verifyBuffer);
+ if (useProgMem) free(progBuffer);
+ return true;
+}
+bool MPU6050_Base::writeProgMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address, bool verify) {
+ return writeMemoryBlock(data, dataSize, bank, address, verify, true);
+}
+bool MPU6050_Base::writeDMPConfigurationSet(const uint8_t *data, uint16_t dataSize, bool useProgMem) {
+ uint8_t *progBuffer = 0;
+ uint8_t success, special;
+ uint16_t i, j;
+ if (useProgMem) {
+ progBuffer = (uint8_t *)malloc(8); // assume 8-byte blocks, realloc later if necessary
+ }
+
+ // config set data is a long string of blocks with the following structure:
+ // [bank] [offset] [length] [byte[0], byte[1], ..., byte[length]]
+ uint8_t bank, offset, length;
+ for (i = 0; i < dataSize;) {
+ if (useProgMem) {
+ bank = pgm_read_byte(data + i++);
+ offset = pgm_read_byte(data + i++);
+ length = pgm_read_byte(data + i++);
+ } else {
+ bank = data[i++];
+ offset = data[i++];
+ length = data[i++];
+ }
+
+ // write data or perform special action
+ if (length > 0) {
+ // regular block of data to write
+ /*Serial.print("Writing config block to bank ");
+ Serial.print(bank);
+ Serial.print(", offset ");
+ Serial.print(offset);
+ Serial.print(", length=");
+ Serial.println(length);*/
+ if (useProgMem) {
+ if (sizeof(progBuffer) < length) progBuffer = (uint8_t *)realloc(progBuffer, length);
+ for (j = 0; j < length; j++) progBuffer[j] = pgm_read_byte(data + i + j);
+ } else {
+ progBuffer = (uint8_t *)data + i;
+ }
+ success = writeMemoryBlock(progBuffer, length, bank, offset, true);
+ i += length;
+ } else {
+ // special instruction
+ // NOTE: this kind of behavior (what and when to do certain things)
+ // is totally undocumented. This code is in here based on observed
+ // behavior only, and exactly why (or even whether) it has to be here
+ // is anybody's guess for now.
+ if (useProgMem) {
+ special = pgm_read_byte(data + i++);
+ } else {
+ special = data[i++];
+ }
+ /*Serial.print("Special command code ");
+ Serial.print(special, HEX);
+ Serial.println(" found...");*/
+ if (special == 0x01) {
+ // enable DMP-related interrupts
+
+ //setIntZeroMotionEnabled(true);
+ //setIntFIFOBufferOverflowEnabled(true);
+ //setIntDMPEnabled(true);
+ I2Cdev::writeByte(devAddr, MPU6050_RA_INT_ENABLE, 0x32, wireObj); // single operation
+
+ success = true;
+ } else {
+ // unknown special command
+ success = false;
+ }
+ }
+
+ if (!success) {
+ if (useProgMem) free(progBuffer);
+ return false; // uh oh
+ }
+ }
+ if (useProgMem) free(progBuffer);
+ return true;
+}
+bool MPU6050_Base::writeProgDMPConfigurationSet(const uint8_t *data, uint16_t dataSize) {
+ return writeDMPConfigurationSet(data, dataSize, true);
+}
+
+// DMP_CFG_1 register
+
+uint8_t MPU6050_Base::getDMPConfig1() {
+ I2Cdev::readByte(devAddr, MPU6050_RA_DMP_CFG_1, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+void MPU6050_Base::setDMPConfig1(uint8_t config) {
+ I2Cdev::writeByte(devAddr, MPU6050_RA_DMP_CFG_1, config, wireObj);
+}
+
+// DMP_CFG_2 register
+
+uint8_t MPU6050_Base::getDMPConfig2() {
+ I2Cdev::readByte(devAddr, MPU6050_RA_DMP_CFG_2, buffer, I2Cdev::readTimeout, wireObj);
+ return buffer[0];
+}
+void MPU6050_Base::setDMPConfig2(uint8_t config) {
+ I2Cdev::writeByte(devAddr, MPU6050_RA_DMP_CFG_2, config, wireObj);
+}
+
+
+//***************************************************************************************
+//********************** Calibration Routines **********************
+//***************************************************************************************
+/**
+ @brief Fully calibrate Gyro from ZERO in about 6-7 Loops 600-700 readings
+*/
+void MPU6050_Base::CalibrateGyro(uint8_t Loops ) {
+ double kP = 0.3;
+ double kI = 90;
+ float x;
+ x = (100 - map(Loops, 1, 5, 20, 0)) * .01;
+ kP *= x;
+ kI *= x;
+
+ PID( 0x43, kP, kI, Loops);
+}
+
+/**
+ @brief Fully calibrate Accel from ZERO in about 6-7 Loops 600-700 readings
+*/
+void MPU6050_Base::CalibrateAccel(uint8_t Loops ) {
+
+ float kP = 0.3;
+ float kI = 20;
+ float x;
+ x = (100 - map(Loops, 1, 5, 20, 0)) * .01;
+ kP *= x;
+ kI *= x;
+ PID( 0x3B, kP, kI, Loops);
+}
+
+void MPU6050_Base::PID(uint8_t ReadAddress, float kP,float kI, uint8_t Loops){
+ uint8_t SaveAddress = (ReadAddress == 0x3B)?((getDeviceID() < 0x38 )? 0x06:0x77):0x13;
+
+ int16_t Data;
+ float Reading;
+ int16_t BitZero[3];
+ uint8_t shift =(SaveAddress == 0x77)?3:2;
+ float Error, PTerm, ITerm[3];
+ int16_t eSample;
+ uint32_t eSum;
+ uint16_t gravity = 8192; // prevent uninitialized compiler warning
+ if (ReadAddress == 0x3B) gravity = 16384 >> getFullScaleAccelRange();
+ Serial.write('>');
+ for (int i = 0; i < 3; i++) {
+ I2Cdev::readWords(devAddr, SaveAddress + (i * shift), 1, (uint16_t *)&Data, I2Cdev::readTimeout, wireObj); // reads 1 or more 16 bit integers (Word)
+ Reading = Data;
+ if(SaveAddress != 0x13){
+ BitZero[i] = Data & 1; // Capture Bit Zero to properly handle Accelerometer calibration
+ ITerm[i] = ((float)Reading) * 8;
+ } else {
+ ITerm[i] = Reading * 4;
+ }
+ }
+ for (int L = 0; L < Loops; L++) {
+ eSample = 0;
+ for (int c = 0; c < 100; c++) {// 100 PI Calculations
+ eSum = 0;
+ for (int i = 0; i < 3; i++) {
+ I2Cdev::readWords(devAddr, ReadAddress + (i * 2), 1, (uint16_t *)&Data, I2Cdev::readTimeout, wireObj); // reads 1 or more 16 bit integers (Word)
+ Reading = Data;
+ if ((ReadAddress == 0x3B)&&(i == 2)) Reading -= gravity; //remove Gravity
+ Error = -Reading;
+ eSum += abs(Reading);
+ PTerm = kP * Error;
+ ITerm[i] += (Error * 0.001) * kI; // Integral term 1000 Calculations a second = 0.001
+ if(SaveAddress != 0x13){
+ Data = round((PTerm + ITerm[i] ) / 8); //Compute PID Output
+ Data = ((Data)&0xFFFE) |BitZero[i]; // Insert Bit0 Saved at beginning
+ } else Data = round((PTerm + ITerm[i] ) / 4); //Compute PID Output
+ I2Cdev::writeWords(devAddr, SaveAddress + (i * shift), 1, (uint16_t *)&Data, wireObj);
+ }
+ if((c == 99) && eSum > 1000){ // Error is still to great to continue
+ c = 0;
+ Serial.write('*');
+ }
+ if((eSum * ((ReadAddress == 0x3B)?.05: 1)) < 5) eSample++; // Successfully found offsets prepare to advance
+ if((eSum < 100) && (c > 10) && (eSample >= 10)) break; // Advance to next Loop
+ delay(1);
+ }
+ Serial.write('.');
+ kP *= .75;
+ kI *= .75;
+ for (int i = 0; i < 3; i++){
+ if(SaveAddress != 0x13) {
+ Data = round((ITerm[i] ) / 8); //Compute PID Output
+ Data = ((Data)&0xFFFE) |BitZero[i]; // Insert Bit0 Saved at beginning
+ } else Data = round((ITerm[i]) / 4);
+ I2Cdev::writeWords(devAddr, SaveAddress + (i * shift), 1, (uint16_t *)&Data, wireObj);
+ }
+ }
+ resetFIFO();
+ resetDMP();
+}
+
+int16_t * MPU6050_Base::GetActiveOffsets() {
+ uint8_t AOffsetRegister = (getDeviceID() < 0x38 )? MPU6050_RA_XA_OFFS_H:0x77;
+ if(AOffsetRegister == 0x06) I2Cdev::readWords(devAddr, AOffsetRegister, 3, (uint16_t *)offsets, I2Cdev::readTimeout, wireObj);
+ else {
+ I2Cdev::readWords(devAddr, AOffsetRegister, 1, (uint16_t *)offsets, I2Cdev::readTimeout, wireObj);
+ I2Cdev::readWords(devAddr, AOffsetRegister+3, 1, (uint16_t *)(offsets+1), I2Cdev::readTimeout, wireObj);
+ I2Cdev::readWords(devAddr, AOffsetRegister+6, 1, (uint16_t *)(offsets+2), I2Cdev::readTimeout, wireObj);
+ }
+ I2Cdev::readWords(devAddr, 0x13, 3, (uint16_t *)(offsets+3), I2Cdev::readTimeout, wireObj);
+ return offsets;
+}
+
+void MPU6050_Base::PrintActiveOffsets() {
+ GetActiveOffsets();
+ // A_OFFSET_H_READ_A_OFFS(Data);
+ Serial.print((float)offsets[0], 5); Serial.print(",\t");
+ Serial.print((float)offsets[1], 5); Serial.print(",\t");
+ Serial.print((float)offsets[2], 5); Serial.print(",\t");
+
+ // XG_OFFSET_H_READ_OFFS_USR(Data);
+ Serial.print((float)offsets[3], 5); Serial.print(",\t");
+ Serial.print((float)offsets[4], 5); Serial.print(",\t");
+ Serial.print((float)offsets[5], 5); Serial.print("\n\n");
+}
\ No newline at end of file
diff --git a/lib/MPU6050/src/MPU6050.h b/lib/MPU6050/src/MPU6050.h
new file mode 100644
index 0000000..b8e6a3e
--- /dev/null
+++ b/lib/MPU6050/src/MPU6050.h
@@ -0,0 +1,874 @@
+// I2Cdev library collection - MPU6050 I2C device class
+// Based on InvenSense MPU-6050 register map document rev. 2.0, 5/19/2011 (RM-MPU-6000A-00)
+// 10/3/2011 by Jeff Rowberg
+// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
+//
+// Changelog:
+// 2021/09/27 - split implementations out of header files, finally
+// ... - ongoing debug release
+
+// NOTE: THIS IS ONLY A PARIAL RELEASE. THIS DEVICE CLASS IS CURRENTLY UNDERGOING ACTIVE
+// DEVELOPMENT AND IS STILL MISSING SOME IMPORTANT FEATURES. PLEASE KEEP THIS IN MIND IF
+// YOU DECIDE TO USE THIS PARTICULAR CODE FOR ANYTHING.
+
+/* ============================================
+I2Cdev device library code is placed under the MIT license
+Copyright (c) 2012 Jeff Rowberg
+
+Permission is hereby granted, free of charge, to any person obtaining a copy
+of this software and associated documentation files (the "Software"), to deal
+in the Software without restriction, including without limitation the rights
+to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+copies of the Software, and to permit persons to whom the Software is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in
+all copies or substantial portions of the Software.
+
+THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+THE SOFTWARE.
+===============================================
+*/
+
+#ifndef _MPU6050_H_
+#define _MPU6050_H_
+
+#include "I2Cdev.h"
+#include "helper_3dmath.h"
+
+// supporting link: http://forum.arduino.cc/index.php?&topic=143444.msg1079517#msg1079517
+// also: http://forum.arduino.cc/index.php?&topic=141571.msg1062899#msg1062899s
+
+#ifdef __AVR__
+#include
+#elif defined(ESP32)
+ #include
+#else
+//#define PROGMEM /* empty */
+//#define pgm_read_byte(x) (*(x))
+//#define pgm_read_word(x) (*(x))
+//#define pgm_read_float(x) (*(x))
+//#define PSTR(STR) STR
+#endif
+
+
+#define MPU6050_ADDRESS_AD0_LOW 0x68 // address pin low (GND), default for InvenSense evaluation board
+#define MPU6050_ADDRESS_AD0_HIGH 0x69 // address pin high (VCC)
+#define MPU6050_DEFAULT_ADDRESS MPU6050_ADDRESS_AD0_LOW
+
+#define MPU6050_RA_XG_OFFS_TC 0x00 //[7] PWR_MODE, [6:1] XG_OFFS_TC, [0] OTP_BNK_VLD
+#define MPU6050_RA_YG_OFFS_TC 0x01 //[7] PWR_MODE, [6:1] YG_OFFS_TC, [0] OTP_BNK_VLD
+#define MPU6050_RA_ZG_OFFS_TC 0x02 //[7] PWR_MODE, [6:1] ZG_OFFS_TC, [0] OTP_BNK_VLD
+#define MPU6050_RA_X_FINE_GAIN 0x03 //[7:0] X_FINE_GAIN
+#define MPU6050_RA_Y_FINE_GAIN 0x04 //[7:0] Y_FINE_GAIN
+#define MPU6050_RA_Z_FINE_GAIN 0x05 //[7:0] Z_FINE_GAIN
+#define MPU6050_RA_XA_OFFS_H 0x06 //[15:0] XA_OFFS
+#define MPU6050_RA_XA_OFFS_L_TC 0x07
+#define MPU6050_RA_YA_OFFS_H 0x08 //[15:0] YA_OFFS
+#define MPU6050_RA_YA_OFFS_L_TC 0x09
+#define MPU6050_RA_ZA_OFFS_H 0x0A //[15:0] ZA_OFFS
+#define MPU6050_RA_ZA_OFFS_L_TC 0x0B
+#define MPU6050_RA_SELF_TEST_X 0x0D //[7:5] XA_TEST[4-2], [4:0] XG_TEST[4-0]
+#define MPU6050_RA_SELF_TEST_Y 0x0E //[7:5] YA_TEST[4-2], [4:0] YG_TEST[4-0]
+#define MPU6050_RA_SELF_TEST_Z 0x0F //[7:5] ZA_TEST[4-2], [4:0] ZG_TEST[4-0]
+#define MPU6050_RA_SELF_TEST_A 0x10 //[5:4] XA_TEST[1-0], [3:2] YA_TEST[1-0], [1:0] ZA_TEST[1-0]
+#define MPU6050_RA_XG_OFFS_USRH 0x13 //[15:0] XG_OFFS_USR
+#define MPU6050_RA_XG_OFFS_USRL 0x14
+#define MPU6050_RA_YG_OFFS_USRH 0x15 //[15:0] YG_OFFS_USR
+#define MPU6050_RA_YG_OFFS_USRL 0x16
+#define MPU6050_RA_ZG_OFFS_USRH 0x17 //[15:0] ZG_OFFS_USR
+#define MPU6050_RA_ZG_OFFS_USRL 0x18
+#define MPU6050_RA_SMPLRT_DIV 0x19
+#define MPU6050_RA_CONFIG 0x1A
+#define MPU6050_RA_GYRO_CONFIG 0x1B
+#define MPU6050_RA_ACCEL_CONFIG 0x1C
+#define MPU6050_RA_FF_THR 0x1D
+#define MPU6050_RA_FF_DUR 0x1E
+#define MPU6050_RA_MOT_THR 0x1F
+#define MPU6050_RA_MOT_DUR 0x20
+#define MPU6050_RA_ZRMOT_THR 0x21
+#define MPU6050_RA_ZRMOT_DUR 0x22
+#define MPU6050_RA_FIFO_EN 0x23
+#define MPU6050_RA_I2C_MST_CTRL 0x24
+#define MPU6050_RA_I2C_SLV0_ADDR 0x25
+#define MPU6050_RA_I2C_SLV0_REG 0x26
+#define MPU6050_RA_I2C_SLV0_CTRL 0x27
+#define MPU6050_RA_I2C_SLV1_ADDR 0x28
+#define MPU6050_RA_I2C_SLV1_REG 0x29
+#define MPU6050_RA_I2C_SLV1_CTRL 0x2A
+#define MPU6050_RA_I2C_SLV2_ADDR 0x2B
+#define MPU6050_RA_I2C_SLV2_REG 0x2C
+#define MPU6050_RA_I2C_SLV2_CTRL 0x2D
+#define MPU6050_RA_I2C_SLV3_ADDR 0x2E
+#define MPU6050_RA_I2C_SLV3_REG 0x2F
+#define MPU6050_RA_I2C_SLV3_CTRL 0x30
+#define MPU6050_RA_I2C_SLV4_ADDR 0x31
+#define MPU6050_RA_I2C_SLV4_REG 0x32
+#define MPU6050_RA_I2C_SLV4_DO 0x33
+#define MPU6050_RA_I2C_SLV4_CTRL 0x34
+#define MPU6050_RA_I2C_SLV4_DI 0x35
+#define MPU6050_RA_I2C_MST_STATUS 0x36
+#define MPU6050_RA_INT_PIN_CFG 0x37
+#define MPU6050_RA_INT_ENABLE 0x38
+#define MPU6050_RA_DMP_INT_STATUS 0x39
+#define MPU6050_RA_INT_STATUS 0x3A
+#define MPU6050_RA_ACCEL_XOUT_H 0x3B
+#define MPU6050_RA_ACCEL_XOUT_L 0x3C
+#define MPU6050_RA_ACCEL_YOUT_H 0x3D
+#define MPU6050_RA_ACCEL_YOUT_L 0x3E
+#define MPU6050_RA_ACCEL_ZOUT_H 0x3F
+#define MPU6050_RA_ACCEL_ZOUT_L 0x40
+#define MPU6050_RA_TEMP_OUT_H 0x41
+#define MPU6050_RA_TEMP_OUT_L 0x42
+#define MPU6050_RA_GYRO_XOUT_H 0x43
+#define MPU6050_RA_GYRO_XOUT_L 0x44
+#define MPU6050_RA_GYRO_YOUT_H 0x45
+#define MPU6050_RA_GYRO_YOUT_L 0x46
+#define MPU6050_RA_GYRO_ZOUT_H 0x47
+#define MPU6050_RA_GYRO_ZOUT_L 0x48
+#define MPU6050_RA_EXT_SENS_DATA_00 0x49
+#define MPU6050_RA_EXT_SENS_DATA_01 0x4A
+#define MPU6050_RA_EXT_SENS_DATA_02 0x4B
+#define MPU6050_RA_EXT_SENS_DATA_03 0x4C
+#define MPU6050_RA_EXT_SENS_DATA_04 0x4D
+#define MPU6050_RA_EXT_SENS_DATA_05 0x4E
+#define MPU6050_RA_EXT_SENS_DATA_06 0x4F
+#define MPU6050_RA_EXT_SENS_DATA_07 0x50
+#define MPU6050_RA_EXT_SENS_DATA_08 0x51
+#define MPU6050_RA_EXT_SENS_DATA_09 0x52
+#define MPU6050_RA_EXT_SENS_DATA_10 0x53
+#define MPU6050_RA_EXT_SENS_DATA_11 0x54
+#define MPU6050_RA_EXT_SENS_DATA_12 0x55
+#define MPU6050_RA_EXT_SENS_DATA_13 0x56
+#define MPU6050_RA_EXT_SENS_DATA_14 0x57
+#define MPU6050_RA_EXT_SENS_DATA_15 0x58
+#define MPU6050_RA_EXT_SENS_DATA_16 0x59
+#define MPU6050_RA_EXT_SENS_DATA_17 0x5A
+#define MPU6050_RA_EXT_SENS_DATA_18 0x5B
+#define MPU6050_RA_EXT_SENS_DATA_19 0x5C
+#define MPU6050_RA_EXT_SENS_DATA_20 0x5D
+#define MPU6050_RA_EXT_SENS_DATA_21 0x5E
+#define MPU6050_RA_EXT_SENS_DATA_22 0x5F
+#define MPU6050_RA_EXT_SENS_DATA_23 0x60
+#define MPU6050_RA_MOT_DETECT_STATUS 0x61
+#define MPU6050_RA_I2C_SLV0_DO 0x63
+#define MPU6050_RA_I2C_SLV1_DO 0x64
+#define MPU6050_RA_I2C_SLV2_DO 0x65
+#define MPU6050_RA_I2C_SLV3_DO 0x66
+#define MPU6050_RA_I2C_MST_DELAY_CTRL 0x67
+#define MPU6050_RA_SIGNAL_PATH_RESET 0x68
+#define MPU6050_RA_MOT_DETECT_CTRL 0x69
+#define MPU6050_RA_USER_CTRL 0x6A
+#define MPU6050_RA_PWR_MGMT_1 0x6B
+#define MPU6050_RA_PWR_MGMT_2 0x6C
+#define MPU6050_RA_BANK_SEL 0x6D
+#define MPU6050_RA_MEM_START_ADDR 0x6E
+#define MPU6050_RA_MEM_R_W 0x6F
+#define MPU6050_RA_DMP_CFG_1 0x70
+#define MPU6050_RA_DMP_CFG_2 0x71
+#define MPU6050_RA_FIFO_COUNTH 0x72
+#define MPU6050_RA_FIFO_COUNTL 0x73
+#define MPU6050_RA_FIFO_R_W 0x74
+#define MPU6050_RA_WHO_AM_I 0x75
+
+#define MPU6050_SELF_TEST_XA_1_BIT 0x07
+#define MPU6050_SELF_TEST_XA_1_LENGTH 0x03
+#define MPU6050_SELF_TEST_XA_2_BIT 0x05
+#define MPU6050_SELF_TEST_XA_2_LENGTH 0x02
+#define MPU6050_SELF_TEST_YA_1_BIT 0x07
+#define MPU6050_SELF_TEST_YA_1_LENGTH 0x03
+#define MPU6050_SELF_TEST_YA_2_BIT 0x03
+#define MPU6050_SELF_TEST_YA_2_LENGTH 0x02
+#define MPU6050_SELF_TEST_ZA_1_BIT 0x07
+#define MPU6050_SELF_TEST_ZA_1_LENGTH 0x03
+#define MPU6050_SELF_TEST_ZA_2_BIT 0x01
+#define MPU6050_SELF_TEST_ZA_2_LENGTH 0x02
+
+#define MPU6050_SELF_TEST_XG_1_BIT 0x04
+#define MPU6050_SELF_TEST_XG_1_LENGTH 0x05
+#define MPU6050_SELF_TEST_YG_1_BIT 0x04
+#define MPU6050_SELF_TEST_YG_1_LENGTH 0x05
+#define MPU6050_SELF_TEST_ZG_1_BIT 0x04
+#define MPU6050_SELF_TEST_ZG_1_LENGTH 0x05
+
+#define MPU6050_TC_PWR_MODE_BIT 7
+#define MPU6050_TC_OFFSET_BIT 6
+#define MPU6050_TC_OFFSET_LENGTH 6
+#define MPU6050_TC_OTP_BNK_VLD_BIT 0
+
+#define MPU6050_VDDIO_LEVEL_VLOGIC 0
+#define MPU6050_VDDIO_LEVEL_VDD 1
+
+#define MPU6050_CFG_EXT_SYNC_SET_BIT 5
+#define MPU6050_CFG_EXT_SYNC_SET_LENGTH 3
+#define MPU6050_CFG_DLPF_CFG_BIT 2
+#define MPU6050_CFG_DLPF_CFG_LENGTH 3
+
+#define MPU6050_EXT_SYNC_DISABLED 0x0
+#define MPU6050_EXT_SYNC_TEMP_OUT_L 0x1
+#define MPU6050_EXT_SYNC_GYRO_XOUT_L 0x2
+#define MPU6050_EXT_SYNC_GYRO_YOUT_L 0x3
+#define MPU6050_EXT_SYNC_GYRO_ZOUT_L 0x4
+#define MPU6050_EXT_SYNC_ACCEL_XOUT_L 0x5
+#define MPU6050_EXT_SYNC_ACCEL_YOUT_L 0x6
+#define MPU6050_EXT_SYNC_ACCEL_ZOUT_L 0x7
+
+#define MPU6050_DLPF_BW_256 0x00
+#define MPU6050_DLPF_BW_188 0x01
+#define MPU6050_DLPF_BW_98 0x02
+#define MPU6050_DLPF_BW_42 0x03
+#define MPU6050_DLPF_BW_20 0x04
+#define MPU6050_DLPF_BW_10 0x05
+#define MPU6050_DLPF_BW_5 0x06
+
+#define MPU6050_GCONFIG_FS_SEL_BIT 4
+#define MPU6050_GCONFIG_FS_SEL_LENGTH 2
+
+#define MPU6050_GYRO_FS_250 0x00
+#define MPU6050_GYRO_FS_500 0x01
+#define MPU6050_GYRO_FS_1000 0x02
+#define MPU6050_GYRO_FS_2000 0x03
+
+#define MPU6050_ACONFIG_XA_ST_BIT 7
+#define MPU6050_ACONFIG_YA_ST_BIT 6
+#define MPU6050_ACONFIG_ZA_ST_BIT 5
+#define MPU6050_ACONFIG_AFS_SEL_BIT 4
+#define MPU6050_ACONFIG_AFS_SEL_LENGTH 2
+#define MPU6050_ACONFIG_ACCEL_HPF_BIT 2
+#define MPU6050_ACONFIG_ACCEL_HPF_LENGTH 3
+
+#define MPU6050_ACCEL_FS_2 0x00
+#define MPU6050_ACCEL_FS_4 0x01
+#define MPU6050_ACCEL_FS_8 0x02
+#define MPU6050_ACCEL_FS_16 0x03
+
+#define MPU6050_DHPF_RESET 0x00
+#define MPU6050_DHPF_5 0x01
+#define MPU6050_DHPF_2P5 0x02
+#define MPU6050_DHPF_1P25 0x03
+#define MPU6050_DHPF_0P63 0x04
+#define MPU6050_DHPF_HOLD 0x07
+
+#define MPU6050_TEMP_FIFO_EN_BIT 7
+#define MPU6050_XG_FIFO_EN_BIT 6
+#define MPU6050_YG_FIFO_EN_BIT 5
+#define MPU6050_ZG_FIFO_EN_BIT 4
+#define MPU6050_ACCEL_FIFO_EN_BIT 3
+#define MPU6050_SLV2_FIFO_EN_BIT 2
+#define MPU6050_SLV1_FIFO_EN_BIT 1
+#define MPU6050_SLV0_FIFO_EN_BIT 0
+
+#define MPU6050_MULT_MST_EN_BIT 7
+#define MPU6050_WAIT_FOR_ES_BIT 6
+#define MPU6050_SLV_3_FIFO_EN_BIT 5
+#define MPU6050_I2C_MST_P_NSR_BIT 4
+#define MPU6050_I2C_MST_CLK_BIT 3
+#define MPU6050_I2C_MST_CLK_LENGTH 4
+
+#define MPU6050_CLOCK_DIV_348 0x0
+#define MPU6050_CLOCK_DIV_333 0x1
+#define MPU6050_CLOCK_DIV_320 0x2
+#define MPU6050_CLOCK_DIV_308 0x3
+#define MPU6050_CLOCK_DIV_296 0x4
+#define MPU6050_CLOCK_DIV_286 0x5
+#define MPU6050_CLOCK_DIV_276 0x6
+#define MPU6050_CLOCK_DIV_267 0x7
+#define MPU6050_CLOCK_DIV_258 0x8
+#define MPU6050_CLOCK_DIV_500 0x9
+#define MPU6050_CLOCK_DIV_471 0xA
+#define MPU6050_CLOCK_DIV_444 0xB
+#define MPU6050_CLOCK_DIV_421 0xC
+#define MPU6050_CLOCK_DIV_400 0xD
+#define MPU6050_CLOCK_DIV_381 0xE
+#define MPU6050_CLOCK_DIV_364 0xF
+
+#define MPU6050_I2C_SLV_RW_BIT 7
+#define MPU6050_I2C_SLV_ADDR_BIT 6
+#define MPU6050_I2C_SLV_ADDR_LENGTH 7
+#define MPU6050_I2C_SLV_EN_BIT 7
+#define MPU6050_I2C_SLV_BYTE_SW_BIT 6
+#define MPU6050_I2C_SLV_REG_DIS_BIT 5
+#define MPU6050_I2C_SLV_GRP_BIT 4
+#define MPU6050_I2C_SLV_LEN_BIT 3
+#define MPU6050_I2C_SLV_LEN_LENGTH 4
+
+#define MPU6050_I2C_SLV4_RW_BIT 7
+#define MPU6050_I2C_SLV4_ADDR_BIT 6
+#define MPU6050_I2C_SLV4_ADDR_LENGTH 7
+#define MPU6050_I2C_SLV4_EN_BIT 7
+#define MPU6050_I2C_SLV4_INT_EN_BIT 6
+#define MPU6050_I2C_SLV4_REG_DIS_BIT 5
+#define MPU6050_I2C_SLV4_MST_DLY_BIT 4
+#define MPU6050_I2C_SLV4_MST_DLY_LENGTH 5
+
+#define MPU6050_MST_PASS_THROUGH_BIT 7
+#define MPU6050_MST_I2C_SLV4_DONE_BIT 6
+#define MPU6050_MST_I2C_LOST_ARB_BIT 5
+#define MPU6050_MST_I2C_SLV4_NACK_BIT 4
+#define MPU6050_MST_I2C_SLV3_NACK_BIT 3
+#define MPU6050_MST_I2C_SLV2_NACK_BIT 2
+#define MPU6050_MST_I2C_SLV1_NACK_BIT 1
+#define MPU6050_MST_I2C_SLV0_NACK_BIT 0
+
+#define MPU6050_INTCFG_INT_LEVEL_BIT 7
+#define MPU6050_INTCFG_INT_OPEN_BIT 6
+#define MPU6050_INTCFG_LATCH_INT_EN_BIT 5
+#define MPU6050_INTCFG_INT_RD_CLEAR_BIT 4
+#define MPU6050_INTCFG_FSYNC_INT_LEVEL_BIT 3
+#define MPU6050_INTCFG_FSYNC_INT_EN_BIT 2
+#define MPU6050_INTCFG_I2C_BYPASS_EN_BIT 1
+#define MPU6050_INTCFG_CLKOUT_EN_BIT 0
+
+#define MPU6050_INTMODE_ACTIVEHIGH 0x00
+#define MPU6050_INTMODE_ACTIVELOW 0x01
+
+#define MPU6050_INTDRV_PUSHPULL 0x00
+#define MPU6050_INTDRV_OPENDRAIN 0x01
+
+#define MPU6050_INTLATCH_50USPULSE 0x00
+#define MPU6050_INTLATCH_WAITCLEAR 0x01
+
+#define MPU6050_INTCLEAR_STATUSREAD 0x00
+#define MPU6050_INTCLEAR_ANYREAD 0x01
+
+#define MPU6050_INTERRUPT_FF_BIT 7
+#define MPU6050_INTERRUPT_MOT_BIT 6
+#define MPU6050_INTERRUPT_ZMOT_BIT 5
+#define MPU6050_INTERRUPT_FIFO_OFLOW_BIT 4
+#define MPU6050_INTERRUPT_I2C_MST_INT_BIT 3
+#define MPU6050_INTERRUPT_PLL_RDY_INT_BIT 2
+#define MPU6050_INTERRUPT_DMP_INT_BIT 1
+#define MPU6050_INTERRUPT_DATA_RDY_BIT 0
+
+// TODO: figure out what these actually do
+// UMPL source code is not very obivous
+#define MPU6050_DMPINT_5_BIT 5
+#define MPU6050_DMPINT_4_BIT 4
+#define MPU6050_DMPINT_3_BIT 3
+#define MPU6050_DMPINT_2_BIT 2
+#define MPU6050_DMPINT_1_BIT 1
+#define MPU6050_DMPINT_0_BIT 0
+
+#define MPU6050_MOTION_MOT_XNEG_BIT 7
+#define MPU6050_MOTION_MOT_XPOS_BIT 6
+#define MPU6050_MOTION_MOT_YNEG_BIT 5
+#define MPU6050_MOTION_MOT_YPOS_BIT 4
+#define MPU6050_MOTION_MOT_ZNEG_BIT 3
+#define MPU6050_MOTION_MOT_ZPOS_BIT 2
+#define MPU6050_MOTION_MOT_ZRMOT_BIT 0
+
+#define MPU6050_DELAYCTRL_DELAY_ES_SHADOW_BIT 7
+#define MPU6050_DELAYCTRL_I2C_SLV4_DLY_EN_BIT 4
+#define MPU6050_DELAYCTRL_I2C_SLV3_DLY_EN_BIT 3
+#define MPU6050_DELAYCTRL_I2C_SLV2_DLY_EN_BIT 2
+#define MPU6050_DELAYCTRL_I2C_SLV1_DLY_EN_BIT 1
+#define MPU6050_DELAYCTRL_I2C_SLV0_DLY_EN_BIT 0
+
+#define MPU6050_PATHRESET_GYRO_RESET_BIT 2
+#define MPU6050_PATHRESET_ACCEL_RESET_BIT 1
+#define MPU6050_PATHRESET_TEMP_RESET_BIT 0
+
+#define MPU6050_DETECT_ACCEL_ON_DELAY_BIT 5
+#define MPU6050_DETECT_ACCEL_ON_DELAY_LENGTH 2
+#define MPU6050_DETECT_FF_COUNT_BIT 3
+#define MPU6050_DETECT_FF_COUNT_LENGTH 2
+#define MPU6050_DETECT_MOT_COUNT_BIT 1
+#define MPU6050_DETECT_MOT_COUNT_LENGTH 2
+
+#define MPU6050_DETECT_DECREMENT_RESET 0x0
+#define MPU6050_DETECT_DECREMENT_1 0x1
+#define MPU6050_DETECT_DECREMENT_2 0x2
+#define MPU6050_DETECT_DECREMENT_4 0x3
+
+#define MPU6050_USERCTRL_DMP_EN_BIT 7
+#define MPU6050_USERCTRL_FIFO_EN_BIT 6
+#define MPU6050_USERCTRL_I2C_MST_EN_BIT 5
+#define MPU6050_USERCTRL_I2C_IF_DIS_BIT 4
+#define MPU6050_USERCTRL_DMP_RESET_BIT 3
+#define MPU6050_USERCTRL_FIFO_RESET_BIT 2
+#define MPU6050_USERCTRL_I2C_MST_RESET_BIT 1
+#define MPU6050_USERCTRL_SIG_COND_RESET_BIT 0
+
+#define MPU6050_PWR1_DEVICE_RESET_BIT 7
+#define MPU6050_PWR1_SLEEP_BIT 6
+#define MPU6050_PWR1_CYCLE_BIT 5
+#define MPU6050_PWR1_TEMP_DIS_BIT 3
+#define MPU6050_PWR1_CLKSEL_BIT 2
+#define MPU6050_PWR1_CLKSEL_LENGTH 3
+
+#define MPU6050_CLOCK_INTERNAL 0x00
+#define MPU6050_CLOCK_PLL_XGYRO 0x01
+#define MPU6050_CLOCK_PLL_YGYRO 0x02
+#define MPU6050_CLOCK_PLL_ZGYRO 0x03
+#define MPU6050_CLOCK_PLL_EXT32K 0x04
+#define MPU6050_CLOCK_PLL_EXT19M 0x05
+#define MPU6050_CLOCK_KEEP_RESET 0x07
+
+#define MPU6050_PWR2_LP_WAKE_CTRL_BIT 7
+#define MPU6050_PWR2_LP_WAKE_CTRL_LENGTH 2
+#define MPU6050_PWR2_STBY_XA_BIT 5
+#define MPU6050_PWR2_STBY_YA_BIT 4
+#define MPU6050_PWR2_STBY_ZA_BIT 3
+#define MPU6050_PWR2_STBY_XG_BIT 2
+#define MPU6050_PWR2_STBY_YG_BIT 1
+#define MPU6050_PWR2_STBY_ZG_BIT 0
+
+#define MPU6050_WAKE_FREQ_1P25 0x0
+#define MPU6050_WAKE_FREQ_2P5 0x1
+#define MPU6050_WAKE_FREQ_5 0x2
+#define MPU6050_WAKE_FREQ_10 0x3
+
+#define MPU6050_BANKSEL_PRFTCH_EN_BIT 6
+#define MPU6050_BANKSEL_CFG_USER_BANK_BIT 5
+#define MPU6050_BANKSEL_MEM_SEL_BIT 4
+#define MPU6050_BANKSEL_MEM_SEL_LENGTH 5
+
+#define MPU6050_WHO_AM_I_BIT 6
+#define MPU6050_WHO_AM_I_LENGTH 6
+
+#define MPU6050_DMP_MEMORY_BANKS 8
+#define MPU6050_DMP_MEMORY_BANK_SIZE 256
+#define MPU6050_DMP_MEMORY_CHUNK_SIZE 16
+
+#define MPU6050_FIFO_DEFAULT_TIMEOUT 11000
+
+enum class ACCEL_FS {
+ A2G,
+ A4G,
+ A8G,
+ A16G
+};
+
+enum class GYRO_FS {
+ G250DPS,
+ G500DPS,
+ G1000DPS,
+ G2000DPS
+};
+
+class MPU6050_Base {
+ public:
+ MPU6050_Base(uint8_t address=MPU6050_DEFAULT_ADDRESS, void *wireObj=0);
+
+ void initialize();
+ void initialize(ACCEL_FS accelRange, GYRO_FS gyroRange);
+
+ float get_acce_resolution();
+ float get_gyro_resolution();
+
+ bool testConnection();
+
+ // AUX_VDDIO register
+ uint8_t getAuxVDDIOLevel();
+ void setAuxVDDIOLevel(uint8_t level);
+
+ // SMPLRT_DIV register
+ uint8_t getRate();
+ void setRate(uint8_t rate);
+
+ // CONFIG register
+ uint8_t getExternalFrameSync();
+ void setExternalFrameSync(uint8_t sync);
+ uint8_t getDLPFMode();
+ void setDLPFMode(uint8_t bandwidth);
+
+ // GYRO_CONFIG register
+ uint8_t getFullScaleGyroRange();
+ void setFullScaleGyroRange(uint8_t range);
+
+ // SELF_TEST registers
+ uint8_t getAccelXSelfTestFactoryTrim();
+ uint8_t getAccelYSelfTestFactoryTrim();
+ uint8_t getAccelZSelfTestFactoryTrim();
+
+ uint8_t getGyroXSelfTestFactoryTrim();
+ uint8_t getGyroYSelfTestFactoryTrim();
+ uint8_t getGyroZSelfTestFactoryTrim();
+
+ // ACCEL_CONFIG register
+ bool getAccelXSelfTest();
+ void setAccelXSelfTest(bool enabled);
+ bool getAccelYSelfTest();
+ void setAccelYSelfTest(bool enabled);
+ bool getAccelZSelfTest();
+ void setAccelZSelfTest(bool enabled);
+ uint8_t getFullScaleAccelRange();
+ void setFullScaleAccelRange(uint8_t range);
+ uint8_t getDHPFMode();
+ void setDHPFMode(uint8_t mode);
+
+ // FF_THR register
+ uint8_t getFreefallDetectionThreshold();
+ void setFreefallDetectionThreshold(uint8_t threshold);
+
+ // FF_DUR register
+ uint8_t getFreefallDetectionDuration();
+ void setFreefallDetectionDuration(uint8_t duration);
+
+ // MOT_THR register
+ uint8_t getMotionDetectionThreshold();
+ void setMotionDetectionThreshold(uint8_t threshold);
+
+ // MOT_DUR register
+ uint8_t getMotionDetectionDuration();
+ void setMotionDetectionDuration(uint8_t duration);
+
+ // ZRMOT_THR register
+ uint8_t getZeroMotionDetectionThreshold();
+ void setZeroMotionDetectionThreshold(uint8_t threshold);
+
+ // ZRMOT_DUR register
+ uint8_t getZeroMotionDetectionDuration();
+ void setZeroMotionDetectionDuration(uint8_t duration);
+
+ // FIFO_EN register
+ bool getTempFIFOEnabled();
+ void setTempFIFOEnabled(bool enabled);
+ bool getXGyroFIFOEnabled();
+ void setXGyroFIFOEnabled(bool enabled);
+ bool getYGyroFIFOEnabled();
+ void setYGyroFIFOEnabled(bool enabled);
+ bool getZGyroFIFOEnabled();
+ void setZGyroFIFOEnabled(bool enabled);
+ bool getAccelFIFOEnabled();
+ void setAccelFIFOEnabled(bool enabled);
+ bool getSlave2FIFOEnabled();
+ void setSlave2FIFOEnabled(bool enabled);
+ bool getSlave1FIFOEnabled();
+ void setSlave1FIFOEnabled(bool enabled);
+ bool getSlave0FIFOEnabled();
+ void setSlave0FIFOEnabled(bool enabled);
+
+ // I2C_MST_CTRL register
+ bool getMultiMasterEnabled();
+ void setMultiMasterEnabled(bool enabled);
+ bool getWaitForExternalSensorEnabled();
+ void setWaitForExternalSensorEnabled(bool enabled);
+ bool getSlave3FIFOEnabled();
+ void setSlave3FIFOEnabled(bool enabled);
+ bool getSlaveReadWriteTransitionEnabled();
+ void setSlaveReadWriteTransitionEnabled(bool enabled);
+ uint8_t getMasterClockSpeed();
+ void setMasterClockSpeed(uint8_t speed);
+
+ // I2C_SLV* registers (Slave 0-3)
+ uint8_t getSlaveAddress(uint8_t num);
+ void setSlaveAddress(uint8_t num, uint8_t address);
+ uint8_t getSlaveRegister(uint8_t num);
+ void setSlaveRegister(uint8_t num, uint8_t reg);
+ bool getSlaveEnabled(uint8_t num);
+ void setSlaveEnabled(uint8_t num, bool enabled);
+ bool getSlaveWordByteSwap(uint8_t num);
+ void setSlaveWordByteSwap(uint8_t num, bool enabled);
+ bool getSlaveWriteMode(uint8_t num);
+ void setSlaveWriteMode(uint8_t num, bool mode);
+ bool getSlaveWordGroupOffset(uint8_t num);
+ void setSlaveWordGroupOffset(uint8_t num, bool enabled);
+ uint8_t getSlaveDataLength(uint8_t num);
+ void setSlaveDataLength(uint8_t num, uint8_t length);
+
+ // I2C_SLV* registers (Slave 4)
+ uint8_t getSlave4Address();
+ void setSlave4Address(uint8_t address);
+ uint8_t getSlave4Register();
+ void setSlave4Register(uint8_t reg);
+ void setSlave4OutputByte(uint8_t data);
+ bool getSlave4Enabled();
+ void setSlave4Enabled(bool enabled);
+ bool getSlave4InterruptEnabled();
+ void setSlave4InterruptEnabled(bool enabled);
+ bool getSlave4WriteMode();
+ void setSlave4WriteMode(bool mode);
+ uint8_t getSlave4MasterDelay();
+ void setSlave4MasterDelay(uint8_t delay);
+ uint8_t getSlate4InputByte();
+
+ // I2C_MST_STATUS register
+ bool getPassthroughStatus();
+ bool getSlave4IsDone();
+ bool getLostArbitration();
+ bool getSlave4Nack();
+ bool getSlave3Nack();
+ bool getSlave2Nack();
+ bool getSlave1Nack();
+ bool getSlave0Nack();
+
+ // INT_PIN_CFG register
+ bool getInterruptMode();
+ void setInterruptMode(bool mode);
+ bool getInterruptDrive();
+ void setInterruptDrive(bool drive);
+ bool getInterruptLatch();
+ void setInterruptLatch(bool latch);
+ bool getInterruptLatchClear();
+ void setInterruptLatchClear(bool clear);
+ bool getFSyncInterruptLevel();
+ void setFSyncInterruptLevel(bool level);
+ bool getFSyncInterruptEnabled();
+ void setFSyncInterruptEnabled(bool enabled);
+ bool getI2CBypassEnabled();
+ void setI2CBypassEnabled(bool enabled);
+ bool getClockOutputEnabled();
+ void setClockOutputEnabled(bool enabled);
+
+ // INT_ENABLE register
+ uint8_t getIntEnabled();
+ void setIntEnabled(uint8_t enabled);
+ bool getIntFreefallEnabled();
+ void setIntFreefallEnabled(bool enabled);
+ bool getIntMotionEnabled();
+ void setIntMotionEnabled(bool enabled);
+ bool getIntZeroMotionEnabled();
+ void setIntZeroMotionEnabled(bool enabled);
+ bool getIntFIFOBufferOverflowEnabled();
+ void setIntFIFOBufferOverflowEnabled(bool enabled);
+ bool getIntI2CMasterEnabled();
+ void setIntI2CMasterEnabled(bool enabled);
+ bool getIntDataReadyEnabled();
+ void setIntDataReadyEnabled(bool enabled);
+
+ // INT_STATUS register
+ uint8_t getIntStatus();
+ bool getIntFreefallStatus();
+ bool getIntMotionStatus();
+ bool getIntZeroMotionStatus();
+ bool getIntFIFOBufferOverflowStatus();
+ bool getIntI2CMasterStatus();
+ bool getIntDataReadyStatus();
+
+ // ACCEL_*OUT_* registers
+ void getMotion9(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz, int16_t* mx, int16_t* my, int16_t* mz);
+ void getMotion6(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz);
+ void getAcceleration(int16_t* x, int16_t* y, int16_t* z);
+ int16_t getAccelerationX();
+ int16_t getAccelerationY();
+ int16_t getAccelerationZ();
+
+ // TEMP_OUT_* registers
+ int16_t getTemperature();
+
+ // GYRO_*OUT_* registers
+ void getRotation(int16_t* x, int16_t* y, int16_t* z);
+ int16_t getRotationX();
+ int16_t getRotationY();
+ int16_t getRotationZ();
+
+ // EXT_SENS_DATA_* registers
+ uint8_t getExternalSensorByte(int position);
+ uint16_t getExternalSensorWord(int position);
+ uint32_t getExternalSensorDWord(int position);
+
+ // MOT_DETECT_STATUS register
+ uint8_t getMotionStatus();
+ bool getXNegMotionDetected();
+ bool getXPosMotionDetected();
+ bool getYNegMotionDetected();
+ bool getYPosMotionDetected();
+ bool getZNegMotionDetected();
+ bool getZPosMotionDetected();
+ bool getZeroMotionDetected();
+
+ // I2C_SLV*_DO register
+ void setSlaveOutputByte(uint8_t num, uint8_t data);
+
+ // I2C_MST_DELAY_CTRL register
+ bool getExternalShadowDelayEnabled();
+ void setExternalShadowDelayEnabled(bool enabled);
+ bool getSlaveDelayEnabled(uint8_t num);
+ void setSlaveDelayEnabled(uint8_t num, bool enabled);
+
+ // SIGNAL_PATH_RESET register
+ void resetGyroscopePath();
+ void resetAccelerometerPath();
+ void resetTemperaturePath();
+
+ // MOT_DETECT_CTRL register
+ uint8_t getAccelerometerPowerOnDelay();
+ void setAccelerometerPowerOnDelay(uint8_t delay);
+ uint8_t getFreefallDetectionCounterDecrement();
+ void setFreefallDetectionCounterDecrement(uint8_t decrement);
+ uint8_t getMotionDetectionCounterDecrement();
+ void setMotionDetectionCounterDecrement(uint8_t decrement);
+
+ // USER_CTRL register
+ bool getFIFOEnabled();
+ void setFIFOEnabled(bool enabled);
+ bool getI2CMasterModeEnabled();
+ void setI2CMasterModeEnabled(bool enabled);
+ void switchSPIEnabled(bool enabled);
+ void resetFIFO();
+ void resetI2CMaster();
+ void resetSensors();
+
+ // PWR_MGMT_1 register
+ void reset();
+ bool getSleepEnabled();
+ void setSleepEnabled(bool enabled);
+ bool getWakeCycleEnabled();
+ void setWakeCycleEnabled(bool enabled);
+ bool getTempSensorEnabled();
+ void setTempSensorEnabled(bool enabled);
+ uint8_t getClockSource();
+ void setClockSource(uint8_t source);
+
+ // PWR_MGMT_2 register
+ uint8_t getWakeFrequency();
+ void setWakeFrequency(uint8_t frequency);
+ bool getStandbyXAccelEnabled();
+ void setStandbyXAccelEnabled(bool enabled);
+ bool getStandbyYAccelEnabled();
+ void setStandbyYAccelEnabled(bool enabled);
+ bool getStandbyZAccelEnabled();
+ void setStandbyZAccelEnabled(bool enabled);
+ bool getStandbyXGyroEnabled();
+ void setStandbyXGyroEnabled(bool enabled);
+ bool getStandbyYGyroEnabled();
+ void setStandbyYGyroEnabled(bool enabled);
+ bool getStandbyZGyroEnabled();
+ void setStandbyZGyroEnabled(bool enabled);
+
+ // FIFO_COUNT_* registers
+ uint16_t getFIFOCount();
+
+ // FIFO_R_W register
+ uint8_t getFIFOByte();
+ int8_t GetCurrentFIFOPacket(uint8_t *data, uint8_t length);
+ void setFIFOByte(uint8_t data);
+ void getFIFOBytes(uint8_t *data, uint8_t length);
+ void setFIFOTimeout(uint32_t fifoTimeout);
+ uint32_t getFIFOTimeout();
+
+ // WHO_AM_I register
+ uint8_t getDeviceID();
+ void setDeviceID(uint8_t id);
+
+ // ======== UNDOCUMENTED/DMP REGISTERS/METHODS ========
+
+ // XG_OFFS_TC register
+ uint8_t getOTPBankValid();
+ void setOTPBankValid(bool enabled);
+ int8_t getXGyroOffsetTC();
+ void setXGyroOffsetTC(int8_t offset);
+
+ // YG_OFFS_TC register
+ int8_t getYGyroOffsetTC();
+ void setYGyroOffsetTC(int8_t offset);
+
+ // ZG_OFFS_TC register
+ int8_t getZGyroOffsetTC();
+ void setZGyroOffsetTC(int8_t offset);
+
+ // X_FINE_GAIN register
+ int8_t getXFineGain();
+ void setXFineGain(int8_t gain);
+
+ // Y_FINE_GAIN register
+ int8_t getYFineGain();
+ void setYFineGain(int8_t gain);
+
+ // Z_FINE_GAIN register
+ int8_t getZFineGain();
+ void setZFineGain(int8_t gain);
+
+ // XA_OFFS_* registers
+ int16_t getXAccelOffset();
+ void setXAccelOffset(int16_t offset);
+
+ // YA_OFFS_* register
+ int16_t getYAccelOffset();
+ void setYAccelOffset(int16_t offset);
+
+ // ZA_OFFS_* register
+ int16_t getZAccelOffset();
+ void setZAccelOffset(int16_t offset);
+
+ // XG_OFFS_USR* registers
+ int16_t getXGyroOffset();
+ void setXGyroOffset(int16_t offset);
+
+ // YG_OFFS_USR* register
+ int16_t getYGyroOffset();
+ void setYGyroOffset(int16_t offset);
+
+ // ZG_OFFS_USR* register
+ int16_t getZGyroOffset();
+ void setZGyroOffset(int16_t offset);
+
+ // INT_ENABLE register (DMP functions)
+ bool getIntPLLReadyEnabled();
+ void setIntPLLReadyEnabled(bool enabled);
+ bool getIntDMPEnabled();
+ void setIntDMPEnabled(bool enabled);
+
+ // DMP_INT_STATUS
+ bool getDMPInt5Status();
+ bool getDMPInt4Status();
+ bool getDMPInt3Status();
+ bool getDMPInt2Status();
+ bool getDMPInt1Status();
+ bool getDMPInt0Status();
+
+ // INT_STATUS register (DMP functions)
+ bool getIntPLLReadyStatus();
+ bool getIntDMPStatus();
+
+ // USER_CTRL register (DMP functions)
+ bool getDMPEnabled();
+ void setDMPEnabled(bool enabled);
+ void resetDMP();
+
+ // BANK_SEL register
+ void setMemoryBank(uint8_t bank, bool prefetchEnabled=false, bool userBank=false);
+
+ // MEM_START_ADDR register
+ void setMemoryStartAddress(uint8_t address);
+
+ // MEM_R_W register
+ uint8_t readMemoryByte();
+ void writeMemoryByte(uint8_t data);
+ void readMemoryBlock(uint8_t *data, uint16_t dataSize, uint8_t bank=0, uint8_t address=0);
+ bool writeMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank=0, uint8_t address=0, bool verify=true, bool useProgMem=false);
+ bool writeProgMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank=0, uint8_t address=0, bool verify=true);
+
+ bool writeDMPConfigurationSet(const uint8_t *data, uint16_t dataSize, bool useProgMem=false);
+ bool writeProgDMPConfigurationSet(const uint8_t *data, uint16_t dataSize);
+
+ // DMP_CFG_1 register
+ uint8_t getDMPConfig1();
+ void setDMPConfig1(uint8_t config);
+
+ // DMP_CFG_2 register
+ uint8_t getDMPConfig2();
+ void setDMPConfig2(uint8_t config);
+
+ // Calibration Routines
+ void CalibrateGyro(uint8_t Loops = 15); // Fine tune after setting offsets with less Loops.
+ void CalibrateAccel(uint8_t Loops = 15);// Fine tune after setting offsets with less Loops.
+ void PID(uint8_t ReadAddress, float kP,float kI, uint8_t Loops); // Does the math
+ void PrintActiveOffsets(); // See the results of the Calibration
+ int16_t * GetActiveOffsets();
+
+ protected:
+ uint8_t devAddr;
+ void *wireObj;
+ uint8_t buffer[14];
+ uint32_t fifoTimeout = MPU6050_FIFO_DEFAULT_TIMEOUT;
+
+ float accelerationResolution;
+ float gyroscopeResolution;
+
+ private:
+ int16_t offsets[6];
+};
+
+#ifndef I2CDEVLIB_MPU6050_TYPEDEF
+#define I2CDEVLIB_MPU6050_TYPEDEF
+typedef MPU6050_Base MPU6050;
+#endif
+
+#endif /* _MPU6050_H_ */
\ No newline at end of file
diff --git a/lib/MPU6050/src/MPU6050_6Axis_MotionApps20.cpp b/lib/MPU6050/src/MPU6050_6Axis_MotionApps20.cpp
new file mode 100644
index 0000000..ed0f505
--- /dev/null
+++ b/lib/MPU6050/src/MPU6050_6Axis_MotionApps20.cpp
@@ -0,0 +1,632 @@
+// I2Cdev library collection - MPU6050 I2C device class, 6-axis MotionApps 2.0 implementation
+// Based on InvenSense MPU-6050 register map document rev. 2.0, 5/19/2011 (RM-MPU-6000A-00)
+// 5/20/2013 by Jeff Rowberg
+// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
+//
+// Changelog:
+// 2021/09/27 - split implementations out of header files, finally
+// 2019/07/08 - merged all DMP Firmware configuration items into the dmpMemory array
+// - Simplified dmpInitialize() to accomidate the dmpmemory array alterations
+
+/* ============================================
+I2Cdev device library code is placed under the MIT license
+Copyright (c) 2021 Jeff Rowberg
+
+Permission is hereby granted, free of charge, to any person obtaining a copy
+of this software and associated documentation files (the "Software"), to deal
+in the Software without restriction, including without limitation the rights
+to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+copies of the Software, and to permit persons to whom the Software is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in
+all copies or substantial portions of the Software.
+
+THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+THE SOFTWARE.
+===============================================
+*/
+
+// MotionApps 2.0 DMP implementation, built using the MPU-6050EVB evaluation board
+#define MPU6050_INCLUDE_DMP_MOTIONAPPS20
+
+#include "MPU6050_6Axis_MotionApps20.h"
+
+// Tom Carpenter's conditional PROGMEM code
+// http://forum.arduino.cc/index.php?topic=129407.0
+#ifdef __AVR__
+ #include
+#elif defined(ESP32)
+ #include
+#else
+ // Teensy 3.0 library conditional PROGMEM code from Paul Stoffregen
+ #ifndef __PGMSPACE_H_
+ #define __PGMSPACE_H_ 1
+ #include
+
+ #define PROGMEM
+ #define PGM_P const char *
+ #define PSTR(str) (str)
+ #define F(x) x
+
+ typedef void prog_void;
+ typedef char prog_char;
+ typedef unsigned char prog_uchar;
+ typedef int8_t prog_int8_t;
+ typedef uint8_t prog_uint8_t;
+ typedef int16_t prog_int16_t;
+ typedef uint16_t prog_uint16_t;
+ typedef int32_t prog_int32_t;
+ typedef uint32_t prog_uint32_t;
+
+ #define strcpy_P(dest, src) strcpy((dest), (src))
+ #define strcat_P(dest, src) strcat((dest), (src))
+ #define strcmp_P(a, b) strcmp((a), (b))
+
+ #define pgm_read_byte(addr) (*(const unsigned char *)(addr))
+ #define pgm_read_word(addr) (*(const unsigned short *)(addr))
+ #define pgm_read_dword(addr) (*(const unsigned long *)(addr))
+ #define pgm_read_float(addr) (*(const float *)(addr))
+
+ #define pgm_read_byte_near(addr) pgm_read_byte(addr)
+ #define pgm_read_word_near(addr) pgm_read_word(addr)
+ #define pgm_read_dword_near(addr) pgm_read_dword(addr)
+ #define pgm_read_float_near(addr) pgm_read_float(addr)
+ #define pgm_read_byte_far(addr) pgm_read_byte(addr)
+ #define pgm_read_word_far(addr) pgm_read_word(addr)
+ #define pgm_read_dword_far(addr) pgm_read_dword(addr)
+ #define pgm_read_float_far(addr) pgm_read_float(addr)
+ #endif
+#endif
+
+/* Source is from the InvenSense MotionApps v2 demo code. Original source is
+ * unavailable, unless you happen to be amazing as decompiling binary by
+ * hand (in which case, please contact me, and I'm totally serious).
+ *
+ * Also, I'd like to offer many, many thanks to Noah Zerkin for all of the
+ * DMP reverse-engineering he did to help make this bit of wizardry
+ * possible.
+ */
+
+// NOTE! Enabling DEBUG adds about 3.3kB to the flash program size.
+// Debug output is now working even on ATMega328P MCUs (e.g. Arduino Uno)
+// after moving string constants to flash memory storage using the F()
+// compiler macro (Arduino IDE 1.0+ required).
+
+//#define DEBUG
+/* Control whether debugging macros are active at compile time */
+#undef DB_ACTIVE
+#ifdef DEBUG
+#define DB_ACTIVE 1
+#else
+#define DB_ACTIVE 0
+#endif /* DEBUG */
+
+/*
+** Usage: DB_PRINT((...));
+** Usage: DB_PRINTLN((...));
+**
+** "..." is whatever extra arguments fmt requires (possibly nothing).
+**
+** The structure of the macros means that the code is always validated
+** but is not called when DEBUG is undefined.
+** -- See chapter 8 of 'The Practice of Programming', by Kernighan and Pike.
+*/
+#define DEBUG_PRINT(...)\
+ do { if (DB_ACTIVE) Serial.print(__VA_ARGS__); } while (0)
+#define DEBUG_PRINTF(...)\
+ do { if (DB_ACTIVE) Serial.printf(__VA_ARGS__); } while (0)
+#define DEBUG_PRINTLN(...)\
+ do { if (DB_ACTIVE) Serial.println(__VA_ARGS__); } while (0)
+#define DEBUG_PRINTLNF(x, y)\
+ do { if (DB_ACTIVE) Serial.println(x, y); } while (0)
+
+#define MPU6050_DMP_CODE_SIZE 1929 // dmpMemory[]
+#define MPU6050_DMP_CONFIG_SIZE 192 // dmpConfig[]
+#define MPU6050_DMP_UPDATES_SIZE 47 // dmpUpdates[]
+
+/* ================================================================================================ *
+ | Default MotionApps v2.0 42-byte FIFO packet structure: |
+ | |
+ | [QUAT W][ ][QUAT X][ ][QUAT Y][ ][QUAT Z][ ][GYRO X][ ][GYRO Y][ ] |
+ | 0 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 |
+ | |
+ | [GYRO Z][ ][ACC X ][ ][ACC Y ][ ][ACC Z ][ ][ ] |
+ | 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 |
+ * ================================================================================================ */
+
+// this block of memory gets written to the MPU on start-up, and it seems
+// to be volatile memory, so it has to be done each time (it only takes ~1
+// second though)
+
+// I Only Changed this by applying all the configuration data and capturing it before startup:
+// *** this is a capture of the DMP Firmware after all the messy changes were made so we can just load it
+static const unsigned char dmpMemory[MPU6050_DMP_CODE_SIZE] PROGMEM = {
+ /* bank # 0 */
+ 0xFB, 0x00, 0x00, 0x3E, 0x00, 0x0B, 0x00, 0x36, 0x00, 0x01, 0x00, 0x02, 0x00, 0x03, 0x00, 0x00,
+ 0x00, 0x65, 0x00, 0x54, 0xFF, 0xEF, 0x00, 0x00, 0xFA, 0x80, 0x00, 0x0B, 0x12, 0x82, 0x00, 0x01,
+ 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x28, 0x00, 0x00, 0xFF, 0xFF, 0x45, 0x81, 0xFF, 0xFF, 0xFA, 0x72, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x03, 0xE8, 0x00, 0x00, 0x00, 0x01, 0x00, 0x01, 0x7F, 0xFF, 0xFF, 0xFE, 0x80, 0x01,
+ 0x00, 0x1B, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x40, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x02, 0xCB, 0x47, 0xA2, 0x20, 0x00, 0x00, 0x00,
+ 0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x60, 0x00, 0x00, 0x00,
+ 0x41, 0xFF, 0x00, 0x00, 0x00, 0x00, 0x0B, 0x2A, 0x00, 0x00, 0x16, 0x55, 0x00, 0x00, 0x21, 0x82,
+ 0xFD, 0x87, 0x26, 0x50, 0xFD, 0x80, 0x00, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x00, 0x05, 0x80, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x03, 0x00, 0x00,
+ 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x04, 0x6F, 0x00, 0x02, 0x65, 0x32, 0x00, 0x00, 0x5E, 0xC0,
+ 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0xFB, 0x8C, 0x6F, 0x5D, 0xFD, 0x5D, 0x08, 0xD9, 0x00, 0x7C, 0x73, 0x3B, 0x00, 0x6C, 0x12, 0xCC,
+ 0x32, 0x00, 0x13, 0x9D, 0x32, 0x00, 0xD0, 0xD6, 0x32, 0x00, 0x08, 0x00, 0x40, 0x00, 0x01, 0xF4,
+ 0xFF, 0xE6, 0x80, 0x79, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0xD0, 0xD6, 0x00, 0x00, 0x27, 0x10,
+ /* bank # 1 */
+ 0xFB, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x01, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0xFA, 0x36, 0xFF, 0xBC, 0x30, 0x8E, 0x00, 0x05, 0xFB, 0xF0, 0xFF, 0xD9, 0x5B, 0xC8,
+ 0xFF, 0xD0, 0x9A, 0xBE, 0x00, 0x00, 0x10, 0xA9, 0xFF, 0xF4, 0x1E, 0xB2, 0x00, 0xCE, 0xBB, 0xF7,
+ 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x04, 0x00, 0x02, 0x00, 0x02, 0x02, 0x00, 0x00, 0x0C,
+ 0xFF, 0xC2, 0x80, 0x00, 0x00, 0x01, 0x80, 0x00, 0x00, 0xCF, 0x80, 0x00, 0x40, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00, 0x14,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x09, 0x23, 0xA1, 0x35, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x03, 0x3F, 0x68, 0xB6, 0x79, 0x35, 0x28, 0xBC, 0xC6, 0x7E, 0xD1, 0x6C,
+ 0x80, 0x00, 0xFF, 0xFF, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0xB2, 0x6A, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3F, 0xF0, 0x00, 0x00, 0x00, 0x30,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00,
+ 0x00, 0x00, 0x25, 0x4D, 0x00, 0x2F, 0x70, 0x6D, 0x00, 0x00, 0x05, 0xAE, 0x00, 0x0C, 0x02, 0xD0,
+ /* bank # 2 */
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x65, 0x00, 0x54, 0xFF, 0xEF, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x01, 0x00, 0x00, 0x44, 0x00, 0x01, 0x00, 0x05, 0x8B, 0xC1, 0x00, 0x00, 0x01, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x65, 0x00, 0x00, 0x00, 0x54, 0x00, 0x00, 0xFF, 0xEF, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x1B, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x1B, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ /* bank # 3 */
+ 0xD8, 0xDC, 0xBA, 0xA2, 0xF1, 0xDE, 0xB2, 0xB8, 0xB4, 0xA8, 0x81, 0x91, 0xF7, 0x4A, 0x90, 0x7F,
+ 0x91, 0x6A, 0xF3, 0xF9, 0xDB, 0xA8, 0xF9, 0xB0, 0xBA, 0xA0, 0x80, 0xF2, 0xCE, 0x81, 0xF3, 0xC2,
+ 0xF1, 0xC1, 0xF2, 0xC3, 0xF3, 0xCC, 0xA2, 0xB2, 0x80, 0xF1, 0xC6, 0xD8, 0x80, 0xBA, 0xA7, 0xDF,
+ 0xDF, 0xDF, 0xF2, 0xA7, 0xC3, 0xCB, 0xC5, 0xB6, 0xF0, 0x87, 0xA2, 0x94, 0x24, 0x48, 0x70, 0x3C,
+ 0x95, 0x40, 0x68, 0x34, 0x58, 0x9B, 0x78, 0xA2, 0xF1, 0x83, 0x92, 0x2D, 0x55, 0x7D, 0xD8, 0xB1,
+ 0xB4, 0xB8, 0xA1, 0xD0, 0x91, 0x80, 0xF2, 0x70, 0xF3, 0x70, 0xF2, 0x7C, 0x80, 0xA8, 0xF1, 0x01,
+ 0xB0, 0x98, 0x87, 0xD9, 0x43, 0xD8, 0x86, 0xC9, 0x88, 0xBA, 0xA1, 0xF2, 0x0E, 0xB8, 0x97, 0x80,
+ 0xF1, 0xA9, 0xDF, 0xDF, 0xDF, 0xAA, 0xDF, 0xDF, 0xDF, 0xF2, 0xAA, 0x4C, 0xCD, 0x6C, 0xA9, 0x0C,
+ 0xC9, 0x2C, 0x97, 0x97, 0x97, 0x97, 0xF1, 0xA9, 0x89, 0x26, 0x46, 0x66, 0xB0, 0xB4, 0xBA, 0x80,
+ 0xAC, 0xDE, 0xF2, 0xCA, 0xF1, 0xB2, 0x8C, 0x02, 0xA9, 0xB6, 0x98, 0x00, 0x89, 0x0E, 0x16, 0x1E,
+ 0xB8, 0xA9, 0xB4, 0x99, 0x2C, 0x54, 0x7C, 0xB0, 0x8A, 0xA8, 0x96, 0x36, 0x56, 0x76, 0xF1, 0xB9,
+ 0xAF, 0xB4, 0xB0, 0x83, 0xC0, 0xB8, 0xA8, 0x97, 0x11, 0xB1, 0x8F, 0x98, 0xB9, 0xAF, 0xF0, 0x24,
+ 0x08, 0x44, 0x10, 0x64, 0x18, 0xF1, 0xA3, 0x29, 0x55, 0x7D, 0xAF, 0x83, 0xB5, 0x93, 0xAF, 0xF0,
+ 0x00, 0x28, 0x50, 0xF1, 0xA3, 0x86, 0x9F, 0x61, 0xA6, 0xDA, 0xDE, 0xDF, 0xD9, 0xFA, 0xA3, 0x86,
+ 0x96, 0xDB, 0x31, 0xA6, 0xD9, 0xF8, 0xDF, 0xBA, 0xA6, 0x8F, 0xC2, 0xC5, 0xC7, 0xB2, 0x8C, 0xC1,
+ 0xB8, 0xA2, 0xDF, 0xDF, 0xDF, 0xA3, 0xDF, 0xDF, 0xDF, 0xD8, 0xD8, 0xF1, 0xB8, 0xA8, 0xB2, 0x86,
+ /* bank # 4 */
+ 0xB4, 0x98, 0x0D, 0x35, 0x5D, 0xB8, 0xAA, 0x98, 0xB0, 0x87, 0x2D, 0x35, 0x3D, 0xB2, 0xB6, 0xBA,
+ 0xAF, 0x8C, 0x96, 0x19, 0x8F, 0x9F, 0xA7, 0x0E, 0x16, 0x1E, 0xB4, 0x9A, 0xB8, 0xAA, 0x87, 0x2C,
+ 0x54, 0x7C, 0xB9, 0xA3, 0xDE, 0xDF, 0xDF, 0xA3, 0xB1, 0x80, 0xF2, 0xC4, 0xCD, 0xC9, 0xF1, 0xB8,
+ 0xA9, 0xB4, 0x99, 0x83, 0x0D, 0x35, 0x5D, 0x89, 0xB9, 0xA3, 0x2D, 0x55, 0x7D, 0xB5, 0x93, 0xA3,
+ 0x0E, 0x16, 0x1E, 0xA9, 0x2C, 0x54, 0x7C, 0xB8, 0xB4, 0xB0, 0xF1, 0x97, 0x83, 0xA8, 0x11, 0x84,
+ 0xA5, 0x09, 0x98, 0xA3, 0x83, 0xF0, 0xDA, 0x24, 0x08, 0x44, 0x10, 0x64, 0x18, 0xD8, 0xF1, 0xA5,
+ 0x29, 0x55, 0x7D, 0xA5, 0x85, 0x95, 0x02, 0x1A, 0x2E, 0x3A, 0x56, 0x5A, 0x40, 0x48, 0xF9, 0xF3,
+ 0xA3, 0xD9, 0xF8, 0xF0, 0x98, 0x83, 0x24, 0x08, 0x44, 0x10, 0x64, 0x18, 0x97, 0x82, 0xA8, 0xF1,
+ 0x11, 0xF0, 0x98, 0xA2, 0x24, 0x08, 0x44, 0x10, 0x64, 0x18, 0xDA, 0xF3, 0xDE, 0xD8, 0x83, 0xA5,
+ 0x94, 0x01, 0xD9, 0xA3, 0x02, 0xF1, 0xA2, 0xC3, 0xC5, 0xC7, 0xD8, 0xF1, 0x84, 0x92, 0xA2, 0x4D,
+ 0xDA, 0x2A, 0xD8, 0x48, 0x69, 0xD9, 0x2A, 0xD8, 0x68, 0x55, 0xDA, 0x32, 0xD8, 0x50, 0x71, 0xD9,
+ 0x32, 0xD8, 0x70, 0x5D, 0xDA, 0x3A, 0xD8, 0x58, 0x79, 0xD9, 0x3A, 0xD8, 0x78, 0x93, 0xA3, 0x4D,
+ 0xDA, 0x2A, 0xD8, 0x48, 0x69, 0xD9, 0x2A, 0xD8, 0x68, 0x55, 0xDA, 0x32, 0xD8, 0x50, 0x71, 0xD9,
+ 0x32, 0xD8, 0x70, 0x5D, 0xDA, 0x3A, 0xD8, 0x58, 0x79, 0xD9, 0x3A, 0xD8, 0x78, 0xA8, 0x8A, 0x9A,
+ 0xF0, 0x28, 0x50, 0x78, 0x9E, 0xF3, 0x88, 0x18, 0xF1, 0x9F, 0x1D, 0x98, 0xA8, 0xD9, 0x08, 0xD8,
+ 0xC8, 0x9F, 0x12, 0x9E, 0xF3, 0x15, 0xA8, 0xDA, 0x12, 0x10, 0xD8, 0xF1, 0xAF, 0xC8, 0x97, 0x87,
+ /* bank # 5 */
+ 0x34, 0xB5, 0xB9, 0x94, 0xA4, 0x21, 0xF3, 0xD9, 0x22, 0xD8, 0xF2, 0x2D, 0xF3, 0xD9, 0x2A, 0xD8,
+ 0xF2, 0x35, 0xF3, 0xD9, 0x32, 0xD8, 0x81, 0xA4, 0x60, 0x60, 0x61, 0xD9, 0x61, 0xD8, 0x6C, 0x68,
+ 0x69, 0xD9, 0x69, 0xD8, 0x74, 0x70, 0x71, 0xD9, 0x71, 0xD8, 0xB1, 0xA3, 0x84, 0x19, 0x3D, 0x5D,
+ 0xA3, 0x83, 0x1A, 0x3E, 0x5E, 0x93, 0x10, 0x30, 0x81, 0x10, 0x11, 0xB8, 0xB0, 0xAF, 0x8F, 0x94,
+ 0xF2, 0xDA, 0x3E, 0xD8, 0xB4, 0x9A, 0xA8, 0x87, 0x29, 0xDA, 0xF8, 0xD8, 0x87, 0x9A, 0x35, 0xDA,
+ 0xF8, 0xD8, 0x87, 0x9A, 0x3D, 0xDA, 0xF8, 0xD8, 0xB1, 0xB9, 0xA4, 0x98, 0x85, 0x02, 0x2E, 0x56,
+ 0xA5, 0x81, 0x00, 0x0C, 0x14, 0xA3, 0x97, 0xB0, 0x8A, 0xF1, 0x2D, 0xD9, 0x28, 0xD8, 0x4D, 0xD9,
+ 0x48, 0xD8, 0x6D, 0xD9, 0x68, 0xD8, 0xB1, 0x84, 0x0D, 0xDA, 0x0E, 0xD8, 0xA3, 0x29, 0x83, 0xDA,
+ 0x2C, 0x0E, 0xD8, 0xA3, 0x84, 0x49, 0x83, 0xDA, 0x2C, 0x4C, 0x0E, 0xD8, 0xB8, 0xB0, 0xA8, 0x8A,
+ 0x9A, 0xF5, 0x20, 0xAA, 0xDA, 0xDF, 0xD8, 0xA8, 0x40, 0xAA, 0xD0, 0xDA, 0xDE, 0xD8, 0xA8, 0x60,
+ 0xAA, 0xDA, 0xD0, 0xDF, 0xD8, 0xF1, 0x97, 0x86, 0xA8, 0x31, 0x9B, 0x06, 0x99, 0x07, 0xAB, 0x97,
+ 0x28, 0x88, 0x9B, 0xF0, 0x0C, 0x20, 0x14, 0x40, 0xB8, 0xB0, 0xB4, 0xA8, 0x8C, 0x9C, 0xF0, 0x04,
+ 0x28, 0x51, 0x79, 0x1D, 0x30, 0x14, 0x38, 0xB2, 0x82, 0xAB, 0xD0, 0x98, 0x2C, 0x50, 0x50, 0x78,
+ 0x78, 0x9B, 0xF1, 0x1A, 0xB0, 0xF0, 0x8A, 0x9C, 0xA8, 0x29, 0x51, 0x79, 0x8B, 0x29, 0x51, 0x79,
+ 0x8A, 0x24, 0x70, 0x59, 0x8B, 0x20, 0x58, 0x71, 0x8A, 0x44, 0x69, 0x38, 0x8B, 0x39, 0x40, 0x68,
+ 0x8A, 0x64, 0x48, 0x31, 0x8B, 0x30, 0x49, 0x60, 0xA5, 0x88, 0x20, 0x09, 0x71, 0x58, 0x44, 0x68,
+ /* bank # 6 */
+ 0x11, 0x39, 0x64, 0x49, 0x30, 0x19, 0xF1, 0xAC, 0x00, 0x2C, 0x54, 0x7C, 0xF0, 0x8C, 0xA8, 0x04,
+ 0x28, 0x50, 0x78, 0xF1, 0x88, 0x97, 0x26, 0xA8, 0x59, 0x98, 0xAC, 0x8C, 0x02, 0x26, 0x46, 0x66,
+ 0xF0, 0x89, 0x9C, 0xA8, 0x29, 0x51, 0x79, 0x24, 0x70, 0x59, 0x44, 0x69, 0x38, 0x64, 0x48, 0x31,
+ 0xA9, 0x88, 0x09, 0x20, 0x59, 0x70, 0xAB, 0x11, 0x38, 0x40, 0x69, 0xA8, 0x19, 0x31, 0x48, 0x60,
+ 0x8C, 0xA8, 0x3C, 0x41, 0x5C, 0x20, 0x7C, 0x00, 0xF1, 0x87, 0x98, 0x19, 0x86, 0xA8, 0x6E, 0x76,
+ 0x7E, 0xA9, 0x99, 0x88, 0x2D, 0x55, 0x7D, 0x9E, 0xB9, 0xA3, 0x8A, 0x22, 0x8A, 0x6E, 0x8A, 0x56,
+ 0x8A, 0x5E, 0x9F, 0xB1, 0x83, 0x06, 0x26, 0x46, 0x66, 0x0E, 0x2E, 0x4E, 0x6E, 0x9D, 0xB8, 0xAD,
+ 0x00, 0x2C, 0x54, 0x7C, 0xF2, 0xB1, 0x8C, 0xB4, 0x99, 0xB9, 0xA3, 0x2D, 0x55, 0x7D, 0x81, 0x91,
+ 0xAC, 0x38, 0xAD, 0x3A, 0xB5, 0x83, 0x91, 0xAC, 0x2D, 0xD9, 0x28, 0xD8, 0x4D, 0xD9, 0x48, 0xD8,
+ 0x6D, 0xD9, 0x68, 0xD8, 0x8C, 0x9D, 0xAE, 0x29, 0xD9, 0x04, 0xAE, 0xD8, 0x51, 0xD9, 0x04, 0xAE,
+ 0xD8, 0x79, 0xD9, 0x04, 0xD8, 0x81, 0xF3, 0x9D, 0xAD, 0x00, 0x8D, 0xAE, 0x19, 0x81, 0xAD, 0xD9,
+ 0x01, 0xD8, 0xF2, 0xAE, 0xDA, 0x26, 0xD8, 0x8E, 0x91, 0x29, 0x83, 0xA7, 0xD9, 0xAD, 0xAD, 0xAD,
+ 0xAD, 0xF3, 0x2A, 0xD8, 0xD8, 0xF1, 0xB0, 0xAC, 0x89, 0x91, 0x3E, 0x5E, 0x76, 0xF3, 0xAC, 0x2E,
+ 0x2E, 0xF1, 0xB1, 0x8C, 0x5A, 0x9C, 0xAC, 0x2C, 0x28, 0x28, 0x28, 0x9C, 0xAC, 0x30, 0x18, 0xA8,
+ 0x98, 0x81, 0x28, 0x34, 0x3C, 0x97, 0x24, 0xA7, 0x28, 0x34, 0x3C, 0x9C, 0x24, 0xF2, 0xB0, 0x89,
+ 0xAC, 0x91, 0x2C, 0x4C, 0x6C, 0x8A, 0x9B, 0x2D, 0xD9, 0xD8, 0xD8, 0x51, 0xD9, 0xD8, 0xD8, 0x79,
+ /* bank # 7 */
+ 0xD9, 0xD8, 0xD8, 0xF1, 0x9E, 0x88, 0xA3, 0x31, 0xDA, 0xD8, 0xD8, 0x91, 0x2D, 0xD9, 0x28, 0xD8,
+ 0x4D, 0xD9, 0x48, 0xD8, 0x6D, 0xD9, 0x68, 0xD8, 0xB1, 0x83, 0x93, 0x35, 0x3D, 0x80, 0x25, 0xDA,
+ 0xD8, 0xD8, 0x85, 0x69, 0xDA, 0xD8, 0xD8, 0xB4, 0x93, 0x81, 0xA3, 0x28, 0x34, 0x3C, 0xF3, 0xAB,
+ 0x8B, 0xF8, 0xA3, 0x91, 0xB6, 0x09, 0xB4, 0xD9, 0xAB, 0xDE, 0xFA, 0xB0, 0x87, 0x9C, 0xB9, 0xA3,
+ 0xDD, 0xF1, 0x20, 0x28, 0x30, 0x38, 0x9A, 0xF1, 0x28, 0x30, 0x38, 0x9D, 0xF1, 0xA3, 0xA3, 0xA3,
+ 0xA3, 0xF2, 0xA3, 0xB4, 0x90, 0x80, 0xF2, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3,
+ 0xA3, 0xB2, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xB0, 0x87, 0xB5, 0x99, 0xF1, 0x28, 0x30, 0x38,
+ 0x98, 0xF1, 0xA3, 0xA3, 0xA3, 0xA3, 0x97, 0xA3, 0xA3, 0xA3, 0xA3, 0xF3, 0x9B, 0xA3, 0x30, 0xDC,
+ 0xB9, 0xA7, 0xF1, 0x26, 0x26, 0x26, 0xFE, 0xD8, 0xFF,
+
+};
+
+#ifndef MPU6050_DMP_FIFO_RATE_DIVISOR
+#define MPU6050_DMP_FIFO_RATE_DIVISOR 0x01 // The New instance of the Firmware has this as the default
+#endif
+
+// I Simplified this:
+uint8_t MPU6050_6Axis_MotionApps20::dmpInitialize() {
+ // reset device
+ DEBUG_PRINTLN(F("\n\nResetting MPU6050..."));
+ reset();
+ delay(30); // wait after reset
+
+ // enable sleep mode and wake cycle
+ /*Serial.println(F("Enabling sleep mode..."));
+ setSleepEnabled(true);
+ Serial.println(F("Enabling wake cycle..."));
+ setWakeCycleEnabled(true);*/
+
+ // disable sleep mode
+ setSleepEnabled(false);
+
+ // get MPU hardware revision
+ setMemoryBank(0x10, true, true);
+ setMemoryStartAddress(0x06);
+ DEBUG_PRINTLN(F("Checking hardware revision..."));
+ DEBUG_PRINT(F("Revision @ user[16][6] = "));
+ DEBUG_PRINTLN(readMemoryByte());
+ DEBUG_PRINTLN(F("Resetting memory bank selection to 0..."));
+ setMemoryBank(0, false, false);
+
+ // check OTP bank valid
+ DEBUG_PRINTLN(F("Reading OTP bank valid flag..."));
+ DEBUG_PRINT(F("OTP bank is "));
+ DEBUG_PRINTLN(getOTPBankValid() ? F("valid!") : F("invalid!"));
+
+ // setup weird slave stuff (?)
+ DEBUG_PRINTLN(F("Setting slave 0 address to 0x7F..."));
+ setSlaveAddress(0, 0x7F);
+ DEBUG_PRINTLN(F("Disabling I2C Master mode..."));
+ setI2CMasterModeEnabled(false);
+ DEBUG_PRINTLN(F("Setting slave 0 address to 0x68 (self)..."));
+ setSlaveAddress(0, 0x68);
+ DEBUG_PRINTLN(F("Resetting I2C Master control..."));
+ resetI2CMaster();
+ delay(20);
+ DEBUG_PRINTLN(F("Setting clock source to Z Gyro..."));
+ setClockSource(MPU6050_CLOCK_PLL_ZGYRO);
+
+ DEBUG_PRINTLN(F("Setting DMP and FIFO_OFLOW interrupts enabled..."));
+ setIntEnabled(1<= dmpGetFIFOPacketSize();
+}
+
+// uint8_t MPU6050_6Axis_MotionApps20::dmpSetFIFORate(uint8_t fifoRate);
+// uint8_t MPU6050_6Axis_MotionApps20::dmpGetFIFORate();
+// uint8_t MPU6050_6Axis_MotionApps20::dmpGetSampleStepSizeMS();
+// uint8_t MPU6050_6Axis_MotionApps20::dmpGetSampleFrequency();
+// int32_t MPU6050_6Axis_MotionApps20::dmpDecodeTemperature(int8_t tempReg);
+
+//uint8_t MPU6050_6Axis_MotionApps20::dmpRegisterFIFORateProcess(inv_obj_func func, int16_t priority);
+//uint8_t MPU6050_6Axis_MotionApps20::dmpUnregisterFIFORateProcess(inv_obj_func func);
+//uint8_t MPU6050_6Axis_MotionApps20::dmpRunFIFORateProcesses();
+
+// uint8_t MPU6050_6Axis_MotionApps20::dmpSendQuaternion(uint_fast16_t accuracy);
+// uint8_t MPU6050_6Axis_MotionApps20::dmpSendGyro(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050_6Axis_MotionApps20::dmpSendAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050_6Axis_MotionApps20::dmpSendLinearAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050_6Axis_MotionApps20::dmpSendLinearAccelInWorld(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050_6Axis_MotionApps20::dmpSendControlData(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050_6Axis_MotionApps20::dmpSendSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050_6Axis_MotionApps20::dmpSendExternalSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050_6Axis_MotionApps20::dmpSendGravity(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050_6Axis_MotionApps20::dmpSendPacketNumber(uint_fast16_t accuracy);
+// uint8_t MPU6050_6Axis_MotionApps20::dmpSendQuantizedAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050_6Axis_MotionApps20::dmpSendEIS(uint_fast16_t elements, uint_fast16_t accuracy);
+
+uint8_t MPU6050_6Axis_MotionApps20::dmpGetAccel(int32_t *data, const uint8_t* packet) {
+ // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+ if (packet == 0) packet = dmpPacketBuffer;
+ data[0] = (((int32_t)packet[28] << 24) | ((int32_t)packet[29] << 16) | ((int32_t)packet[30] << 8) | (int32_t)packet[31]);
+ data[1] = (((int32_t)packet[32] << 24) | ((int32_t)packet[33] << 16) | ((int32_t)packet[34] << 8) | (int32_t)packet[35]);
+ data[2] = (((int32_t)packet[36] << 24) | ((int32_t)packet[37] << 16) | ((int32_t)packet[38] << 8) | (int32_t)packet[39]);
+ return 0;
+}
+uint8_t MPU6050_6Axis_MotionApps20::dmpGetAccel(int16_t *data, const uint8_t* packet) {
+ // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+ if (packet == 0) packet = dmpPacketBuffer;
+ data[0] = ((int16_t)packet[28] << 8) | (int16_t)packet[29];
+ data[1] = ((int16_t)packet[32] << 8) | (int16_t)packet[33];
+ data[2] = ((int16_t)packet[36] << 8) | (int16_t)packet[37];
+ return 0;
+}
+
+uint8_t MPU6050_6Axis_MotionApps20::dmpGetAccel(VectorInt16 *v, const uint8_t* packet) {
+ // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+ if (packet == 0) packet = dmpPacketBuffer;
+ v -> x = ((int16_t)packet[28] << 8) | (int16_t)packet[29];
+ v -> y = ((int16_t)packet[32] << 8) | (int16_t)packet[33];
+ v -> z = ((int16_t)packet[36] << 8) | (int16_t)packet[37];
+ return 0;
+}
+uint8_t MPU6050_6Axis_MotionApps20::dmpGetQuaternion(int32_t *data, const uint8_t* packet) {
+ // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+ if (packet == 0) packet = dmpPacketBuffer;
+ data[0] = (((int32_t)packet[0] << 24) | ((int32_t)packet[1] << 16) | ((int32_t)packet[2] << 8) | (int32_t)packet[3]);
+ data[1] = (((int32_t)packet[4] << 24) | ((int32_t)packet[5] << 16) | ((int32_t)packet[6] << 8) | (int32_t)packet[7]);
+ data[2] = (((int32_t)packet[8] << 24) | ((int32_t)packet[9] << 16) | ((int32_t)packet[10] << 8) | (int32_t)packet[11]);
+ data[3] = (((int32_t)packet[12] << 24) | ((int32_t)packet[13] << 16) | ((int32_t)packet[14] << 8) | (int32_t)packet[15]);
+ return 0;
+}
+uint8_t MPU6050_6Axis_MotionApps20::dmpGetQuaternion(int16_t *data, const uint8_t* packet) {
+ // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+ if (packet == 0) packet = dmpPacketBuffer;
+ data[0] = (((int16_t)packet[0] << 8) | (int16_t)packet[1]);
+ data[1] = (((int16_t)packet[4] << 8) | (int16_t)packet[5]);
+ data[2] = (((int16_t)packet[8] << 8) | (int16_t)packet[9]);
+ data[3] = (((int16_t)packet[12] << 8) | (int16_t)packet[13]);
+ return 0;
+}
+uint8_t MPU6050_6Axis_MotionApps20::dmpGetQuaternion(Quaternion *q, const uint8_t* packet) {
+ // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+ int16_t qI[4];
+ uint8_t status = dmpGetQuaternion(qI, packet);
+ if (status == 0) {
+ q -> w = (float)qI[0] / 16384.0f;
+ q -> x = (float)qI[1] / 16384.0f;
+ q -> y = (float)qI[2] / 16384.0f;
+ q -> z = (float)qI[3] / 16384.0f;
+ return 0;
+ }
+ return status; // int16 return value, indicates error if this line is reached
+}
+// uint8_t MPU6050_6Axis_MotionApps20::dmpGet6AxisQuaternion(long *data, const uint8_t* packet);
+// uint8_t MPU6050_6Axis_MotionApps20::dmpGetRelativeQuaternion(long *data, const uint8_t* packet);
+uint8_t MPU6050_6Axis_MotionApps20::dmpGetGyro(int32_t *data, const uint8_t* packet) {
+ // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+ if (packet == 0) packet = dmpPacketBuffer;
+ data[0] = (((int32_t)packet[16] << 24) | ((int32_t)packet[17] << 16) | ((int32_t)packet[18] << 8) | (int32_t)packet[19]);
+ data[1] = (((int32_t)packet[20] << 24) | ((int32_t)packet[21] << 16) | ((int32_t)packet[22] << 8) | (int32_t)packet[23]);
+ data[2] = (((int32_t)packet[24] << 24) | ((int32_t)packet[25] << 16) | ((int32_t)packet[26] << 8) | (int32_t)packet[27]);
+ return 0;
+}
+uint8_t MPU6050_6Axis_MotionApps20::dmpGetGyro(int16_t *data, const uint8_t* packet) {
+ // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+ if (packet == 0) packet = dmpPacketBuffer;
+ data[0] = ((int16_t)packet[16] << 8) | (int16_t)packet[17];
+ data[1] = ((int16_t)packet[20] << 8) | (int16_t)packet[21];
+ data[2] = ((int16_t)packet[24] << 8) | (int16_t)packet[25];
+ return 0;
+}
+uint8_t MPU6050_6Axis_MotionApps20::dmpGetGyro(VectorInt16 *v, const uint8_t* packet) {
+ // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+ if (packet == 0) packet = dmpPacketBuffer;
+ v -> x = ((int16_t)packet[16] << 8) | (int16_t)packet[17];
+ v -> y = ((int16_t)packet[20] << 8) | (int16_t)packet[21];
+ v -> z = ((int16_t)packet[24] << 8) | (int16_t)packet[25];
+ return 0;
+}
+// uint8_t MPU6050_6Axis_MotionApps20::dmpSetLinearAccelFilterCoefficient(float coef);
+// uint8_t MPU6050_6Axis_MotionApps20::dmpGetLinearAccel(long *data, const uint8_t* packet);
+uint8_t MPU6050_6Axis_MotionApps20::dmpGetLinearAccel(VectorInt16 *v, VectorInt16 *vRaw, VectorFloat *gravity) {
+ // get rid of the gravity component (+1g = +8192 in standard DMP FIFO packet, sensitivity is 2g)
+ v -> x = vRaw -> x - gravity -> x*8192;
+ v -> y = vRaw -> y - gravity -> y*8192;
+ v -> z = vRaw -> z - gravity -> z*8192;
+ return 0;
+}
+// uint8_t MPU6050_6Axis_MotionApps20::dmpConvertToWorldFrame(long *data, const uint8_t* packet);
+uint8_t MPU6050_6Axis_MotionApps20::dmpConvertToWorldFrame(VectorInt16 *v, VectorInt16 *vReal, Quaternion *q) {
+ // rotate measured 3D acceleration vector into original state
+ // frame of reference based on orientation quaternion
+ memcpy(v, vReal, sizeof(VectorInt16));
+ v -> rotate(q);
+ return 0;
+}
+// uint8_t MPU6050_6Axis_MotionApps20::dmpGetGyroAndAccelSensor(long *data, const uint8_t* packet);
+// uint8_t MPU6050_6Axis_MotionApps20::dmpGetGyroSensor(long *data, const uint8_t* packet);
+// uint8_t MPU6050_6Axis_MotionApps20::dmpGetControlData(long *data, const uint8_t* packet);
+// uint8_t MPU6050_6Axis_MotionApps20::dmpGetTemperature(long *data, const uint8_t* packet);
+// uint8_t MPU6050_6Axis_MotionApps20::dmpGetGravity(long *data, const uint8_t* packet);
+uint8_t MPU6050_6Axis_MotionApps20::dmpGetGravity(int16_t *data, const uint8_t* packet) {
+ /* +1g corresponds to +8192, sensitivity is 2g. */
+ int16_t qI[4];
+ uint8_t status = dmpGetQuaternion(qI, packet);
+ data[0] = ((int32_t)qI[1] * qI[3] - (int32_t)qI[0] * qI[2]) / 16384;
+ data[1] = ((int32_t)qI[0] * qI[1] + (int32_t)qI[2] * qI[3]) / 16384;
+ data[2] = ((int32_t)qI[0] * qI[0] - (int32_t)qI[1] * qI[1] - (int32_t)qI[2] * qI[2] + (int32_t)qI[3] * qI[3]) / (int32_t)(2 * 16384L);
+ return status;
+}
+
+uint8_t MPU6050_6Axis_MotionApps20::dmpGetGravity(VectorFloat *v, Quaternion *q) {
+ v -> x = 2 * (q -> x*q -> z - q -> w*q -> y);
+ v -> y = 2 * (q -> w*q -> x + q -> y*q -> z);
+ v -> z = q -> w*q -> w - q -> x*q -> x - q -> y*q -> y + q -> z*q -> z;
+ return 0;
+
+}
+// uint8_t MPU6050_6Axis_MotionApps20::dmpGetUnquantizedAccel(long *data, const uint8_t* packet);
+// uint8_t MPU6050_6Axis_MotionApps20::dmpGetQuantizedAccel(long *data, const uint8_t* packet);
+// uint8_t MPU6050_6Axis_MotionApps20::dmpGetExternalSensorData(long *data, int size, const uint8_t* packet);
+// uint8_t MPU6050_6Axis_MotionApps20::dmpGetEIS(long *data, const uint8_t* packet);
+
+uint8_t MPU6050_6Axis_MotionApps20::dmpGetEuler(float *data, Quaternion *q) {
+ data[0] = atan2(2*q -> x*q -> y - 2*q -> w*q -> z, 2*q -> w*q -> w + 2*q -> x*q -> x - 1); // psi
+ data[1] = -asin(2*q -> x*q -> z + 2*q -> w*q -> y); // theta
+ data[2] = atan2(2*q -> y*q -> z - 2*q -> w*q -> x, 2*q -> w*q -> w + 2*q -> z*q -> z - 1); // phi
+ return 0;
+}
+
+#ifdef USE_OLD_DMPGETYAWPITCHROLL
+uint8_t MPU6050_6Axis_MotionApps20::dmpGetYawPitchRoll(float *data, Quaternion *q, VectorFloat *gravity) {
+ // yaw: (about Z axis)
+ data[0] = atan2(2*q -> x*q -> y - 2*q -> w*q -> z, 2*q -> w*q -> w + 2*q -> x*q -> x - 1);
+ // pitch: (nose up/down, about Y axis)
+ data[1] = atan(gravity -> x / sqrt(gravity -> y*gravity -> y + gravity -> z*gravity -> z));
+ // roll: (tilt left/right, about X axis)
+ data[2] = atan(gravity -> y / sqrt(gravity -> x*gravity -> x + gravity -> z*gravity -> z));
+ return 0;
+}
+#else
+uint8_t MPU6050_6Axis_MotionApps20::dmpGetYawPitchRoll(float *data, Quaternion *q, VectorFloat *gravity) {
+ // yaw: (about Z axis)
+ data[0] = atan2(2*q -> x*q -> y - 2*q -> w*q -> z, 2*q -> w*q -> w + 2*q -> x*q -> x - 1);
+ // pitch: (nose up/down, about Y axis)
+ data[1] = atan2(gravity -> x , sqrt(gravity -> y*gravity -> y + gravity -> z*gravity -> z));
+ // roll: (tilt left/right, about X axis)
+ data[2] = atan2(gravity -> y , gravity -> z);
+ if (gravity -> z < 0) {
+ if(data[1] > 0) {
+ data[1] = PI - data[1];
+ } else {
+ data[1] = -PI - data[1];
+ }
+ }
+ return 0;
+}
+#endif
+
+// uint8_t MPU6050_6Axis_MotionApps20::dmpGetAccelFloat(float *data, const uint8_t* packet);
+// uint8_t MPU6050_6Axis_MotionApps20::dmpGetQuaternionFloat(float *data, const uint8_t* packet);
+
+uint8_t MPU6050_6Axis_MotionApps20::dmpProcessFIFOPacket(const unsigned char *dmpData) {
+ (void)dmpData; // unused parameter
+ /*for (uint8_t k = 0; k < dmpPacketSize; k++) {
+ if (dmpData[k] < 0x10) Serial.print("0");
+ Serial.print(dmpData[k], HEX);
+ Serial.print(" ");
+ }
+ Serial.print("\n");*/
+ //Serial.println((uint16_t)dmpPacketBuffer);
+ return 0;
+}
+uint8_t MPU6050_6Axis_MotionApps20::dmpReadAndProcessFIFOPacket(uint8_t numPackets, uint8_t *processed) {
+ uint8_t status;
+ uint8_t buf[dmpPacketSize];
+ for (uint8_t i = 0; i < numPackets; i++) {
+ // read packet from FIFO
+ getFIFOBytes(buf, dmpPacketSize);
+
+ // process packet
+ if ((status = dmpProcessFIFOPacket(buf)) > 0) return status;
+
+ // increment external process count variable, if supplied
+ if (processed != 0) (*processed)++;
+ }
+ return 0;
+}
+
+// uint8_t MPU6050_6Axis_MotionApps20::dmpSetFIFOProcessedCallback(void (*func) (void));
+
+// uint8_t MPU6050_6Axis_MotionApps20::dmpInitFIFOParam();
+// uint8_t MPU6050_6Axis_MotionApps20::dmpCloseFIFO();
+// uint8_t MPU6050_6Axis_MotionApps20::dmpSetGyroDataSource(uint_fast8_t source);
+// uint8_t MPU6050_6Axis_MotionApps20::dmpDecodeQuantizedAccel();
+// uint32_t MPU6050_6Axis_MotionApps20::dmpGetGyroSumOfSquare();
+// uint32_t MPU6050_6Axis_MotionApps20::dmpGetAccelSumOfSquare();
+// void MPU6050_6Axis_MotionApps20::dmpOverrideQuaternion(long *q);
+uint16_t MPU6050_6Axis_MotionApps20::dmpGetFIFOPacketSize() {
+ return dmpPacketSize;
+}
+
+
+
+uint8_t MPU6050_6Axis_MotionApps20::dmpGetCurrentFIFOPacket(uint8_t *data) { // overflow proof
+ return(GetCurrentFIFOPacket(data, dmpPacketSize));
+}
\ No newline at end of file
diff --git a/lib/MPU6050/src/MPU6050_6Axis_MotionApps20.h b/lib/MPU6050/src/MPU6050_6Axis_MotionApps20.h
new file mode 100644
index 0000000..98e7c34
--- /dev/null
+++ b/lib/MPU6050/src/MPU6050_6Axis_MotionApps20.h
@@ -0,0 +1,154 @@
+// I2Cdev library collection - MPU6050 I2C device class
+// Based on InvenSense MPU-6050 register map document rev. 2.0, 5/19/2011 (RM-MPU-6000A-00)
+// 10/3/2011 by Jeff Rowberg
+// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
+//
+// Changelog:
+// 2021/09/27 - split implementations out of header files, finally
+// ... - ongoing debug release
+
+// NOTE: THIS IS ONLY A PARIAL RELEASE. THIS DEVICE CLASS IS CURRENTLY UNDERGOING ACTIVE
+// DEVELOPMENT AND IS STILL MISSING SOME IMPORTANT FEATURES. PLEASE KEEP THIS IN MIND IF
+// YOU DECIDE TO USE THIS PARTICULAR CODE FOR ANYTHING.
+
+/* ============================================
+I2Cdev device library code is placed under the MIT license
+Copyright (c) 2012 Jeff Rowberg
+
+Permission is hereby granted, free of charge, to any person obtaining a copy
+of this software and associated documentation files (the "Software"), to deal
+in the Software without restriction, including without limitation the rights
+to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+copies of the Software, and to permit persons to whom the Software is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in
+all copies or substantial portions of the Software.
+
+THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+THE SOFTWARE.
+===============================================
+*/
+
+#ifndef _MPU6050_6AXIS_MOTIONAPPS20_H_
+#define _MPU6050_6AXIS_MOTIONAPPS20_H_
+
+// take ownership of the "MPU6050" typedef
+#define I2CDEVLIB_MPU6050_TYPEDEF
+
+#include "MPU6050.h"
+
+class MPU6050_6Axis_MotionApps20 : public MPU6050_Base {
+ public:
+ MPU6050_6Axis_MotionApps20(uint8_t address=MPU6050_DEFAULT_ADDRESS, void *wireObj=0) : MPU6050_Base(address, wireObj) { }
+
+ uint8_t dmpInitialize();
+ bool dmpPacketAvailable();
+
+ uint8_t dmpSetFIFORate(uint8_t fifoRate);
+ uint8_t dmpGetFIFORate();
+ uint8_t dmpGetSampleStepSizeMS();
+ uint8_t dmpGetSampleFrequency();
+ int32_t dmpDecodeTemperature(int8_t tempReg);
+
+ // Register callbacks after a packet of FIFO data is processed
+ //uint8_t dmpRegisterFIFORateProcess(inv_obj_func func, int16_t priority);
+ //uint8_t dmpUnregisterFIFORateProcess(inv_obj_func func);
+ uint8_t dmpRunFIFORateProcesses();
+
+ // Setup FIFO for various output
+ uint8_t dmpSendQuaternion(uint_fast16_t accuracy);
+ uint8_t dmpSendGyro(uint_fast16_t elements, uint_fast16_t accuracy);
+ uint8_t dmpSendAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+ uint8_t dmpSendLinearAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+ uint8_t dmpSendLinearAccelInWorld(uint_fast16_t elements, uint_fast16_t accuracy);
+ uint8_t dmpSendControlData(uint_fast16_t elements, uint_fast16_t accuracy);
+ uint8_t dmpSendSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
+ uint8_t dmpSendExternalSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
+ uint8_t dmpSendGravity(uint_fast16_t elements, uint_fast16_t accuracy);
+ uint8_t dmpSendPacketNumber(uint_fast16_t accuracy);
+ uint8_t dmpSendQuantizedAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+ uint8_t dmpSendEIS(uint_fast16_t elements, uint_fast16_t accuracy);
+
+ // Get Fixed Point data from FIFO
+ uint8_t dmpGetAccel(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetAccel(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetAccel(VectorInt16 *v, const uint8_t* packet=0);
+ uint8_t dmpGetQuaternion(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetQuaternion(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetQuaternion(Quaternion *q, const uint8_t* packet=0);
+ uint8_t dmpGet6AxisQuaternion(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGet6AxisQuaternion(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGet6AxisQuaternion(Quaternion *q, const uint8_t* packet=0);
+ uint8_t dmpGetRelativeQuaternion(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetRelativeQuaternion(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetRelativeQuaternion(Quaternion *data, const uint8_t* packet=0);
+ uint8_t dmpGetGyro(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetGyro(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetGyro(VectorInt16 *v, const uint8_t* packet=0);
+ uint8_t dmpSetLinearAccelFilterCoefficient(float coef);
+ uint8_t dmpGetLinearAccel(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetLinearAccel(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetLinearAccel(VectorInt16 *v, const uint8_t* packet=0);
+ uint8_t dmpGetLinearAccel(VectorInt16 *v, VectorInt16 *vRaw, VectorFloat *gravity);
+ uint8_t dmpConvertToWorldFrame(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpConvertToWorldFrame(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpConvertToWorldFrame(VectorInt16 *v, const uint8_t* packet=0);
+ uint8_t dmpConvertToWorldFrame(VectorInt16 *v, VectorInt16 *vReal, Quaternion *q);
+ uint8_t dmpGetGyroAndAccelSensor(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetGyroAndAccelSensor(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetGyroAndAccelSensor(VectorInt16 *g, VectorInt16 *a, const uint8_t* packet=0);
+ uint8_t dmpGetGyroSensor(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetGyroSensor(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetGyroSensor(VectorInt16 *v, const uint8_t* packet=0);
+ uint8_t dmpGetControlData(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetTemperature(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetGravity(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetGravity(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetGravity(VectorInt16 *v, const uint8_t* packet=0);
+ uint8_t dmpGetGravity(VectorFloat *v, Quaternion *q);
+ uint8_t dmpGetUnquantizedAccel(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetUnquantizedAccel(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetUnquantizedAccel(VectorInt16 *v, const uint8_t* packet=0);
+ uint8_t dmpGetQuantizedAccel(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetQuantizedAccel(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetQuantizedAccel(VectorInt16 *v, const uint8_t* packet=0);
+ uint8_t dmpGetExternalSensorData(int32_t *data, uint16_t size, const uint8_t* packet=0);
+ uint8_t dmpGetEIS(int32_t *data, const uint8_t* packet=0);
+
+ uint8_t dmpGetEuler(float *data, Quaternion *q);
+ uint8_t dmpGetYawPitchRoll(float *data, Quaternion *q, VectorFloat *gravity);
+
+ // Get Floating Point data from FIFO
+ uint8_t dmpGetAccelFloat(float *data, const uint8_t* packet=0);
+ uint8_t dmpGetQuaternionFloat(float *data, const uint8_t* packet=0);
+
+ uint8_t dmpProcessFIFOPacket(const unsigned char *dmpData);
+ uint8_t dmpReadAndProcessFIFOPacket(uint8_t numPackets, uint8_t *processed=NULL);
+
+ uint8_t dmpSetFIFOProcessedCallback(void (*func) (void));
+
+ uint8_t dmpInitFIFOParam();
+ uint8_t dmpCloseFIFO();
+ uint8_t dmpSetGyroDataSource(uint8_t source);
+ uint8_t dmpDecodeQuantizedAccel();
+ uint32_t dmpGetGyroSumOfSquare();
+ uint32_t dmpGetAccelSumOfSquare();
+ void dmpOverrideQuaternion(long *q);
+ uint16_t dmpGetFIFOPacketSize();
+ uint8_t dmpGetCurrentFIFOPacket(uint8_t *data); // overflow proof
+
+ private:
+ uint8_t *dmpPacketBuffer;
+ uint16_t dmpPacketSize;
+};
+
+typedef MPU6050_6Axis_MotionApps20 MPU6050;
+
+
+#endif /* _MPU6050_6AXIS_MOTIONAPPS20_H_ */
\ No newline at end of file
diff --git a/lib/MPU6050/src/MPU6050_6Axis_MotionApps612.cpp b/lib/MPU6050/src/MPU6050_6Axis_MotionApps612.cpp
new file mode 100644
index 0000000..5958c25
--- /dev/null
+++ b/lib/MPU6050/src/MPU6050_6Axis_MotionApps612.cpp
@@ -0,0 +1,627 @@
+// I2Cdev library collection - MPU6050 I2C device class, 6-axis MotionApps 6.12 implementation
+// Based on InvenSense MPU-6050 register map document rev. 2.0, 5/19/2011 (RM-MPU-6000A-00)
+// 5/20/2013 by Jeff Rowberg
+// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
+//
+// Changelog:
+// 2021/09/27 - split implementations out of header files, finally
+// 2019/07/10 - I incorporated DMP Firmware Version 6.12 Latest as of today with many features and bug fixes.
+// - MPU6050 Registers have not changed just the DMP Image so that full backwards compatibility is present
+// - Run-time calibration routine is enabled which calibrates after no motion state is detected
+// - once no motion state is detected Calibration completes within 0.5 seconds
+// - The Drawback is that the firmware image is larger.
+// ... - ongoing debug release
+
+/* ============================================
+I2Cdev device library code is placed under the MIT license
+Copyright (c) 2012 Jeff Rowberg
+
+Permission is hereby granted, free of charge, to any person obtaining a copy
+of this software and associated documentation files (the "Software"), to deal
+in the Software without restriction, including without limitation the rights
+to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+copies of the Software, and to permit persons to whom the Software is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in
+all copies or substantial portions of the Software.
+
+THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+THE SOFTWARE.
+===============================================
+*/
+
+// MotionApps 2.0 DMP implementation, built using the MPU-6050EVB evaluation board
+#define MPU6050_INCLUDE_DMP_MOTIONAPPS612
+
+#include "MPU6050_6Axis_MotionApps612.h"
+
+// Tom Carpenter's conditional PROGMEM code
+// http://forum.arduino.cc/index.php?topic=129407.0
+#ifdef __AVR__
+ #include
+#elif defined(ESP32)
+ #include
+#else
+ // Teensy 3.0 library conditional PROGMEM code from Paul Stoffregen
+ #ifndef __PGMSPACE_H_
+ #define __PGMSPACE_H_ 1
+ #include
+
+ #define PROGMEM
+ #define PGM_P const char *
+ #define PSTR(str) (str)
+ #define F(x) x
+
+ typedef void prog_void;
+ typedef char prog_char;
+ typedef unsigned char prog_uchar;
+ typedef int8_t prog_int8_t;
+ typedef uint8_t prog_uint8_t;
+ typedef int16_t prog_int16_t;
+ typedef uint16_t prog_uint16_t;
+ typedef int32_t prog_int32_t;
+ typedef uint32_t prog_uint32_t;
+
+ #define strcpy_P(dest, src) strcpy((dest), (src))
+ #define strcat_P(dest, src) strcat((dest), (src))
+ #define strcmp_P(a, b) strcmp((a), (b))
+
+ #define pgm_read_byte(addr) (*(const unsigned char *)(addr))
+ #define pgm_read_word(addr) (*(const unsigned short *)(addr))
+ #define pgm_read_dword(addr) (*(const unsigned long *)(addr))
+ #define pgm_read_float(addr) (*(const float *)(addr))
+
+ #define pgm_read_byte_near(addr) pgm_read_byte(addr)
+ #define pgm_read_word_near(addr) pgm_read_word(addr)
+ #define pgm_read_dword_near(addr) pgm_read_dword(addr)
+ #define pgm_read_float_near(addr) pgm_read_float(addr)
+ #define pgm_read_byte_far(addr) pgm_read_byte(addr)
+ #define pgm_read_word_far(addr) pgm_read_word(addr)
+ #define pgm_read_dword_far(addr) pgm_read_dword(addr)
+ #define pgm_read_float_far(addr) pgm_read_float(addr)
+ #endif
+#endif
+
+/* Source is from the InvenSense MotionApps v2 demo code. Original source is
+ * unavailable, unless you happen to be amazing as decompiling binary by
+ * hand (in which case, please contact me, and I'm totally serious).
+ *
+ * Also, I'd like to offer many, many thanks to Noah Zerkin for all of the
+ * DMP reverse-engineering he did to help make this bit of wizardry
+ * possible.
+ */
+
+// NOTE! Enabling DEBUG adds about 3.3kB to the flash program size.
+// Debug output is now working even on ATMega328P MCUs (e.g. Arduino Uno)
+// after moving string constants to flash memory storage using the F()
+// compiler macro (Arduino IDE 1.0+ required).
+
+//#define DEBUG
+/* Control whether debugging macros are active at compile time */
+#undef DB_ACTIVE
+#ifdef DEBUG
+#define DB_ACTIVE 1
+#else
+#define DB_ACTIVE 0
+#endif /* DEBUG */
+
+/*
+** Usage: DB_PRINT((...));
+** Usage: DB_PRINTLN((...));
+**
+** "..." is whatever extra arguments fmt requires (possibly nothing).
+**
+** The structure of the macros means that the code is always validated
+** but is not called when DEBUG is undefined.
+** -- See chapter 8 of 'The Practice of Programming', by Kernighan and Pike.
+*/
+#define DEBUG_PRINT(...)\
+ do { if (DB_ACTIVE) Serial.print(__VA_ARGS__); } while (0)
+#define DEBUG_PRINTF(...)\
+ do { if (DB_ACTIVE) Serial.printf(__VA_ARGS__); } while (0)
+#define DEBUG_PRINTLN(...)\
+ do { if (DB_ACTIVE) Serial.println(__VA_ARGS__); } while (0)
+#define DEBUG_PRINTLNF(x, y)\
+ do { if (DB_ACTIVE) Serial.println(x, y); } while (0)
+
+#define MPU6050_DMP_CODE_SIZE 3062 // dmpMemory[]
+
+/* ================================================================ *
+ | Default MotionApps v6.12 28-byte FIFO packet structure: |
+ | |
+ | [QUAT W][ ][QUAT X][ ][QUAT Y][ ][QUAT Z][ ] |
+ | 0 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 |
+ | |
+ | [GYRO X][GYRO Y][GYRO Z][ACC X ][ACC Y ][ACC Z ] |
+ | 16 17 18 19 20 21 22 23 24 25 26 27 |
+ * ================================================================ */
+
+// this block of memory gets written to the MPU on start-up, and it seems
+// to be volatile memory, so it has to be done each time (it only takes ~1
+// second though)
+
+// *** this is a capture of the DMP Firmware V6.1.2 after all the messy changes were made so we can just load it
+const unsigned char dmpMemory[MPU6050_DMP_CODE_SIZE] PROGMEM = {
+/* bank # 0 */
+0x00, 0xF8, 0xF6, 0x2A, 0x3F, 0x68, 0xF5, 0x7A, 0x00, 0x06, 0xFF, 0xFE, 0x00, 0x03, 0x00, 0x00,
+0x00, 0x65, 0x00, 0x54, 0xFF, 0xEF, 0x00, 0x00, 0xFA, 0x80, 0x00, 0x0B, 0x12, 0x82, 0x00, 0x01,
+0x03, 0x0C, 0x30, 0xC3, 0x0A, 0x74, 0x56, 0x2D, 0x0D, 0x62, 0xDB, 0xC7, 0x16, 0xF4, 0xBA, 0x02,
+0x38, 0x83, 0xF8, 0x83, 0x30, 0x00, 0xF8, 0x83, 0x25, 0x8E, 0xF8, 0x83, 0x30, 0x00, 0xF8, 0x83,
+0xFF, 0xFF, 0xFF, 0xFF, 0x0C, 0xBD, 0xD8, 0x11, 0x24, 0x00, 0x04, 0x00, 0x1A, 0x82, 0x79, 0xA1,
+0x00, 0x36, 0x00, 0x3C, 0x00, 0x00, 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x38, 0x83, 0x6F, 0xA2,
+0x00, 0x3E, 0x03, 0x30, 0x40, 0x00, 0x00, 0x00, 0x02, 0xCA, 0xE3, 0x09, 0x3E, 0x80, 0x00, 0x00,
+0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x60, 0x00, 0x00, 0x00,
+0x1F, 0xA4, 0xE8, 0xE4, 0xFF, 0xF5, 0xDC, 0xB9, 0x00, 0x5B, 0x79, 0xCF, 0x1F, 0x3F, 0x78, 0x76,
+0x00, 0x86, 0x7C, 0x5A, 0x00, 0x86, 0x23, 0x47, 0xFA, 0xB9, 0x86, 0x31, 0x00, 0x74, 0x87, 0x8A,
+0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x43, 0x05, 0xFF, 0xFF, 0xE9, 0xA8, 0x00, 0x00, 0x21, 0x82,
+0xFA, 0xB8, 0x4D, 0x46, 0xFF, 0xFA, 0xDF, 0x3D, 0xFF, 0xFF, 0xB2, 0xB3, 0x00, 0x00, 0x00, 0x00,
+0x3F, 0xFF, 0xBA, 0x98, 0x00, 0x5D, 0xAC, 0x08, 0x00, 0x0A, 0x63, 0x78, 0x00, 0x01, 0x46, 0x21,
+0xFF, 0xFF, 0x00, 0x00, 0x00, 0x00, 0x42, 0xB5, 0x00, 0x06, 0x00, 0x64, 0x00, 0x64, 0x00, 0x06,
+0x14, 0x06, 0x02, 0x9F, 0x0F, 0x47, 0x91, 0x32, 0xD9, 0x0E, 0x9F, 0xC9, 0x1D, 0xCF, 0x4C, 0x34,
+0x3B, 0xB6, 0x7A, 0xE8, 0x00, 0x64, 0x00, 0x06, 0x00, 0xC8, 0x00, 0x00, 0x00, 0x00, 0xFF, 0xFE,
+/* bank # 1 */
+0x10, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+0x00, 0x07, 0x00, 0x00, 0xFF, 0xF1, 0x00, 0x00, 0xFA, 0x46, 0x00, 0x00, 0xA2, 0xB8, 0x00, 0x00,
+0x10, 0x00, 0x00, 0x00, 0x04, 0xD6, 0x00, 0x00, 0x04, 0xCC, 0x00, 0x00, 0x04, 0xCC, 0x00, 0x00,
+0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+0x00, 0x06, 0x00, 0x02, 0x00, 0x05, 0x00, 0x07, 0x00, 0x00, 0x00, 0x00, 0x00, 0x64, 0x00, 0x00,
+0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0C, 0x00, 0x05, 0x00, 0x64, 0x00, 0x20, 0x00, 0x00,
+0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x03, 0x00,
+0x00, 0x00, 0x00, 0x32, 0xF8, 0x98, 0x00, 0x00, 0xFF, 0x65, 0x00, 0x00, 0x83, 0x0F, 0x00, 0x00,
+0x00, 0x06, 0x00, 0x00, 0xFF, 0xF1, 0x00, 0x00, 0xFA, 0x46, 0x00, 0x00, 0xA2, 0xB8, 0x00, 0x00,
+0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+0x00, 0x00, 0x00, 0x32, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x10, 0x00,
+0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x0D, 0x00, 0x00, 0xB2, 0x6A, 0x00, 0x02, 0x00, 0x00,
+0x00, 0x01, 0xFB, 0x83, 0x00, 0x7C, 0x00, 0x00, 0xFB, 0x15, 0xFC, 0x00, 0x1F, 0xB4, 0xFF, 0x83,
+0x00, 0x00, 0x00, 0x01, 0x00, 0x65, 0x00, 0x07, 0x00, 0x64, 0x03, 0xE8, 0x00, 0x64, 0x00, 0x28,
+0x00, 0x00, 0xFF, 0xFD, 0x00, 0x00, 0x00, 0x00, 0x16, 0xA0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+0x00, 0x00, 0x10, 0x00, 0x00, 0x2F, 0x00, 0x00, 0x00, 0x00, 0x01, 0xF4, 0x00, 0x00, 0x10, 0x00,
+/* bank # 2 */
+0x00, 0x28, 0x00, 0x00, 0xFF, 0xFF, 0x45, 0x81, 0xFF, 0xFF, 0xFA, 0x72, 0x00, 0x00, 0x00, 0x00,
+0x00, 0x00, 0x00, 0x00, 0x00, 0x44, 0x00, 0x01, 0x00, 0x05, 0xBA, 0xC6, 0x00, 0x47, 0x78, 0xA2,
+0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00, 0x14,
+0x00, 0x00, 0x23, 0xBB, 0x00, 0x2E, 0xA2, 0x5B, 0x00, 0x00, 0x05, 0x68, 0x00, 0x0B, 0xCF, 0x49,
+0x00, 0x04, 0xFF, 0xFD, 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x00,
+0x00, 0x1B, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+0x00, 0x64, 0x00, 0x07, 0x00, 0x08, 0x00, 0x06, 0x00, 0x06, 0xFF, 0xFE, 0x00, 0x00, 0x00, 0x00,
+0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+0x00, 0x2E, 0xA2, 0x5B, 0x00, 0x00, 0x05, 0x68, 0x00, 0x0B, 0xCF, 0x49, 0x00, 0x00, 0x00, 0x00,
+0x00, 0xF8, 0xF6, 0x2A, 0x3F, 0x68, 0xF5, 0x7A, 0x00, 0x04, 0xFF, 0xFD, 0x00, 0x02, 0x00, 0x00,
+0x00, 0x1B, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0E, 0x00, 0x0E,
+0xFF, 0xFF, 0xFF, 0xCF, 0x00, 0x04, 0x00, 0x00, 0x00, 0x00, 0x00, 0x32, 0xFF, 0xFF, 0xFF, 0x9C,
+0x00, 0x00, 0x43, 0x05, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x64,
+0xFF, 0xE5, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+/* bank # 3 */
+0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+0x00, 0x01, 0x80, 0x00, 0x00, 0x01, 0x80, 0x00, 0x00, 0x01, 0x80, 0x00, 0x00, 0x24, 0x26, 0xD3,
+0x00, 0x01, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x00, 0x10, 0x00, 0x96, 0x00, 0x3C,
+0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x1F, 0x9E, 0x65, 0x5D,
+0x0C, 0x0A, 0x4E, 0x68, 0xCD, 0xCF, 0x77, 0x09, 0x50, 0x16, 0x67, 0x59, 0xC6, 0x19, 0xCE, 0x82,
+0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x47, 0x71, 0x1C,
+0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x17, 0xD7, 0x84, 0x00, 0x03, 0x00, 0x00, 0x00,
+0x00, 0x11, 0xDC, 0x47, 0x03, 0x00, 0x00, 0x00, 0xC7, 0x93, 0x8F, 0x9D, 0x1E, 0x1B, 0x1C, 0x19,
+0xFF, 0xFF, 0xFF, 0xFF, 0x00, 0x00, 0x00, 0x00, 0x0E, 0xDF, 0xA4, 0x38, 0x1F, 0x9E, 0x65, 0x5D,
+0x00, 0x00, 0x00, 0x00, 0x00, 0x47, 0x71, 0x1C, 0x02, 0x03, 0x18, 0x85, 0x00, 0x00, 0x40, 0x00,
+0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+0x3F, 0xFF, 0xFF, 0xFD, 0xFF, 0xFF, 0xF4, 0xC9, 0xFF, 0xFF, 0xBC, 0xF0, 0x00, 0x01, 0x0C, 0x0F,
+0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+0xF5, 0xB7, 0xBA, 0xB3, 0x67, 0x7D, 0xDF, 0x7E, 0x72, 0x90, 0x2E, 0x55, 0x4C, 0xF6, 0xE6, 0x88,
+0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+/* bank # 4 */
+0xD8, 0xDC, 0xB4, 0xB8, 0xB0, 0xD8, 0xB9, 0xAB, 0xF3, 0xF8, 0xFA, 0xB3, 0xB7, 0xBB, 0x8E, 0x9E,
+0xAE, 0xF1, 0x32, 0xF5, 0x1B, 0xF1, 0xB4, 0xB8, 0xB0, 0x80, 0x97, 0xF1, 0xA9, 0xDF, 0xDF, 0xDF,
+0xAA, 0xDF, 0xDF, 0xDF, 0xF2, 0xAA, 0x4C, 0xCD, 0x6C, 0xA9, 0x0C, 0xC9, 0x2C, 0x97, 0xF1, 0xA9,
+0x89, 0x26, 0x46, 0x66, 0xB2, 0x89, 0x99, 0xA9, 0x2D, 0x55, 0x7D, 0xB0, 0xB0, 0x8A, 0xA8, 0x96,
+0x36, 0x56, 0x76, 0xF1, 0xBA, 0xA3, 0xB4, 0xB2, 0x80, 0xC0, 0xB8, 0xA8, 0x97, 0x11, 0xB2, 0x83,
+0x98, 0xBA, 0xA3, 0xF0, 0x24, 0x08, 0x44, 0x10, 0x64, 0x18, 0xB2, 0xB9, 0xB4, 0x98, 0x83, 0xF1,
+0xA3, 0x29, 0x55, 0x7D, 0xBA, 0xB5, 0xB1, 0xA3, 0x83, 0x93, 0xF0, 0x00, 0x28, 0x50, 0xF5, 0xB2,
+0xB6, 0xAA, 0x83, 0x93, 0x28, 0x54, 0x7C, 0xF1, 0xB9, 0xA3, 0x82, 0x93, 0x61, 0xBA, 0xA2, 0xDA,
+0xDE, 0xDF, 0xDB, 0x81, 0x9A, 0xB9, 0xAE, 0xF5, 0x60, 0x68, 0x70, 0xF1, 0xDA, 0xBA, 0xA2, 0xDF,
+0xD9, 0xBA, 0xA2, 0xFA, 0xB9, 0xA3, 0x82, 0x92, 0xDB, 0x31, 0xBA, 0xA2, 0xD9, 0xBA, 0xA2, 0xF8,
+0xDF, 0x85, 0xA4, 0xD0, 0xC1, 0xBB, 0xAD, 0x83, 0xC2, 0xC5, 0xC7, 0xB8, 0xA2, 0xDF, 0xDF, 0xDF,
+0xBA, 0xA0, 0xDF, 0xDF, 0xDF, 0xD8, 0xD8, 0xF1, 0xB8, 0xAA, 0xB3, 0x8D, 0xB4, 0x98, 0x0D, 0x35,
+0x5D, 0xB2, 0xB6, 0xBA, 0xAF, 0x8C, 0x96, 0x19, 0x8F, 0x9F, 0xA7, 0x0E, 0x16, 0x1E, 0xB4, 0x9A,
+0xB8, 0xAA, 0x87, 0x2C, 0x54, 0x7C, 0xBA, 0xA4, 0xB0, 0x8A, 0xB6, 0x91, 0x32, 0x56, 0x76, 0xB2,
+0x84, 0x94, 0xA4, 0xC8, 0x08, 0xCD, 0xD8, 0xB8, 0xB4, 0xB0, 0xF1, 0x99, 0x82, 0xA8, 0x2D, 0x55,
+0x7D, 0x98, 0xA8, 0x0E, 0x16, 0x1E, 0xA2, 0x2C, 0x54, 0x7C, 0x92, 0xA4, 0xF0, 0x2C, 0x50, 0x78,
+/* bank # 5 */
+0xF1, 0x84, 0xA8, 0x98, 0xC4, 0xCD, 0xFC, 0xD8, 0x0D, 0xDB, 0xA8, 0xFC, 0x2D, 0xF3, 0xD9, 0xBA,
+0xA6, 0xF8, 0xDA, 0xBA, 0xA6, 0xDE, 0xD8, 0xBA, 0xB2, 0xB6, 0x86, 0x96, 0xA6, 0xD0, 0xF3, 0xC8,
+0x41, 0xDA, 0xA6, 0xC8, 0xF8, 0xD8, 0xB0, 0xB4, 0xB8, 0x82, 0xA8, 0x92, 0xF5, 0x2C, 0x54, 0x88,
+0x98, 0xF1, 0x35, 0xD9, 0xF4, 0x18, 0xD8, 0xF1, 0xA2, 0xD0, 0xF8, 0xF9, 0xA8, 0x84, 0xD9, 0xC7,
+0xDF, 0xF8, 0xF8, 0x83, 0xC5, 0xDA, 0xDF, 0x69, 0xDF, 0x83, 0xC1, 0xD8, 0xF4, 0x01, 0x14, 0xF1,
+0xA8, 0x82, 0x4E, 0xA8, 0x84, 0xF3, 0x11, 0xD1, 0x82, 0xF5, 0xD9, 0x92, 0x28, 0x97, 0x88, 0xF1,
+0x09, 0xF4, 0x1C, 0x1C, 0xD8, 0x84, 0xA8, 0xF3, 0xC0, 0xF9, 0xD1, 0xD9, 0x97, 0x82, 0xF1, 0x29,
+0xF4, 0x0D, 0xD8, 0xF3, 0xF9, 0xF9, 0xD1, 0xD9, 0x82, 0xF4, 0xC2, 0x03, 0xD8, 0xDE, 0xDF, 0x1A,
+0xD8, 0xF1, 0xA2, 0xFA, 0xF9, 0xA8, 0x84, 0x98, 0xD9, 0xC7, 0xDF, 0xF8, 0xF8, 0xF8, 0x83, 0xC7,
+0xDA, 0xDF, 0x69, 0xDF, 0xF8, 0x83, 0xC3, 0xD8, 0xF4, 0x01, 0x14, 0xF1, 0x98, 0xA8, 0x82, 0x2E,
+0xA8, 0x84, 0xF3, 0x11, 0xD1, 0x82, 0xF5, 0xD9, 0x92, 0x50, 0x97, 0x88, 0xF1, 0x09, 0xF4, 0x1C,
+0xD8, 0x84, 0xA8, 0xF3, 0xC0, 0xF8, 0xF9, 0xD1, 0xD9, 0x97, 0x82, 0xF1, 0x49, 0xF4, 0x0D, 0xD8,
+0xF3, 0xF9, 0xF9, 0xD1, 0xD9, 0x82, 0xF4, 0xC4, 0x03, 0xD8, 0xDE, 0xDF, 0xD8, 0xF1, 0xAD, 0x88,
+0x98, 0xCC, 0xA8, 0x09, 0xF9, 0xD9, 0x82, 0x92, 0xA8, 0xF5, 0x7C, 0xF1, 0x88, 0x3A, 0xCF, 0x94,
+0x4A, 0x6E, 0x98, 0xDB, 0x69, 0x31, 0xDA, 0xAD, 0xF2, 0xDE, 0xF9, 0xD8, 0x87, 0x95, 0xA8, 0xF2,
+0x21, 0xD1, 0xDA, 0xA5, 0xF9, 0xF4, 0x17, 0xD9, 0xF1, 0xAE, 0x8E, 0xD0, 0xC0, 0xC3, 0xAE, 0x82,
+/* bank # 6 */
+0xC6, 0x84, 0xC3, 0xA8, 0x85, 0x95, 0xC8, 0xA5, 0x88, 0xF2, 0xC0, 0xF1, 0xF4, 0x01, 0x0E, 0xF1,
+0x8E, 0x9E, 0xA8, 0xC6, 0x3E, 0x56, 0xF5, 0x54, 0xF1, 0x88, 0x72, 0xF4, 0x01, 0x15, 0xF1, 0x98,
+0x45, 0x85, 0x6E, 0xF5, 0x8E, 0x9E, 0x04, 0x88, 0xF1, 0x42, 0x98, 0x5A, 0x8E, 0x9E, 0x06, 0x88,
+0x69, 0xF4, 0x01, 0x1C, 0xF1, 0x98, 0x1E, 0x11, 0x08, 0xD0, 0xF5, 0x04, 0xF1, 0x1E, 0x97, 0x02,
+0x02, 0x98, 0x36, 0x25, 0xDB, 0xF9, 0xD9, 0x85, 0xA5, 0xF3, 0xC1, 0xDA, 0x85, 0xA5, 0xF3, 0xDF,
+0xD8, 0x85, 0x95, 0xA8, 0xF3, 0x09, 0xDA, 0xA5, 0xFA, 0xD8, 0x82, 0x92, 0xA8, 0xF5, 0x78, 0xF1,
+0x88, 0x1A, 0x84, 0x9F, 0x26, 0x88, 0x98, 0x21, 0xDA, 0xF4, 0x1D, 0xF3, 0xD8, 0x87, 0x9F, 0x39,
+0xD1, 0xAF, 0xD9, 0xDF, 0xDF, 0xFB, 0xF9, 0xF4, 0x0C, 0xF3, 0xD8, 0xFA, 0xD0, 0xF8, 0xDA, 0xF9,
+0xF9, 0xD0, 0xDF, 0xD9, 0xF9, 0xD8, 0xF4, 0x0B, 0xD8, 0xF3, 0x87, 0x9F, 0x39, 0xD1, 0xAF, 0xD9,
+0xDF, 0xDF, 0xF4, 0x1D, 0xF3, 0xD8, 0xFA, 0xFC, 0xA8, 0x69, 0xF9, 0xF9, 0xAF, 0xD0, 0xDA, 0xDE,
+0xFA, 0xD9, 0xF8, 0x8F, 0x9F, 0xA8, 0xF1, 0xCC, 0xF3, 0x98, 0xDB, 0x45, 0xD9, 0xAF, 0xDF, 0xD0,
+0xF8, 0xD8, 0xF1, 0x8F, 0x9F, 0xA8, 0xCA, 0xF3, 0x88, 0x09, 0xDA, 0xAF, 0x8F, 0xCB, 0xF8, 0xD8,
+0xF2, 0xAD, 0x97, 0x8D, 0x0C, 0xD9, 0xA5, 0xDF, 0xF9, 0xBA, 0xA6, 0xF3, 0xFA, 0xF4, 0x12, 0xF2,
+0xD8, 0x95, 0x0D, 0xD1, 0xD9, 0xBA, 0xA6, 0xF3, 0xFA, 0xDA, 0xA5, 0xF2, 0xC1, 0xBA, 0xA6, 0xF3,
+0xDF, 0xD8, 0xF1, 0xBA, 0xB2, 0xB6, 0x86, 0x96, 0xA6, 0xD0, 0xCA, 0xF3, 0x49, 0xDA, 0xA6, 0xCB,
+0xF8, 0xD8, 0xB0, 0xB4, 0xB8, 0xD8, 0xAD, 0x84, 0xF2, 0xC0, 0xDF, 0xF1, 0x8F, 0xCB, 0xC3, 0xA8,
+/* bank # 7 */
+0xB2, 0xB6, 0x86, 0x96, 0xC8, 0xC1, 0xCB, 0xC3, 0xF3, 0xB0, 0xB4, 0x88, 0x98, 0xA8, 0x21, 0xDB,
+0x71, 0x8D, 0x9D, 0x71, 0x85, 0x95, 0x21, 0xD9, 0xAD, 0xF2, 0xFA, 0xD8, 0x85, 0x97, 0xA8, 0x28,
+0xD9, 0xF4, 0x08, 0xD8, 0xF2, 0x8D, 0x29, 0xDA, 0xF4, 0x05, 0xD9, 0xF2, 0x85, 0xA4, 0xC2, 0xF2,
+0xD8, 0xA8, 0x8D, 0x94, 0x01, 0xD1, 0xD9, 0xF4, 0x11, 0xF2, 0xD8, 0x87, 0x21, 0xD8, 0xF4, 0x0A,
+0xD8, 0xF2, 0x84, 0x98, 0xA8, 0xC8, 0x01, 0xD1, 0xD9, 0xF4, 0x11, 0xD8, 0xF3, 0xA4, 0xC8, 0xBB,
+0xAF, 0xD0, 0xF2, 0xDE, 0xF8, 0xF8, 0xF8, 0xF8, 0xF8, 0xF8, 0xF8, 0xF8, 0xD8, 0xF1, 0xB8, 0xF6,
+0xB5, 0xB9, 0xB0, 0x8A, 0x95, 0xA3, 0xDE, 0x3C, 0xA3, 0xD9, 0xF8, 0xD8, 0x5C, 0xA3, 0xD9, 0xF8,
+0xD8, 0x7C, 0xA3, 0xD9, 0xF8, 0xD8, 0xF8, 0xF9, 0xD1, 0xA5, 0xD9, 0xDF, 0xDA, 0xFA, 0xD8, 0xB1,
+0x85, 0x30, 0xF7, 0xD9, 0xDE, 0xD8, 0xF8, 0x30, 0xAD, 0xDA, 0xDE, 0xD8, 0xF2, 0xB4, 0x8C, 0x99,
+0xA3, 0x2D, 0x55, 0x7D, 0xA0, 0x83, 0xDF, 0xDF, 0xDF, 0xB5, 0x91, 0xA0, 0xF6, 0x29, 0xD9, 0xFB,
+0xD8, 0xA0, 0xFC, 0x29, 0xD9, 0xFA, 0xD8, 0xA0, 0xD0, 0x51, 0xD9, 0xF8, 0xD8, 0xFC, 0x51, 0xD9,
+0xF9, 0xD8, 0x79, 0xD9, 0xFB, 0xD8, 0xA0, 0xD0, 0xFC, 0x79, 0xD9, 0xFA, 0xD8, 0xA1, 0xF9, 0xF9,
+0xF9, 0xF9, 0xF9, 0xA0, 0xDA, 0xDF, 0xDF, 0xDF, 0xD8, 0xA1, 0xF8, 0xF8, 0xF8, 0xF8, 0xF8, 0xAC,
+0xDE, 0xF8, 0xAD, 0xDE, 0x83, 0x93, 0xAC, 0x2C, 0x54, 0x7C, 0xF1, 0xA8, 0xDF, 0xDF, 0xDF, 0xF6,
+0x9D, 0x2C, 0xDA, 0xA0, 0xDF, 0xD9, 0xFA, 0xDB, 0x2D, 0xF8, 0xD8, 0xA8, 0x50, 0xDA, 0xA0, 0xD0,
+0xDE, 0xD9, 0xD0, 0xF8, 0xF8, 0xF8, 0xDB, 0x55, 0xF8, 0xD8, 0xA8, 0x78, 0xDA, 0xA0, 0xD0, 0xDF,
+/* bank # 8 */
+0xD9, 0xD0, 0xFA, 0xF8, 0xF8, 0xF8, 0xF8, 0xDB, 0x7D, 0xF8, 0xD8, 0x9C, 0xA8, 0x8C, 0xF5, 0x30,
+0xDB, 0x38, 0xD9, 0xD0, 0xDE, 0xDF, 0xA0, 0xD0, 0xDE, 0xDF, 0xD8, 0xA8, 0x48, 0xDB, 0x58, 0xD9,
+0xDF, 0xD0, 0xDE, 0xA0, 0xDF, 0xD0, 0xDE, 0xD8, 0xA8, 0x68, 0xDB, 0x70, 0xD9, 0xDF, 0xDF, 0xA0,
+0xDF, 0xDF, 0xD8, 0xF1, 0xA8, 0x88, 0x90, 0x2C, 0x54, 0x7C, 0x98, 0xA8, 0xD0, 0x5C, 0x38, 0xD1,
+0xDA, 0xF2, 0xAE, 0x8C, 0xDF, 0xF9, 0xD8, 0xB0, 0x87, 0xA8, 0xC1, 0xC1, 0xB1, 0x88, 0xA8, 0xC6,
+0xF9, 0xF9, 0xDA, 0x36, 0xD8, 0xA8, 0xF9, 0xDA, 0x36, 0xD8, 0xA8, 0xF9, 0xDA, 0x36, 0xD8, 0xA8,
+0xF9, 0xDA, 0x36, 0xD8, 0xA8, 0xF9, 0xDA, 0x36, 0xD8, 0xF7, 0x8D, 0x9D, 0xAD, 0xF8, 0x18, 0xDA,
+0xF2, 0xAE, 0xDF, 0xD8, 0xF7, 0xAD, 0xFA, 0x30, 0xD9, 0xA4, 0xDE, 0xF9, 0xD8, 0xF2, 0xAE, 0xDE,
+0xFA, 0xF9, 0x83, 0xA7, 0xD9, 0xC3, 0xC5, 0xC7, 0xF1, 0x88, 0x9B, 0xA7, 0x7A, 0xAD, 0xF7, 0xDE,
+0xDF, 0xA4, 0xF8, 0x84, 0x94, 0x08, 0xA7, 0x97, 0xF3, 0x00, 0xAE, 0xF2, 0x98, 0x19, 0xA4, 0x88,
+0xC6, 0xA3, 0x94, 0x88, 0xF6, 0x32, 0xDF, 0xF2, 0x83, 0x93, 0xDB, 0x09, 0xD9, 0xF2, 0xAA, 0xDF,
+0xD8, 0xD8, 0xAE, 0xF8, 0xF9, 0xD1, 0xDA, 0xF3, 0xA4, 0xDE, 0xA7, 0xF1, 0x88, 0x9B, 0x7A, 0xD8,
+0xF3, 0x84, 0x94, 0xAE, 0x19, 0xF9, 0xDA, 0xAA, 0xF1, 0xDF, 0xD8, 0xA8, 0x81, 0xC0, 0xC3, 0xC5,
+0xC7, 0xA3, 0x92, 0x83, 0xF6, 0x28, 0xAD, 0xDE, 0xD9, 0xF8, 0xD8, 0xA3, 0x50, 0xAD, 0xD9, 0xF8,
+0xD8, 0xA3, 0x78, 0xAD, 0xD9, 0xF8, 0xD8, 0xF8, 0xF9, 0xD1, 0xA1, 0xDA, 0xDE, 0xC3, 0xC5, 0xC7,
+0xD8, 0xA1, 0x81, 0x94, 0xF8, 0x18, 0xF2, 0xB0, 0x89, 0xAC, 0xC3, 0xC5, 0xC7, 0xF1, 0xD8, 0xB8,
+/* bank # 9 */
+0xB4, 0xB0, 0x97, 0x86, 0xA8, 0x31, 0x9B, 0x06, 0x99, 0x07, 0xAB, 0x97, 0x28, 0x88, 0x9B, 0xF0,
+0x0C, 0x20, 0x14, 0x40, 0xB0, 0xB4, 0xB8, 0xF0, 0xA8, 0x8A, 0x9A, 0x28, 0x50, 0x78, 0xB7, 0x9B,
+0xA8, 0x29, 0x51, 0x79, 0x24, 0x70, 0x59, 0x44, 0x69, 0x38, 0x64, 0x48, 0x31, 0xF1, 0xBB, 0xAB,
+0x88, 0x00, 0x2C, 0x54, 0x7C, 0xF0, 0xB3, 0x8B, 0xB8, 0xA8, 0x04, 0x28, 0x50, 0x78, 0xF1, 0xB0,
+0x88, 0xB4, 0x97, 0x26, 0xA8, 0x59, 0x98, 0xBB, 0xAB, 0xB3, 0x8B, 0x02, 0x26, 0x46, 0x66, 0xB0,
+0xB8, 0xF0, 0x8A, 0x9C, 0xA8, 0x29, 0x51, 0x79, 0x8B, 0x29, 0x51, 0x79, 0x8A, 0x24, 0x70, 0x59,
+0x8B, 0x20, 0x58, 0x71, 0x8A, 0x44, 0x69, 0x38, 0x8B, 0x39, 0x40, 0x68, 0x8A, 0x64, 0x48, 0x31,
+0x8B, 0x30, 0x49, 0x60, 0x88, 0xF1, 0xAC, 0x00, 0x2C, 0x54, 0x7C, 0xF0, 0x8C, 0xA8, 0x04, 0x28,
+0x50, 0x78, 0xF1, 0x88, 0x97, 0x26, 0xA8, 0x59, 0x98, 0xAC, 0x8C, 0x02, 0x26, 0x46, 0x66, 0xF0,
+0x89, 0x9C, 0xA8, 0x29, 0x51, 0x79, 0x24, 0x70, 0x59, 0x44, 0x69, 0x38, 0x64, 0x48, 0x31, 0xA9,
+0x88, 0x09, 0x20, 0x59, 0x70, 0xAB, 0x11, 0x38, 0x40, 0x69, 0xA8, 0x19, 0x31, 0x48, 0x60, 0x8C,
+0xA8, 0x3C, 0x41, 0x5C, 0x20, 0x7C, 0x00, 0xF1, 0x87, 0x98, 0x19, 0x86, 0xA8, 0x6E, 0x76, 0x7E,
+0xA9, 0x99, 0x88, 0x2D, 0x55, 0x7D, 0xD8, 0xB1, 0xB5, 0xB9, 0xA3, 0xDF, 0xDF, 0xDF, 0xAE, 0xD0,
+0xDF, 0xAA, 0xD0, 0xDE, 0xF2, 0xAB, 0xF8, 0xF9, 0xD9, 0xB0, 0x87, 0xC4, 0xAA, 0xF1, 0xDF, 0xDF,
+0xBB, 0xAF, 0xDF, 0xDF, 0xB9, 0xD8, 0xB1, 0xF1, 0xA3, 0x97, 0x8E, 0x60, 0xDF, 0xB0, 0x84, 0xF2,
+0xC8, 0xF8, 0xF9, 0xD9, 0xDE, 0xD8, 0x93, 0x85, 0xF1, 0x4A, 0xB1, 0x83, 0xA3, 0x08, 0xB5, 0x83,
+/* bank # 10 */
+0x9A, 0x08, 0x10, 0xB7, 0x9F, 0x10, 0xD8, 0xF1, 0xB0, 0xBA, 0xAE, 0xB0, 0x8A, 0xC2, 0xB2, 0xB6,
+0x8E, 0x9E, 0xF1, 0xFB, 0xD9, 0xF4, 0x1D, 0xD8, 0xF9, 0xD9, 0x0C, 0xF1, 0xD8, 0xF8, 0xF8, 0xAD,
+0x61, 0xD9, 0xAE, 0xFB, 0xD8, 0xF4, 0x0C, 0xF1, 0xD8, 0xF8, 0xF8, 0xAD, 0x19, 0xD9, 0xAE, 0xFB,
+0xDF, 0xD8, 0xF4, 0x16, 0xF1, 0xD8, 0xF8, 0xAD, 0x8D, 0x61, 0xD9, 0xF4, 0xF4, 0xAC, 0xF5, 0x9C,
+0x9C, 0x8D, 0xDF, 0x2B, 0xBA, 0xB6, 0xAE, 0xFA, 0xF8, 0xF4, 0x0B, 0xD8, 0xF1, 0xAE, 0xD0, 0xF8,
+0xAD, 0x51, 0xDA, 0xAE, 0xFA, 0xF8, 0xF1, 0xD8, 0xB9, 0xB1, 0xB6, 0xA3, 0x83, 0x9C, 0x08, 0xB9,
+0xB1, 0x83, 0x9A, 0xB5, 0xAA, 0xC0, 0xFD, 0x30, 0x83, 0xB7, 0x9F, 0x10, 0xB5, 0x8B, 0x93, 0xF2,
+0x02, 0x02, 0xD1, 0xAB, 0xDA, 0xDE, 0xD8, 0xF1, 0xB0, 0x80, 0xBA, 0xAB, 0xC0, 0xC3, 0xB2, 0x84,
+0xC1, 0xC3, 0xD8, 0xB1, 0xB9, 0xF3, 0x8B, 0xA3, 0x91, 0xB6, 0x09, 0xB4, 0xD9, 0xAB, 0xDE, 0xB0,
+0x87, 0x9C, 0xB9, 0xA3, 0xDD, 0xF1, 0xB3, 0x8B, 0x8B, 0x8B, 0x8B, 0x8B, 0xB0, 0x87, 0x20, 0x28,
+0x30, 0x38, 0xB2, 0x8B, 0xB6, 0x9B, 0xF2, 0xA3, 0xC0, 0xC8, 0xC2, 0xC4, 0xCC, 0xC6, 0xA3, 0xA3,
+0xA3, 0xF1, 0xB0, 0x87, 0xB5, 0x9A, 0xD8, 0xF3, 0x9B, 0xA3, 0xA3, 0xDC, 0xBA, 0xAC, 0xDF, 0xB9, //Reverted back as packet size changes causing isues... TODO:change 2742 from 0xD8 to 0x20 Including the DMP_FEATURE_TAP -- known issue in which if you do not enable DMP_FEATURE_TAP then the interrupts will be at 200Hz even if fifo rate
+0xA3, 0xFE, 0xF2, 0xAB, 0xC4, 0xAA, 0xF1, 0xDF, 0xDF, 0xBB, 0xAF, 0xDF, 0xDF, 0xA3, 0xA3, 0xA3,
+0xD8, 0xD8, 0xD8, 0xBB, 0xB3, 0xB7, 0xF1, 0xAA, 0xF9, 0xDA, 0xFF, 0xD9, 0x80, 0x9A, 0xAA, 0x28,
+0xB4, 0x80, 0x98, 0xA7, 0x20, 0xB7, 0x97, 0x87, 0xA8, 0x66, 0x88, 0xF0, 0x79, 0x51, 0xF1, 0x90,
+0x2C, 0x87, 0x0C, 0xA7, 0x81, 0x97, 0x62, 0x93, 0xF0, 0x71, 0x71, 0x60, 0x85, 0x94, 0x01, 0x29,
+/* bank # 11 */
+0x51, 0x79, 0x90, 0xA5, 0xF1, 0x28, 0x4C, 0x6C, 0x87, 0x0C, 0x95, 0x18, 0x85, 0x78, 0xA3, 0x83,
+0x90, 0x28, 0x4C, 0x6C, 0x88, 0x6C, 0xD8, 0xF3, 0xA2, 0x82, 0x00, 0xF2, 0x10, 0xA8, 0x92, 0x19,
+0x80, 0xA2, 0xF2, 0xD9, 0x26, 0xD8, 0xF1, 0x88, 0xA8, 0x4D, 0xD9, 0x48, 0xD8, 0x96, 0xA8, 0x39,
+0x80, 0xD9, 0x3C, 0xD8, 0x95, 0x80, 0xA8, 0x39, 0xA6, 0x86, 0x98, 0xD9, 0x2C, 0xDA, 0x87, 0xA7,
+0x2C, 0xD8, 0xA8, 0x89, 0x95, 0x19, 0xA9, 0x80, 0xD9, 0x38, 0xD8, 0xA8, 0x89, 0x39, 0xA9, 0x80,
+0xDA, 0x3C, 0xD8, 0xA8, 0x2E, 0xA8, 0x39, 0x90, 0xD9, 0x0C, 0xD8, 0xA8, 0x95, 0x31, 0x98, 0xD9,
+0x0C, 0xD8, 0xA8, 0x09, 0xD9, 0xFF, 0xD8, 0x01, 0xDA, 0xFF, 0xD8, 0x95, 0x39, 0xA9, 0xDA, 0x26,
+0xFF, 0xD8, 0x90, 0xA8, 0x0D, 0x89, 0x99, 0xA8, 0x10, 0x80, 0x98, 0x21, 0xDA, 0x2E, 0xD8, 0x89,
+0x99, 0xA8, 0x31, 0x80, 0xDA, 0x2E, 0xD8, 0xA8, 0x86, 0x96, 0x31, 0x80, 0xDA, 0x2E, 0xD8, 0xA8,
+0x87, 0x31, 0x80, 0xDA, 0x2E, 0xD8, 0xA8, 0x82, 0x92, 0xF3, 0x41, 0x80, 0xF1, 0xD9, 0x2E, 0xD8,
+0xA8, 0x82, 0xF3, 0x19, 0x80, 0xF1, 0xD9, 0x2E, 0xD8, 0x82, 0xAC, 0xF3, 0xC0, 0xA2, 0x80, 0x22,
+0xF1, 0xA6, 0x2E, 0xA7, 0x2E, 0xA9, 0x22, 0x98, 0xA8, 0x29, 0xDA, 0xAC, 0xDE, 0xFF, 0xD8, 0xA2,
+0xF2, 0x2A, 0xF1, 0xA9, 0x2E, 0x82, 0x92, 0xA8, 0xF2, 0x31, 0x80, 0xA6, 0x96, 0xF1, 0xD9, 0x00,
+0xAC, 0x8C, 0x9C, 0x0C, 0x30, 0xAC, 0xDE, 0xD0, 0xDE, 0xFF, 0xD8, 0x8C, 0x9C, 0xAC, 0xD0, 0x10,
+0xAC, 0xDE, 0x80, 0x92, 0xA2, 0xF2, 0x4C, 0x82, 0xA8, 0xF1, 0xCA, 0xF2, 0x35, 0xF1, 0x96, 0x88,
+0xA6, 0xD9, 0x00, 0xD8, 0xF1, 0xFF,
+};
+
+// this is the most basic initialization I can create. with the intent that we access the register bytes as few times as needed to get the job done.
+// for detailed descriptins of all registers and there purpose google "MPU-6000/MPU-6050 Register Map and Descriptions"
+uint8_t MPU6050::dmpInitialize(uint8_t rateDivisor, uint8_t mpuAddr) { // Lets get it over with fast Write everything once and set it up necely
+ uint8_t val;
+ uint16_t ival;
+ // Reset procedure per instructions in the "MPU-6000/MPU-6050 Register Map and Descriptions" page 41
+ I2Cdev::writeBit(devAddr,0x6B, 7, (val = 1), wireObj); //PWR_MGMT_1: reset with 100ms delay
+ delay(100);
+ I2Cdev::writeBits(devAddr,0x6A, 2, 3, (val = 0b111), wireObj); // full SIGNAL_PATH_RESET: with another 100ms delay
+ delay(100);
+ I2Cdev::writeBytes(devAddr,0x6B, 1, &(val = 0x01), wireObj); // 1000 0001 PWR_MGMT_1:Clock Source Select PLL_X_gyro
+ I2Cdev::writeBytes(devAddr,0x38, 1, &(val = 0x00), wireObj); // 0000 0000 INT_ENABLE: no Interrupt
+ I2Cdev::writeBytes(devAddr,0x23, 1, &(val = 0x00), wireObj); // 0000 0000 MPU FIFO_EN: (all off) Using DMP's FIFO instead
+ I2Cdev::writeBytes(devAddr,0x1C, 1, &(val = 0x00), wireObj); // 0000 0000 ACCEL_CONFIG: 0 = Accel Full Scale Select: 2g
+ I2Cdev::writeBytes(devAddr,0x37, 1, &(val = 0x80), wireObj); // 1001 0000 INT_PIN_CFG: ACTL The logic level for int pin is active low. and interrupt status bits are cleared on any read
+ I2Cdev::writeBytes(devAddr,0x6B, 1, &(val = 0x01), wireObj); // 0000 0001 PWR_MGMT_1: Clock Source Select PLL_X_gyro
+ I2Cdev::writeBytes(devAddr,0x19, 1, &(val = rateDivisor), wireObj); // 0000 0100 SMPLRT_DIV: Divides the internal sample rate 400Hz ( Sample Rate = Gyroscope Output Rate / (1 + SMPLRT_DIV))
+ I2Cdev::writeBytes(devAddr,0x1A, 1, &(val = 0x01), wireObj); // 0000 0001 CONFIG: Digital Low Pass Filter (DLPF) Configuration 188HZ //Im betting this will be the beat
+ if (!writeProgMemoryBlock(dmpMemory, MPU6050_DMP_CODE_SIZE)) return 1; // Loads the DMP image into the MPU6050 Memory // Should Never Fail
+ I2Cdev::writeWords(devAddr, 0x70, 1, &(ival = 0x0400), wireObj); // DMP Program Start Address
+ I2Cdev::writeBytes(devAddr,0x1B, 1, &(val = 0x18), wireObj); // 0001 1000 GYRO_CONFIG: 3 = +2000 Deg/sec
+ I2Cdev::writeBytes(devAddr,0x6A, 1, &(val = 0xC0), wireObj); // 1100 1100 USER_CTRL: Enable Fifo and Reset Fifo
+ I2Cdev::writeBytes(devAddr,0x38, 1, &(val = 0x02), wireObj); // 0000 0010 INT_ENABLE: RAW_DMP_INT_EN on
+ I2Cdev::writeBit(devAddr,0x6A, 2, 1, wireObj); // Reset FIFO one last time just for kicks. (MPUi2cWrite reads 0x6A first and only alters 1 bit and then saves the byte)
+
+ setDMPEnabled(false); // disable DMP for compatibility with the MPU6050 library
+/*
+ dmpPacketSize += 16;//DMP_FEATURE_6X_LP_QUAT
+ dmpPacketSize += 6;//DMP_FEATURE_SEND_RAW_ACCEL
+ dmpPacketSize += 6;//DMP_FEATURE_SEND_RAW_GYRO
+*/
+ dmpPacketSize = 28;
+ return 0;
+}
+
+bool MPU6050::dmpPacketAvailable() {
+ return getFIFOCount() >= dmpGetFIFOPacketSize();
+}
+
+// uint8_t MPU6050::dmpSetFIFORate(uint8_t fifoRate);
+// uint8_t MPU6050::dmpGetFIFORate();
+// uint8_t MPU6050::dmpGetSampleStepSizeMS();
+// uint8_t MPU6050::dmpGetSampleFrequency();
+// int32_t MPU6050::dmpDecodeTemperature(int8_t tempReg);
+
+//uint8_t MPU6050::dmpRegisterFIFORateProcess(inv_obj_func func, int16_t priority);
+//uint8_t MPU6050::dmpUnregisterFIFORateProcess(inv_obj_func func);
+//uint8_t MPU6050::dmpRunFIFORateProcesses();
+
+// uint8_t MPU6050::dmpSendQuaternion(uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendGyro(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendLinearAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendLinearAccelInWorld(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendControlData(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendExternalSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendGravity(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendPacketNumber(uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendQuantizedAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendEIS(uint_fast16_t elements, uint_fast16_t accuracy);
+
+uint8_t MPU6050::dmpGetAccel(int32_t *data, const uint8_t* packet) {
+ // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+ if (packet == 0) packet = dmpPacketBuffer;
+ data[0] = (((uint32_t)packet[16] << 8) | packet[17]);
+ data[1] = (((uint32_t)packet[18] << 8) | packet[19]);
+ data[2] = (((uint32_t)packet[20] << 8) | packet[21]);
+ return 0;
+}
+uint8_t MPU6050::dmpGetAccel(int16_t *data, const uint8_t* packet) {
+ // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+ if (packet == 0) packet = dmpPacketBuffer;
+ data[0] = (packet[16] << 8) | packet[17];
+ data[1] = (packet[18] << 8) | packet[19];
+ data[2] = (packet[20] << 8) | packet[21];
+ return 0;
+}
+uint8_t MPU6050::dmpGetAccel(VectorInt16 *v, const uint8_t* packet) {
+ // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+ if (packet == 0) packet = dmpPacketBuffer;
+ v -> x = (packet[16] << 8) | packet[17];
+ v -> y = (packet[18] << 8) | packet[19];
+ v -> z = (packet[20] << 8) | packet[21];
+ return 0;
+}
+uint8_t MPU6050::dmpGetQuaternion(int32_t *data, const uint8_t* packet) {
+ // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+ if (packet == 0) packet = dmpPacketBuffer;
+ data[0] = (((uint32_t)packet[0] << 24) | ((uint32_t)packet[1] << 16) | ((uint32_t)packet[2] << 8) | packet[3]);
+ data[1] = (((uint32_t)packet[4] << 24) | ((uint32_t)packet[5] << 16) | ((uint32_t)packet[6] << 8) | packet[7]);
+ data[2] = (((uint32_t)packet[8] << 24) | ((uint32_t)packet[9] << 16) | ((uint32_t)packet[10] << 8) | packet[11]);
+ data[3] = (((uint32_t)packet[12] << 24) | ((uint32_t)packet[13] << 16) | ((uint32_t)packet[14] << 8) | packet[15]);
+ return 0;
+}
+uint8_t MPU6050::dmpGetQuaternion(int16_t *data, const uint8_t* packet) {
+ // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+ if (packet == 0) packet = dmpPacketBuffer;
+ data[0] = ((packet[0] << 8) | packet[1]);
+ data[1] = ((packet[4] << 8) | packet[5]);
+ data[2] = ((packet[8] << 8) | packet[9]);
+ data[3] = ((packet[12] << 8) | packet[13]);
+ return 0;
+}
+uint8_t MPU6050::dmpGetQuaternion(Quaternion *q, const uint8_t* packet) {
+ // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+ int16_t qI[4];
+ uint8_t status = dmpGetQuaternion(qI, packet);
+ if (status == 0) {
+ q -> w = (float)qI[0] / 16384.0f;
+ q -> x = (float)qI[1] / 16384.0f;
+ q -> y = (float)qI[2] / 16384.0f;
+ q -> z = (float)qI[3] / 16384.0f;
+ return 0;
+ }
+ return status; // int16 return value, indicates error if this line is reached
+}
+// uint8_t MPU6050::dmpGet6AxisQuaternion(long *data, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetRelativeQuaternion(long *data, const uint8_t* packet);
+uint8_t MPU6050::dmpGetGyro(int32_t *data, const uint8_t* packet) {
+ // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+ if (packet == 0) packet = dmpPacketBuffer;
+ data[0] = (((uint32_t)packet[22] << 8) | packet[23]);
+ data[1] = (((uint32_t)packet[24] << 8) | packet[25]);
+ data[2] = (((uint32_t)packet[26] << 8) | packet[27]);
+ return 0;
+}
+uint8_t MPU6050::dmpGetGyro(int16_t *data, const uint8_t* packet) {
+ // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+ if (packet == 0) packet = dmpPacketBuffer;
+ data[0] = (packet[22] << 8) | packet[23];
+ data[1] = (packet[24] << 8) | packet[25];
+ data[2] = (packet[26] << 8) | packet[27];
+ return 0;
+}
+uint8_t MPU6050::dmpGetGyro(VectorInt16 *v, const uint8_t* packet) {
+ // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+ if (packet == 0) packet = dmpPacketBuffer;
+ v -> x = (packet[22] << 8) | packet[23];
+ v -> y = (packet[24] << 8) | packet[25];
+ v -> z = (packet[26] << 8) | packet[27];
+ return 0;
+}
+// uint8_t MPU6050::dmpSetLinearAccelFilterCoefficient(float coef);
+// uint8_t MPU6050::dmpGetLinearAccel(long *data, const uint8_t* packet);
+uint8_t MPU6050::dmpGetLinearAccel(VectorInt16 *v, VectorInt16 *vRaw, VectorFloat *gravity) {
+ // get rid of the gravity component (+1g = +16384 in standard DMP FIFO packet, sensitivity is 2g)
+ v -> x = vRaw -> x - gravity -> x*16384;
+ v -> y = vRaw -> y - gravity -> y*16384;
+ v -> z = vRaw -> z - gravity -> z*16384;
+ return 0;
+}
+// uint8_t MPU6050::dmpGetLinearAccelInWorld(long *data, const uint8_t* packet);
+uint8_t MPU6050::dmpGetLinearAccelInWorld(VectorInt16 *v, VectorInt16 *vReal, Quaternion *q) {
+ // rotate measured 3D acceleration vector into original state
+ // frame of reference based on orientation quaternion
+ memcpy(v, vReal, sizeof(VectorInt16));
+ v -> rotate(q);
+ return 0;
+}
+// uint8_t MPU6050::dmpGetGyroAndAccelSensor(long *data, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetGyroSensor(long *data, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetControlData(long *data, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetTemperature(long *data, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetGravity(long *data, const uint8_t* packet);
+uint8_t MPU6050::dmpGetGravity(int16_t *data, const uint8_t* packet) {
+ /* +1g corresponds to +16384, sensitivity is 2g. */
+ int16_t qI[4];
+ uint8_t status = dmpGetQuaternion(qI, packet);
+ data[0] = ((int32_t)qI[1] * qI[3] - (int32_t)qI[0] * qI[2]) / 16384;
+ data[1] = ((int32_t)qI[0] * qI[1] + (int32_t)qI[2] * qI[3]) / 16384;
+ data[2] = ((int32_t)qI[0] * qI[0] - (int32_t)qI[1] * qI[1]
+ - (int32_t)qI[2] * qI[2] + (int32_t)qI[3] * qI[3]) / (int32_t)(2 * 16384L);
+ return status;
+}
+
+uint8_t MPU6050::dmpGetGravity(VectorFloat *v, Quaternion *q) {
+ v -> x = 2 * (q -> x*q -> z - q -> w*q -> y);
+ v -> y = 2 * (q -> w*q -> x + q -> y*q -> z);
+ v -> z = q -> w*q -> w - q -> x*q -> x - q -> y*q -> y + q -> z*q -> z;
+ return 0;
+}
+// uint8_t MPU6050::dmpGetUnquantizedAccel(long *data, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetQuantizedAccel(long *data, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetExternalSensorData(long *data, int size, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetEIS(long *data, const uint8_t* packet);
+
+uint8_t MPU6050::dmpGetEuler(float *data, Quaternion *q) {
+ data[0] = atan2(2*q -> x*q -> y - 2*q -> w*q -> z, 2*q -> w*q -> w + 2*q -> x*q -> x - 1); // psi
+ data[1] = -asin(2*q -> x*q -> z + 2*q -> w*q -> y); // theta
+ data[2] = atan2(2*q -> y*q -> z - 2*q -> w*q -> x, 2*q -> w*q -> w + 2*q -> z*q -> z - 1); // phi
+ return 0;
+}
+
+#ifdef USE_OLD_DMPGETYAWPITCHROLL
+uint8_t MPU6050::dmpGetYawPitchRoll(float *data, Quaternion *q, VectorFloat *gravity) {
+ // yaw: (about Z axis)
+ data[0] = atan2(2*q -> x*q -> y - 2*q -> w*q -> z, 2*q -> w*q -> w + 2*q -> x*q -> x - 1);
+ // pitch: (nose up/down, about Y axis)
+ data[1] = atan(gravity -> x / sqrt(gravity -> y*gravity -> y + gravity -> z*gravity -> z));
+ // roll: (tilt left/right, about X axis)
+ data[2] = atan(gravity -> y / sqrt(gravity -> x*gravity -> x + gravity -> z*gravity -> z));
+ return 0;
+}
+#else
+uint8_t MPU6050::dmpGetYawPitchRoll(float *data, Quaternion *q, VectorFloat *gravity) {
+ // yaw: (about Z axis)
+ data[0] = atan2(2*q -> x*q -> y - 2*q -> w*q -> z, 2*q -> w*q -> w + 2*q -> x*q -> x - 1);
+ // pitch: (nose up/down, about Y axis)
+ data[1] = atan2(gravity -> x , sqrt(gravity -> y*gravity -> y + gravity -> z*gravity -> z));
+ // roll: (tilt left/right, about X axis)
+ data[2] = atan2(gravity -> y , gravity -> z);
+ if (gravity -> z < 0) {
+ if(data[1] > 0) {
+ data[1] = PI - data[1];
+ } else {
+ data[1] = -PI - data[1];
+ }
+ }
+ return 0;
+}
+#endif
+
+// uint8_t MPU6050::dmpGetAccelFloat(float *data, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetQuaternionFloat(float *data, const uint8_t* packet);
+
+uint8_t MPU6050::dmpProcessFIFOPacket(const unsigned char *dmpData) {
+ (void)dmpData; // unused parameter
+ /*for (uint8_t k = 0; k < dmpPacketSize; k++) {
+ if (dmpData[k] < 0x10) Serial.print("0");
+ Serial.print(dmpData[k], HEX);
+ Serial.print(" ");
+ }
+ Serial.print("\n");*/
+ //Serial.println((uint16_t)dmpPacketBuffer);
+ return 0;
+}
+uint8_t MPU6050::dmpReadAndProcessFIFOPacket(uint8_t numPackets, uint8_t *processed) {
+ uint8_t status;
+ uint8_t buf[dmpPacketSize];
+ for (uint8_t i = 0; i < numPackets; i++) {
+ // read packet from FIFO
+ getFIFOBytes(buf, dmpPacketSize);
+
+ // process packet
+ if ((status = dmpProcessFIFOPacket(buf)) > 0) return status;
+
+ // increment external process count variable, if supplied
+ if (processed != 0) (*processed)++;
+ }
+ return 0;
+}
+
+// uint8_t MPU6050::dmpSetFIFOProcessedCallback(void (*func) (void));
+
+// uint8_t MPU6050::dmpInitFIFOParam();
+// uint8_t MPU6050::dmpCloseFIFO();
+// uint8_t MPU6050::dmpSetGyroDataSource(uint_fast8_t source);
+// uint8_t MPU6050::dmpDecodeQuantizedAccel();
+// uint32_t MPU6050::dmpGetGyroSumOfSquare();
+// uint32_t MPU6050::dmpGetAccelSumOfSquare();
+// void MPU6050::dmpOverrideQuaternion(long *q);
+uint16_t MPU6050::dmpGetFIFOPacketSize() {
+ return dmpPacketSize;
+}
+
+
+
+uint8_t MPU6050::dmpGetCurrentFIFOPacket(uint8_t *data) { // overflow proof
+ return(GetCurrentFIFOPacket(data, dmpPacketSize));
+}
diff --git a/lib/MPU6050/src/MPU6050_6Axis_MotionApps612.h b/lib/MPU6050/src/MPU6050_6Axis_MotionApps612.h
new file mode 100644
index 0000000..a1b9526
--- /dev/null
+++ b/lib/MPU6050/src/MPU6050_6Axis_MotionApps612.h
@@ -0,0 +1,158 @@
+// I2Cdev library collection - MPU6050 I2C device class
+// Based on InvenSense MPU-6050 register map document rev. 2.0, 5/19/2011 (RM-MPU-6000A-00)
+// 10/3/2011 by Jeff Rowberg
+// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
+//
+// Changelog:
+// 2021/09/27 - split implementations out of header files, finally
+// ... - ongoing debug release
+
+// NOTE: THIS IS ONLY A PARIAL RELEASE. THIS DEVICE CLASS IS CURRENTLY UNDERGOING ACTIVE
+// DEVELOPMENT AND IS STILL MISSING SOME IMPORTANT FEATURES. PLEASE KEEP THIS IN MIND IF
+// YOU DECIDE TO USE THIS PARTICULAR CODE FOR ANYTHING.
+
+/* ============================================
+I2Cdev device library code is placed under the MIT license
+Copyright (c) 2012 Jeff Rowberg
+
+Permission is hereby granted, free of charge, to any person obtaining a copy
+of this software and associated documentation files (the "Software"), to deal
+in the Software without restriction, including without limitation the rights
+to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+copies of the Software, and to permit persons to whom the Software is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in
+all copies or substantial portions of the Software.
+
+THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+THE SOFTWARE.
+===============================================
+*/
+
+#ifndef _MPU6050_6AXIS_MOTIONAPPS612_H_
+#define _MPU6050_6AXIS_MOTIONAPPS612_H_
+
+// take ownership of the "MPU6050" typedef
+#define I2CDEVLIB_MPU6050_TYPEDEF
+
+#include "MPU6050.h"
+
+// this divisor is pre configured into the above image and can't be modified at this time.
+#ifndef MPU6050_DMP_FIFO_RATE_DIVISOR
+#define MPU6050_DMP_FIFO_RATE_DIVISOR 0x01 // The New instance of the Firmware has this as the default
+#endif
+
+class MPU6050_6Axis_MotionApps612 : public MPU6050_Base {
+ public:
+ MPU6050_6Axis_MotionApps612(uint8_t address=MPU6050_DEFAULT_ADDRESS, void *wireObj=0) : MPU6050_Base(address, wireObj) { }
+
+ uint8_t dmpInitialize(uint8_t rateDivisor = MPU6050_DMP_FIFO_RATE_DIVISOR, uint8_t mpuAddr = 0x68);
+ bool dmpPacketAvailable();
+
+ uint8_t dmpSetFIFORate(uint8_t fifoRate);
+ uint8_t dmpGetFIFORate();
+ uint8_t dmpGetSampleStepSizeMS();
+ uint8_t dmpGetSampleFrequency();
+ int32_t dmpDecodeTemperature(int8_t tempReg);
+
+ // Register callbacks after a packet of FIFO data is processed
+ //uint8_t dmpRegisterFIFORateProcess(inv_obj_func func, int16_t priority);
+ //uint8_t dmpUnregisterFIFORateProcess(inv_obj_func func);
+ uint8_t dmpRunFIFORateProcesses();
+
+ // Setup FIFO for various output
+ uint8_t dmpSendQuaternion(uint_fast16_t accuracy);
+ uint8_t dmpSendGyro(uint_fast16_t elements, uint_fast16_t accuracy);
+ uint8_t dmpSendAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+ uint8_t dmpSendLinearAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+ uint8_t dmpSendLinearAccelInWorld(uint_fast16_t elements, uint_fast16_t accuracy);
+ uint8_t dmpSendControlData(uint_fast16_t elements, uint_fast16_t accuracy);
+ uint8_t dmpSendSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
+ uint8_t dmpSendExternalSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
+ uint8_t dmpSendGravity(uint_fast16_t elements, uint_fast16_t accuracy);
+ uint8_t dmpSendPacketNumber(uint_fast16_t accuracy);
+ uint8_t dmpSendQuantizedAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+ uint8_t dmpSendEIS(uint_fast16_t elements, uint_fast16_t accuracy);
+
+ // Get Fixed Point data from FIFO
+ uint8_t dmpGetAccel(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetAccel(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetAccel(VectorInt16 *v, const uint8_t* packet=0);
+ uint8_t dmpGetQuaternion(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetQuaternion(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetQuaternion(Quaternion *q, const uint8_t* packet=0);
+ uint8_t dmpGet6AxisQuaternion(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGet6AxisQuaternion(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGet6AxisQuaternion(Quaternion *q, const uint8_t* packet=0);
+ uint8_t dmpGetRelativeQuaternion(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetRelativeQuaternion(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetRelativeQuaternion(Quaternion *data, const uint8_t* packet=0);
+ uint8_t dmpGetGyro(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetGyro(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetGyro(VectorInt16 *v, const uint8_t* packet=0);
+ uint8_t dmpSetLinearAccelFilterCoefficient(float coef);
+ uint8_t dmpGetLinearAccel(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetLinearAccel(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetLinearAccel(VectorInt16 *v, const uint8_t* packet=0);
+ uint8_t dmpGetLinearAccel(VectorInt16 *v, VectorInt16 *vRaw, VectorFloat *gravity);
+ uint8_t dmpGetLinearAccelInWorld(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetLinearAccelInWorld(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetLinearAccelInWorld(VectorInt16 *v, const uint8_t* packet=0);
+ uint8_t dmpGetLinearAccelInWorld(VectorInt16 *v, VectorInt16 *vReal, Quaternion *q);
+ uint8_t dmpGetGyroAndAccelSensor(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetGyroAndAccelSensor(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetGyroAndAccelSensor(VectorInt16 *g, VectorInt16 *a, const uint8_t* packet=0);
+ uint8_t dmpGetGyroSensor(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetGyroSensor(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetGyroSensor(VectorInt16 *v, const uint8_t* packet=0);
+ uint8_t dmpGetControlData(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetTemperature(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetGravity(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetGravity(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetGravity(VectorInt16 *v, const uint8_t* packet=0);
+ uint8_t dmpGetGravity(VectorFloat *v, Quaternion *q);
+ uint8_t dmpGetUnquantizedAccel(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetUnquantizedAccel(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetUnquantizedAccel(VectorInt16 *v, const uint8_t* packet=0);
+ uint8_t dmpGetQuantizedAccel(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetQuantizedAccel(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetQuantizedAccel(VectorInt16 *v, const uint8_t* packet=0);
+ uint8_t dmpGetExternalSensorData(int32_t *data, uint16_t size, const uint8_t* packet=0);
+ uint8_t dmpGetEIS(int32_t *data, const uint8_t* packet=0);
+
+ uint8_t dmpGetEuler(float *data, Quaternion *q);
+ uint8_t dmpGetYawPitchRoll(float *data, Quaternion *q, VectorFloat *gravity);
+
+ // Get Floating Point data from FIFO
+ uint8_t dmpGetAccelFloat(float *data, const uint8_t* packet=0);
+ uint8_t dmpGetQuaternionFloat(float *data, const uint8_t* packet=0);
+
+ uint8_t dmpProcessFIFOPacket(const unsigned char *dmpData);
+ uint8_t dmpReadAndProcessFIFOPacket(uint8_t numPackets, uint8_t *processed=NULL);
+
+ uint8_t dmpSetFIFOProcessedCallback(void (*func) (void));
+
+ uint8_t dmpInitFIFOParam();
+ uint8_t dmpCloseFIFO();
+ uint8_t dmpSetGyroDataSource(uint8_t source);
+ uint8_t dmpDecodeQuantizedAccel();
+ uint32_t dmpGetGyroSumOfSquare();
+ uint32_t dmpGetAccelSumOfSquare();
+ void dmpOverrideQuaternion(long *q);
+ uint16_t dmpGetFIFOPacketSize();
+ uint8_t dmpGetCurrentFIFOPacket(uint8_t *data); // overflow proof
+
+ private:
+ uint8_t *dmpPacketBuffer;
+ uint16_t dmpPacketSize;
+};
+
+typedef MPU6050_6Axis_MotionApps612 MPU6050;
+
+#endif /* _MPU6050_6AXIS_MOTIONAPPS612_H_ */
diff --git a/lib/MPU6050/src/MPU6050_9Axis_MotionApps41.cpp b/lib/MPU6050/src/MPU6050_9Axis_MotionApps41.cpp
new file mode 100644
index 0000000..404d5a4
--- /dev/null
+++ b/lib/MPU6050/src/MPU6050_9Axis_MotionApps41.cpp
@@ -0,0 +1,902 @@
+// I2Cdev library collection - MPU6050 I2C device class, 9-axis MotionApps 4.1 implementation
+// Based on InvenSense MPU-6050 register map document rev. 2.0, 5/19/2011 (RM-MPU-6000A-00)
+// 6/18/2012 by Jeff Rowberg
+// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
+//
+// Changelog:
+// 2021/09/27 - split implementations out of header files, finally
+
+/* ============================================
+I2Cdev device library code is placed under the MIT license
+Copyright (c) 2021 Jeff Rowberg
+
+Permission is hereby granted, free of charge, to any person obtaining a copy
+of this software and associated documentation files (the "Software"), to deal
+in the Software without restriction, including without limitation the rights
+to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+copies of the Software, and to permit persons to whom the Software is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in
+all copies or substantial portions of the Software.
+
+THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+THE SOFTWARE.
+===============================================
+*/
+
+// MotionApps 4.1 DMP implementation, built using the MPU-9150 "MotionFit" board
+#define MPU6050_INCLUDE_DMP_MOTIONAPPS41
+
+#include "MPU6050_9Axis_MotionApps41.h"
+
+// Tom Carpenter's conditional PROGMEM code
+// http://forum.arduino.cc/index.php?topic=129407.0
+#ifdef __AVR__
+ #include
+#elif defined(ESP32)
+ #include
+#else
+ // Teensy 3.0 library conditional PROGMEM code from Paul Stoffregen
+ #ifndef __PGMSPACE_H_
+ #define __PGMSPACE_H_ 1
+ #include
+
+ #define PROGMEM
+ #define PGM_P const char *
+ #define PSTR(str) (str)
+ #define F(x) x
+
+ typedef void prog_void;
+ typedef char prog_char;
+ //typedef unsigned char prog_uchar;
+ typedef int8_t prog_int8_t;
+ typedef uint8_t prog_uint8_t;
+ typedef int16_t prog_int16_t;
+ typedef uint16_t prog_uint16_t;
+ typedef int32_t prog_int32_t;
+ typedef uint32_t prog_uint32_t;
+
+ #define strcpy_P(dest, src) strcpy((dest), (src))
+ #define strcat_P(dest, src) strcat((dest), (src))
+ #define strcmp_P(a, b) strcmp((a), (b))
+
+ #define pgm_read_byte(addr) (*(const unsigned char *)(addr))
+ #define pgm_read_word(addr) (*(const unsigned short *)(addr))
+ #define pgm_read_dword(addr) (*(const unsigned long *)(addr))
+ #define pgm_read_float(addr) (*(const float *)(addr))
+
+ #define pgm_read_byte_near(addr) pgm_read_byte(addr)
+ #define pgm_read_word_near(addr) pgm_read_word(addr)
+ #define pgm_read_dword_near(addr) pgm_read_dword(addr)
+ #define pgm_read_float_near(addr) pgm_read_float(addr)
+ #define pgm_read_byte_far(addr) pgm_read_byte(addr)
+ #define pgm_read_word_far(addr) pgm_read_word(addr)
+ #define pgm_read_dword_far(addr) pgm_read_dword(addr)
+ #define pgm_read_float_far(addr) pgm_read_float(addr)
+ #endif
+#endif
+
+// NOTE! Enabling DEBUG adds about 3.3kB to the flash program size.
+// Debug output is now working even on ATMega328P MCUs (e.g. Arduino Uno)
+// after moving string constants to flash memory storage using the F()
+// compiler macro (Arduino IDE 1.0+ required).
+
+// #define DEBUG
+/* Control whether debugging macros are active at compile time */
+#undef DB_ACTIVE
+#ifdef DEBUG
+#define DB_ACTIVE 1
+#else
+#define DB_ACTIVE 0
+#endif /* DEBUG */
+
+/*
+** Usage: DB_PRINT((...));
+** Usage: DB_PRINTLN((...));
+**
+** "..." is whatever extra arguments fmt requires (possibly nothing).
+**
+** The structure of the macros means that the code is always validated
+** but is not called when DEBUG is undefined.
+** -- See chapter 8 of 'The Practice of Programming', by Kernighan and Pike.
+*/
+#define DEBUG_PRINT(...)\
+ do { if (DB_ACTIVE) Serial.print(__VA_ARGS__); } while (0)
+#define DEBUG_PRINTF(...)\
+ do { if (DB_ACTIVE) Serial.printf(__VA_ARGS__); } while (0)
+#define DEBUG_PRINTLN(...)\
+ do { if (DB_ACTIVE) Serial.println(__VA_ARGS__); } while (0)
+#define DEBUG_PRINTLNF(x, y)\
+ do { if (DB_ACTIVE) Serial.println(x, y); } while (0)
+
+#define MPU6050_DMP_CODE_SIZE 1962 // dmpMemory[]
+#define MPU6050_DMP_CONFIG_SIZE 232 // dmpConfig[]
+#define MPU6050_DMP_UPDATES_SIZE 140 // dmpUpdates[]
+
+/* ================================================================================================ *
+ | Default MotionApps v4.1 48-byte FIFO packet structure: |
+ | |
+ | [QUAT W][ ][QUAT X][ ][QUAT Y][ ][QUAT Z][ ][GYRO X][ ][GYRO Y][ ] |
+ | 0 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 |
+ | |
+ | [GYRO Z][ ][MAG X ][MAG Y ][MAG Z ][ACC X ][ ][ACC Y ][ ][ACC Z ][ ][ ] |
+ | 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 |
+ * ================================================================================================ */
+
+// this block of memory gets written to the MPU on start-up, and it seems
+// to be volatile memory, so it has to be done each time (it only takes ~1
+// second though)
+static const unsigned char dmpMemory[MPU6050_DMP_CODE_SIZE] PROGMEM = {
+ // bank 0, 256 bytes
+ 0xFB, 0x00, 0x00, 0x3E, 0x00, 0x0B, 0x00, 0x36, 0x00, 0x01, 0x00, 0x02, 0x00, 0x03, 0x00, 0x00,
+ 0x00, 0x65, 0x00, 0x54, 0xFF, 0xEF, 0x00, 0x00, 0xFA, 0x80, 0x00, 0x0B, 0x12, 0x82, 0x00, 0x01,
+ 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x28, 0x00, 0x00, 0xFF, 0xFF, 0x45, 0x81, 0xFF, 0xFF, 0xFA, 0x72, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x03, 0xE8, 0x00, 0x00, 0x00, 0x01, 0x00, 0x01, 0x7F, 0xFF, 0xFF, 0xFE, 0x80, 0x01,
+ 0x00, 0x1B, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x3E, 0x03, 0x30, 0x40, 0x00, 0x00, 0x00, 0x02, 0xCA, 0xE3, 0x09, 0x3E, 0x80, 0x00, 0x00,
+ 0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x60, 0x00, 0x00, 0x00,
+ 0x41, 0xFF, 0x00, 0x00, 0x00, 0x00, 0x0B, 0x2A, 0x00, 0x00, 0x16, 0x55, 0x00, 0x00, 0x21, 0x82,
+ 0xFD, 0x87, 0x26, 0x50, 0xFD, 0x80, 0x00, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x00, 0x05, 0x80, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x03, 0x00, 0x00,
+ 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x04, 0x6F, 0x00, 0x02, 0x65, 0x32, 0x00, 0x00, 0x5E, 0xC0,
+ 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0xFB, 0x8C, 0x6F, 0x5D, 0xFD, 0x5D, 0x08, 0xD9, 0x00, 0x7C, 0x73, 0x3B, 0x00, 0x6C, 0x12, 0xCC,
+ 0x32, 0x00, 0x13, 0x9D, 0x32, 0x00, 0xD0, 0xD6, 0x32, 0x00, 0x08, 0x00, 0x40, 0x00, 0x01, 0xF4,
+ 0xFF, 0xE6, 0x80, 0x79, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0xD0, 0xD6, 0x00, 0x00, 0x27, 0x10,
+
+ // bank 1, 256 bytes
+ 0xFB, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x01, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0xFA, 0x36, 0xFF, 0xBC, 0x30, 0x8E, 0x00, 0x05, 0xFB, 0xF0, 0xFF, 0xD9, 0x5B, 0xC8,
+ 0xFF, 0xD0, 0x9A, 0xBE, 0x00, 0x00, 0x10, 0xA9, 0xFF, 0xF4, 0x1E, 0xB2, 0x00, 0xCE, 0xBB, 0xF7,
+ 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x04, 0x00, 0x02, 0x00, 0x02, 0x02, 0x00, 0x00, 0x0C,
+ 0xFF, 0xC2, 0x80, 0x00, 0x00, 0x01, 0x80, 0x00, 0x00, 0xCF, 0x80, 0x00, 0x40, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00, 0x14,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x03, 0x3F, 0x68, 0xB6, 0x79, 0x35, 0x28, 0xBC, 0xC6, 0x7E, 0xD1, 0x6C,
+ 0x80, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0xB2, 0x6A, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3F, 0xF0, 0x00, 0x00, 0x00, 0x30,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x25, 0x4D, 0x00, 0x2F, 0x70, 0x6D, 0x00, 0x00, 0x05, 0xAE, 0x00, 0x0C, 0x02, 0xD0,
+
+ // bank 2, 256 bytes
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x65, 0x00, 0x54, 0xFF, 0xEF, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x01, 0x00, 0x00, 0x44, 0x00, 0x00, 0x00, 0x00, 0x0C, 0x00, 0x00, 0x00, 0x01, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x65, 0x00, 0x00, 0x00, 0x54, 0x00, 0x00, 0xFF, 0xEF, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x1B, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00,
+ 0x00, 0x1B, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x47, 0x78, 0xA2,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+
+ // bank 3, 256 bytes
+ 0xD8, 0xDC, 0xF4, 0xD8, 0xB9, 0xAB, 0xF3, 0xF8, 0xFA, 0xF1, 0xBA, 0xA2, 0xDE, 0xB2, 0xB8, 0xB4,
+ 0xA8, 0x81, 0x98, 0xF7, 0x4A, 0x90, 0x7F, 0x91, 0x6A, 0xF3, 0xF9, 0xDB, 0xA8, 0xF9, 0xB0, 0xBA,
+ 0xA0, 0x80, 0xF2, 0xCE, 0x81, 0xF3, 0xC2, 0xF1, 0xC1, 0xF2, 0xC3, 0xF3, 0xCC, 0xA2, 0xB2, 0x80,
+ 0xF1, 0xC6, 0xD8, 0x80, 0xBA, 0xA7, 0xDF, 0xDF, 0xDF, 0xF2, 0xA7, 0xC3, 0xCB, 0xC5, 0xB6, 0xF0,
+ 0x87, 0xA2, 0x94, 0x24, 0x48, 0x70, 0x3C, 0x95, 0x40, 0x68, 0x34, 0x58, 0x9B, 0x78, 0xA2, 0xF1,
+ 0x83, 0x92, 0x2D, 0x55, 0x7D, 0xD8, 0xB1, 0xB4, 0xB8, 0xA1, 0xD0, 0x91, 0x80, 0xF2, 0x70, 0xF3,
+ 0x70, 0xF2, 0x7C, 0x80, 0xA8, 0xF1, 0x01, 0xB0, 0x98, 0x87, 0xD9, 0x43, 0xD8, 0x86, 0xC9, 0x88,
+ 0xBA, 0xA1, 0xF2, 0x0E, 0xB8, 0x97, 0x80, 0xF1, 0xA9, 0xDF, 0xDF, 0xDF, 0xAA, 0xDF, 0xDF, 0xDF,
+ 0xF2, 0xAA, 0xC5, 0xCD, 0xC7, 0xA9, 0x0C, 0xC9, 0x2C, 0x97, 0x97, 0x97, 0x97, 0xF1, 0xA9, 0x89,
+ 0x26, 0x46, 0x66, 0xB0, 0xB4, 0xBA, 0x80, 0xAC, 0xDE, 0xF2, 0xCA, 0xF1, 0xB2, 0x8C, 0x02, 0xA9,
+ 0xB6, 0x98, 0x00, 0x89, 0x0E, 0x16, 0x1E, 0xB8, 0xA9, 0xB4, 0x99, 0x2C, 0x54, 0x7C, 0xB0, 0x8A,
+ 0xA8, 0x96, 0x36, 0x56, 0x76, 0xF1, 0xB9, 0xAF, 0xB4, 0xB0, 0x83, 0xC0, 0xB8, 0xA8, 0x97, 0x11,
+ 0xB1, 0x8F, 0x98, 0xB9, 0xAF, 0xF0, 0x24, 0x08, 0x44, 0x10, 0x64, 0x18, 0xF1, 0xA3, 0x29, 0x55,
+ 0x7D, 0xAF, 0x83, 0xB5, 0x93, 0xF0, 0x00, 0x28, 0x50, 0xF5, 0xBA, 0xAD, 0x8F, 0x9F, 0x28, 0x54,
+ 0x7C, 0xB9, 0xF1, 0xA3, 0x86, 0x9F, 0x61, 0xA6, 0xDA, 0xDE, 0xDF, 0xDB, 0xB2, 0xB6, 0x8E, 0x9D,
+ 0xAE, 0xF5, 0x60, 0x68, 0x70, 0xB1, 0xB5, 0xF1, 0xDA, 0xA6, 0xDF, 0xD9, 0xA6, 0xFA, 0xA3, 0x86,
+
+ // bank 4, 256 bytes
+ 0x96, 0xDB, 0x31, 0xA6, 0xD9, 0xF8, 0xDF, 0xBA, 0xA6, 0x8F, 0xC2, 0xC5, 0xC7, 0xB2, 0x8C, 0xC1,
+ 0xB8, 0xA2, 0xDF, 0xDF, 0xDF, 0xA3, 0xDF, 0xDF, 0xDF, 0xD8, 0xD8, 0xF1, 0xB8, 0xA8, 0xB2, 0x86,
+ 0xB4, 0x98, 0x0D, 0x35, 0x5D, 0xB8, 0xAA, 0x98, 0xB0, 0x87, 0x2D, 0x35, 0x3D, 0xB2, 0xB6, 0xBA,
+ 0xAF, 0x8C, 0x96, 0x19, 0x8F, 0x9F, 0xA7, 0x0E, 0x16, 0x1E, 0xB4, 0x9A, 0xB8, 0xAA, 0x87, 0x2C,
+ 0x54, 0x7C, 0xB9, 0xA3, 0xDE, 0xDF, 0xDF, 0xA3, 0xB1, 0x80, 0xF2, 0xC4, 0xCD, 0xC9, 0xF1, 0xB8,
+ 0xA9, 0xB4, 0x99, 0x83, 0x0D, 0x35, 0x5D, 0x89, 0xB9, 0xA3, 0x2D, 0x55, 0x7D, 0xB5, 0x93, 0xA3,
+ 0x0E, 0x16, 0x1E, 0xA9, 0x2C, 0x54, 0x7C, 0xB8, 0xB4, 0xB0, 0xF1, 0x97, 0x83, 0xA8, 0x11, 0x84,
+ 0xA5, 0x09, 0x98, 0xA3, 0x83, 0xF0, 0xDA, 0x24, 0x08, 0x44, 0x10, 0x64, 0x18, 0xD8, 0xF1, 0xA5,
+ 0x29, 0x55, 0x7D, 0xA5, 0x85, 0x95, 0x02, 0x1A, 0x2E, 0x3A, 0x56, 0x5A, 0x40, 0x48, 0xF9, 0xF3,
+ 0xA3, 0xD9, 0xF8, 0xF0, 0x98, 0x83, 0x24, 0x08, 0x44, 0x10, 0x64, 0x18, 0x97, 0x82, 0xA8, 0xF1,
+ 0x11, 0xF0, 0x98, 0xA2, 0x24, 0x08, 0x44, 0x10, 0x64, 0x18, 0xDA, 0xF3, 0xDE, 0xD8, 0x83, 0xA5,
+ 0x94, 0x01, 0xD9, 0xA3, 0x02, 0xF1, 0xA2, 0xC3, 0xC5, 0xC7, 0xD8, 0xF1, 0x84, 0x92, 0xA2, 0x4D,
+ 0xDA, 0x2A, 0xD8, 0x48, 0x69, 0xD9, 0x2A, 0xD8, 0x68, 0x55, 0xDA, 0x32, 0xD8, 0x50, 0x71, 0xD9,
+ 0x32, 0xD8, 0x70, 0x5D, 0xDA, 0x3A, 0xD8, 0x58, 0x79, 0xD9, 0x3A, 0xD8, 0x78, 0x93, 0xA3, 0x4D,
+ 0xDA, 0x2A, 0xD8, 0x48, 0x69, 0xD9, 0x2A, 0xD8, 0x68, 0x55, 0xDA, 0x32, 0xD8, 0x50, 0x71, 0xD9,
+ 0x32, 0xD8, 0x70, 0x5D, 0xDA, 0x3A, 0xD8, 0x58, 0x79, 0xD9, 0x3A, 0xD8, 0x78, 0xA8, 0x8A, 0x9A,
+
+ // bank 5, 256 bytes
+ 0xF0, 0x28, 0x50, 0x78, 0x9E, 0xF3, 0x88, 0x18, 0xF1, 0x9F, 0x1D, 0x98, 0xA8, 0xD9, 0x08, 0xD8,
+ 0xC8, 0x9F, 0x12, 0x9E, 0xF3, 0x15, 0xA8, 0xDA, 0x12, 0x10, 0xD8, 0xF1, 0xAF, 0xC8, 0x97, 0x87,
+ 0x34, 0xB5, 0xB9, 0x94, 0xA4, 0x21, 0xF3, 0xD9, 0x22, 0xD8, 0xF2, 0x2D, 0xF3, 0xD9, 0x2A, 0xD8,
+ 0xF2, 0x35, 0xF3, 0xD9, 0x32, 0xD8, 0x81, 0xA4, 0x60, 0x60, 0x61, 0xD9, 0x61, 0xD8, 0x6C, 0x68,
+ 0x69, 0xD9, 0x69, 0xD8, 0x74, 0x70, 0x71, 0xD9, 0x71, 0xD8, 0xB1, 0xA3, 0x84, 0x19, 0x3D, 0x5D,
+ 0xA3, 0x83, 0x1A, 0x3E, 0x5E, 0x93, 0x10, 0x30, 0x81, 0x10, 0x11, 0xB8, 0xB0, 0xAF, 0x8F, 0x94,
+ 0xF2, 0xDA, 0x3E, 0xD8, 0xB4, 0x9A, 0xA8, 0x87, 0x29, 0xDA, 0xF8, 0xD8, 0x87, 0x9A, 0x35, 0xDA,
+ 0xF8, 0xD8, 0x87, 0x9A, 0x3D, 0xDA, 0xF8, 0xD8, 0xB1, 0xB9, 0xA4, 0x98, 0x85, 0x02, 0x2E, 0x56,
+ 0xA5, 0x81, 0x00, 0x0C, 0x14, 0xA3, 0x97, 0xB0, 0x8A, 0xF1, 0x2D, 0xD9, 0x28, 0xD8, 0x4D, 0xD9,
+ 0x48, 0xD8, 0x6D, 0xD9, 0x68, 0xD8, 0xB1, 0x84, 0x0D, 0xDA, 0x0E, 0xD8, 0xA3, 0x29, 0x83, 0xDA,
+ 0x2C, 0x0E, 0xD8, 0xA3, 0x84, 0x49, 0x83, 0xDA, 0x2C, 0x4C, 0x0E, 0xD8, 0xB8, 0xB0, 0x97, 0x86,
+ 0xA8, 0x31, 0x9B, 0x06, 0x99, 0x07, 0xAB, 0x97, 0x28, 0x88, 0x9B, 0xF0, 0x0C, 0x20, 0x14, 0x40,
+ 0xB9, 0xA3, 0x8A, 0xC3, 0xC5, 0xC7, 0x9A, 0xA3, 0x28, 0x50, 0x78, 0xF1, 0xB5, 0x93, 0x01, 0xD9,
+ 0xDF, 0xDF, 0xDF, 0xD8, 0xB8, 0xB4, 0xA8, 0x8C, 0x9C, 0xF0, 0x04, 0x28, 0x51, 0x79, 0x1D, 0x30,
+ 0x14, 0x38, 0xB2, 0x82, 0xAB, 0xD0, 0x98, 0x2C, 0x50, 0x50, 0x78, 0x78, 0x9B, 0xF1, 0x1A, 0xB0,
+ 0xF0, 0xB1, 0x83, 0x9C, 0xA8, 0x29, 0x51, 0x79, 0xB0, 0x8B, 0x29, 0x51, 0x79, 0xB1, 0x83, 0x24,
+
+ // bank 6, 256 bytes
+ 0x70, 0x59, 0xB0, 0x8B, 0x20, 0x58, 0x71, 0xB1, 0x83, 0x44, 0x69, 0x38, 0xB0, 0x8B, 0x39, 0x40,
+ 0x68, 0xB1, 0x83, 0x64, 0x48, 0x31, 0xB0, 0x8B, 0x30, 0x49, 0x60, 0xA5, 0x88, 0x20, 0x09, 0x71,
+ 0x58, 0x44, 0x68, 0x11, 0x39, 0x64, 0x49, 0x30, 0x19, 0xF1, 0xAC, 0x00, 0x2C, 0x54, 0x7C, 0xF0,
+ 0x8C, 0xA8, 0x04, 0x28, 0x50, 0x78, 0xF1, 0x88, 0x97, 0x26, 0xA8, 0x59, 0x98, 0xAC, 0x8C, 0x02,
+ 0x26, 0x46, 0x66, 0xF0, 0x89, 0x9C, 0xA8, 0x29, 0x51, 0x79, 0x24, 0x70, 0x59, 0x44, 0x69, 0x38,
+ 0x64, 0x48, 0x31, 0xA9, 0x88, 0x09, 0x20, 0x59, 0x70, 0xAB, 0x11, 0x38, 0x40, 0x69, 0xA8, 0x19,
+ 0x31, 0x48, 0x60, 0x8C, 0xA8, 0x3C, 0x41, 0x5C, 0x20, 0x7C, 0x00, 0xF1, 0x87, 0x98, 0x19, 0x86,
+ 0xA8, 0x6E, 0x76, 0x7E, 0xA9, 0x99, 0x88, 0x2D, 0x55, 0x7D, 0x9E, 0xB9, 0xA3, 0x8A, 0x22, 0x8A,
+ 0x6E, 0x8A, 0x56, 0x8A, 0x5E, 0x9F, 0xB1, 0x83, 0x06, 0x26, 0x46, 0x66, 0x0E, 0x2E, 0x4E, 0x6E,
+ 0x9D, 0xB8, 0xAD, 0x00, 0x2C, 0x54, 0x7C, 0xF2, 0xB1, 0x8C, 0xB4, 0x99, 0xB9, 0xA3, 0x2D, 0x55,
+ 0x7D, 0x81, 0x91, 0xAC, 0x38, 0xAD, 0x3A, 0xB5, 0x83, 0x91, 0xAC, 0x2D, 0xD9, 0x28, 0xD8, 0x4D,
+ 0xD9, 0x48, 0xD8, 0x6D, 0xD9, 0x68, 0xD8, 0x8C, 0x9D, 0xAE, 0x29, 0xD9, 0x04, 0xAE, 0xD8, 0x51,
+ 0xD9, 0x04, 0xAE, 0xD8, 0x79, 0xD9, 0x04, 0xD8, 0x81, 0xF3, 0x9D, 0xAD, 0x00, 0x8D, 0xAE, 0x19,
+ 0x81, 0xAD, 0xD9, 0x01, 0xD8, 0xF2, 0xAE, 0xDA, 0x26, 0xD8, 0x8E, 0x91, 0x29, 0x83, 0xA7, 0xD9,
+ 0xAD, 0xAD, 0xAD, 0xAD, 0xF3, 0x2A, 0xD8, 0xD8, 0xF1, 0xB0, 0xAC, 0x89, 0x91, 0x3E, 0x5E, 0x76,
+ 0xF3, 0xAC, 0x2E, 0x2E, 0xF1, 0xB1, 0x8C, 0x5A, 0x9C, 0xAC, 0x2C, 0x28, 0x28, 0x28, 0x9C, 0xAC,
+
+ // bank 7, 170 bytes (remainder)
+ 0x30, 0x18, 0xA8, 0x98, 0x81, 0x28, 0x34, 0x3C, 0x97, 0x24, 0xA7, 0x28, 0x34, 0x3C, 0x9C, 0x24,
+ 0xF2, 0xB0, 0x89, 0xAC, 0x91, 0x2C, 0x4C, 0x6C, 0x8A, 0x9B, 0x2D, 0xD9, 0xD8, 0xD8, 0x51, 0xD9,
+ 0xD8, 0xD8, 0x79, 0xD9, 0xD8, 0xD8, 0xF1, 0x9E, 0x88, 0xA3, 0x31, 0xDA, 0xD8, 0xD8, 0x91, 0x2D,
+ 0xD9, 0x28, 0xD8, 0x4D, 0xD9, 0x48, 0xD8, 0x6D, 0xD9, 0x68, 0xD8, 0xB1, 0x83, 0x93, 0x35, 0x3D,
+ 0x80, 0x25, 0xDA, 0xD8, 0xD8, 0x85, 0x69, 0xDA, 0xD8, 0xD8, 0xB4, 0x93, 0x81, 0xA3, 0x28, 0x34,
+ 0x3C, 0xF3, 0xAB, 0x8B, 0xA3, 0x91, 0xB6, 0x09, 0xB4, 0xD9, 0xAB, 0xDE, 0xB0, 0x87, 0x9C, 0xB9,
+ 0xA3, 0xDD, 0xF1, 0xA3, 0xA3, 0xA3, 0xA3, 0x95, 0xF1, 0xA3, 0xA3, 0xA3, 0x9D, 0xF1, 0xA3, 0xA3,
+ 0xA3, 0xA3, 0xF2, 0xA3, 0xB4, 0x90, 0x80, 0xF2, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3,
+ 0xA3, 0xA3, 0xB2, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xB0, 0x87, 0xB5, 0x99, 0xF1, 0xA3, 0xA3,
+ 0xA3, 0x98, 0xF1, 0xA3, 0xA3, 0xA3, 0xA3, 0x97, 0xA3, 0xA3, 0xA3, 0xA3, 0xF3, 0x9B, 0xA3, 0xA3,
+ 0xDC, 0xB9, 0xA7, 0xF1, 0x26, 0x26, 0x26, 0xD8, 0xD8, 0xFF
+};
+
+#ifndef MPU6050_DMP_FIFO_RATE_DIVISOR
+#define MPU6050_DMP_FIFO_RATE_DIVISOR 0x03
+#endif
+
+static const unsigned char dmpConfig[MPU6050_DMP_CONFIG_SIZE] PROGMEM = {
+// BANK OFFSET LENGTH [DATA]
+ 0x02, 0xEC, 0x04, 0x00, 0x47, 0x7D, 0x1A, // ?
+ 0x03, 0x82, 0x03, 0x4C, 0xCD, 0x6C, // FCFG_1 inv_set_gyro_calibration
+ 0x03, 0xB2, 0x03, 0x36, 0x56, 0x76, // FCFG_3 inv_set_gyro_calibration
+ 0x00, 0x68, 0x04, 0x02, 0xCA, 0xE3, 0x09, // D_0_104 inv_set_gyro_calibration
+ 0x01, 0x0C, 0x04, 0x00, 0x00, 0x00, 0x00, // D_1_152 inv_set_accel_calibration
+ 0x03, 0x86, 0x03, 0x0C, 0xC9, 0x2C, // FCFG_2 inv_set_accel_calibration
+ 0x03, 0x90, 0x03, 0x26, 0x46, 0x66, // (continued)...FCFG_2 inv_set_accel_calibration
+ 0x00, 0x6C, 0x02, 0x40, 0x00, // D_0_108 inv_set_accel_calibration
+
+ 0x02, 0x40, 0x04, 0x00, 0x00, 0x00, 0x00, // CPASS_MTX_00 inv_set_compass_calibration
+ 0x02, 0x44, 0x04, 0x40, 0x00, 0x00, 0x00, // CPASS_MTX_01
+ 0x02, 0x48, 0x04, 0x00, 0x00, 0x00, 0x00, // CPASS_MTX_02
+ 0x02, 0x4C, 0x04, 0x40, 0x00, 0x00, 0x00, // CPASS_MTX_10
+ 0x02, 0x50, 0x04, 0x00, 0x00, 0x00, 0x00, // CPASS_MTX_11
+ 0x02, 0x54, 0x04, 0x00, 0x00, 0x00, 0x00, // CPASS_MTX_12
+ 0x02, 0x58, 0x04, 0x00, 0x00, 0x00, 0x00, // CPASS_MTX_20
+ 0x02, 0x5C, 0x04, 0x00, 0x00, 0x00, 0x00, // CPASS_MTX_21
+ 0x02, 0xBC, 0x04, 0xC0, 0x00, 0x00, 0x00, // CPASS_MTX_22
+
+ 0x01, 0xEC, 0x04, 0x00, 0x00, 0x40, 0x00, // D_1_236 inv_apply_endian_accel
+ 0x03, 0x86, 0x06, 0x0C, 0xC9, 0x2C, 0x97, 0x97, 0x97, // FCFG_2 inv_set_mpu_sensors
+ 0x04, 0x22, 0x03, 0x0D, 0x35, 0x5D, // CFG_MOTION_BIAS inv_turn_on_bias_from_no_motion
+ 0x00, 0xA3, 0x01, 0x00, // ?
+ 0x04, 0x29, 0x04, 0x87, 0x2D, 0x35, 0x3D, // FCFG_5 inv_set_bias_update
+ 0x07, 0x62, 0x05, 0xF1, 0x20, 0x28, 0x30, 0x38, // CFG_8 inv_send_quaternion
+ 0x07, 0x9F, 0x01, 0x30, // CFG_16 inv_set_footer
+ 0x07, 0x67, 0x01, 0x9A, // CFG_GYRO_SOURCE inv_send_gyro
+ 0x07, 0x68, 0x04, 0xF1, 0x28, 0x30, 0x38, // CFG_9 inv_send_gyro -> inv_construct3_fifo
+ 0x07, 0x62, 0x05, 0xF1, 0x20, 0x28, 0x30, 0x38, // ?
+ 0x02, 0x0C, 0x04, 0x00, 0x00, 0x00, 0x00, // ?
+ 0x07, 0x83, 0x06, 0xC2, 0xCA, 0xC4, 0xA3, 0xA3, 0xA3, // ?
+ // SPECIAL 0x01 = enable interrupts
+ 0x00, 0x00, 0x00, 0x01, // SET INT_ENABLE, SPECIAL INSTRUCTION
+ 0x07, 0xA7, 0x01, 0xFE, // ?
+ 0x07, 0x62, 0x05, 0xF1, 0x20, 0x28, 0x30, 0x38, // ?
+ 0x07, 0x67, 0x01, 0x9A, // ?
+ 0x07, 0x68, 0x04, 0xF1, 0x28, 0x30, 0x38, // CFG_12 inv_send_accel -> inv_construct3_fifo
+ 0x07, 0x8D, 0x04, 0xF1, 0x28, 0x30, 0x38, // ??? CFG_12 inv_send_mag -> inv_construct3_fifo
+ 0x02, 0x16, 0x02, 0x00, MPU6050_DMP_FIFO_RATE_DIVISOR // D_0_22 inv_set_fifo_rate
+
+ // This very last 0x03 WAS a 0x09, which drops the FIFO rate down to 20 Hz. 0x07 is 25 Hz,
+ // 0x01 is 100Hz. Going faster than 100Hz (0x00=200Hz) tends to result in very noisy data.
+ // DMP output frequency is calculated easily using this equation: (200Hz / (1 + value))
+
+ // It is important to make sure the host processor can keep up with reading and processing
+ // the FIFO output at the desired rate. Handling FIFO overflow cleanly is also a good idea.
+};
+
+const unsigned char dmpUpdates[MPU6050_DMP_UPDATES_SIZE] PROGMEM = {
+ 0x01, 0xB2, 0x02, 0xFF, 0xF5,
+ 0x01, 0x90, 0x04, 0x0A, 0x0D, 0x97, 0xC0,
+ 0x00, 0xA3, 0x01, 0x00,
+ 0x04, 0x29, 0x04, 0x87, 0x2D, 0x35, 0x3D,
+ 0x01, 0x6A, 0x02, 0x06, 0x00,
+ 0x01, 0x60, 0x08, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x60, 0x04, 0x40, 0x00, 0x00, 0x00,
+ 0x02, 0x60, 0x0C, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x01, 0x08, 0x02, 0x01, 0x20,
+ 0x01, 0x0A, 0x02, 0x00, 0x4E,
+ 0x01, 0x02, 0x02, 0xFE, 0xB3,
+ 0x02, 0x6C, 0x04, 0x00, 0x00, 0x00, 0x00, // READ
+ 0x02, 0x6C, 0x04, 0xFA, 0xFE, 0x00, 0x00,
+ 0x02, 0x60, 0x0C, 0xFF, 0xFF, 0xCB, 0x4D, 0x00, 0x01, 0x08, 0xC1, 0xFF, 0xFF, 0xBC, 0x2C,
+ 0x02, 0xF4, 0x04, 0x00, 0x00, 0x00, 0x00,
+ 0x02, 0xF8, 0x04, 0x00, 0x00, 0x00, 0x00,
+ 0x02, 0xFC, 0x04, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x60, 0x04, 0x40, 0x00, 0x00, 0x00,
+ 0x00, 0x60, 0x04, 0x00, 0x40, 0x00, 0x00
+};
+
+uint8_t MPU6050_9Axis_MotionApps41::dmpInitialize() {
+ // reset device
+ DEBUG_PRINTLN(F("\n\nResetting MPU6050..."));
+ reset();
+ delay(30); // wait after reset
+
+ // disable sleep mode
+ DEBUG_PRINTLN(F("Disabling sleep mode..."));
+ setSleepEnabled(false);
+
+ // get MPU product ID
+ //DEBUG_PRINTLN(F("Getting product ID..."));
+ //uint8_t productID = 0; //getProductID();
+ //DEBUG_PRINT(F("Product ID = "));
+ //DEBUG_PRINT(productID);
+
+ // get MPU hardware revision
+ DEBUG_PRINTLN(F("Selecting user bank 16..."));
+ setMemoryBank(0x10, true, true);
+ DEBUG_PRINTLN(F("Selecting memory byte 6..."));
+ setMemoryStartAddress(0x06);
+ DEBUG_PRINTLN(F("Checking hardware revision..."));
+ uint8_t hwRevision = readMemoryByte();
+ (void)hwRevision; // suppress unused variable compile warning
+ DEBUG_PRINT(F("Revision @ user[16][6] = "));
+ DEBUG_PRINTLNF(hwRevision, HEX);
+ DEBUG_PRINTLN(F("Resetting memory bank selection to 0..."));
+ setMemoryBank(0, false, false);
+
+ // check OTP bank valid
+ DEBUG_PRINTLN(F("Reading OTP bank valid flag..."));
+ uint8_t otpValid = getOTPBankValid();
+ (void)otpValid; // suppress unused variable compile warning
+ DEBUG_PRINT(F("OTP bank is "));
+ DEBUG_PRINTLN(otpValid ? F("valid!") : F("invalid!"));
+
+ // get X/Y/Z gyro offsets
+ DEBUG_PRINTLN(F("Reading gyro offset values..."));
+ int8_t xgOffset = getXGyroOffset();
+ int8_t ygOffset = getYGyroOffset();
+ int8_t zgOffset = getZGyroOffset();
+ DEBUG_PRINT(F("X gyro offset = "));
+ DEBUG_PRINTLN(xgOffset);
+ DEBUG_PRINT(F("Y gyro offset = "));
+ DEBUG_PRINTLN(ygOffset);
+ DEBUG_PRINT(F("Z gyro offset = "));
+ DEBUG_PRINTLN(zgOffset);
+
+ I2Cdev::readByte(devAddr, MPU6050_RA_USER_CTRL, buffer, I2Cdev::readTimeout, wireObj); // ?
+
+ DEBUG_PRINTLN(F("Enabling interrupt latch, clear on any read, AUX bypass enabled"));
+ I2Cdev::writeByte(devAddr, MPU6050_RA_INT_PIN_CFG, 0x32, wireObj);
+
+ // enable MPU AUX I2C bypass mode
+ //DEBUG_PRINTLN(F("Enabling AUX I2C bypass mode..."));
+ //setI2CBypassEnabled(true);
+
+ DEBUG_PRINTLN(F("Setting magnetometer mode to power-down..."));
+ //mag -> setMode(0);
+ I2Cdev::writeByte(0x0E, 0x0A, 0x00, wireObj);
+
+ DEBUG_PRINTLN(F("Setting magnetometer mode to fuse access..."));
+ //mag -> setMode(0x0F);
+ I2Cdev::writeByte(0x0E, 0x0A, 0x0F, wireObj);
+
+ DEBUG_PRINTLN(F("Reading mag magnetometer factory calibration..."));
+ int8_t asax, asay, asaz;
+ //mag -> getAdjustment(&asax, &asay, &asaz);
+ I2Cdev::readBytes(0x0E, 0x10, 3, buffer, I2Cdev::readTimeout, wireObj);
+ asax = (int8_t)buffer[0];
+ asay = (int8_t)buffer[1];
+ asaz = (int8_t)buffer[2];
+ (void)asax; // suppress unused variable compiler warning
+ (void)asay; // suppress unused variable compiler warning
+ (void)asaz; // suppress unused variable compiler warning
+ DEBUG_PRINT(F("Adjustment X/Y/Z = "));
+ DEBUG_PRINT(asax);
+ DEBUG_PRINT(F(" / "));
+ DEBUG_PRINT(asay);
+ DEBUG_PRINT(F(" / "));
+ DEBUG_PRINTLN(asaz);
+
+ DEBUG_PRINTLN(F("Setting magnetometer mode to power-down..."));
+ //mag -> setMode(0);
+ I2Cdev::writeByte(0x0E, 0x0A, 0x00, wireObj);
+
+ // load DMP code into memory banks
+ DEBUG_PRINT(F("Writing DMP code to MPU memory banks ("));
+ DEBUG_PRINT(MPU6050_DMP_CODE_SIZE);
+ DEBUG_PRINTLN(F(" bytes)"));
+ if (writeProgMemoryBlock(dmpMemory, MPU6050_DMP_CODE_SIZE)) {
+ DEBUG_PRINTLN(F("Success! DMP code written and verified."));
+
+ DEBUG_PRINTLN(F("Configuring DMP and related settings..."));
+
+ // write DMP configuration
+ DEBUG_PRINT(F("Writing DMP configuration to MPU memory banks ("));
+ DEBUG_PRINT(MPU6050_DMP_CONFIG_SIZE);
+ DEBUG_PRINTLN(F(" bytes in config def)"));
+ if (writeProgDMPConfigurationSet(dmpConfig, MPU6050_DMP_CONFIG_SIZE)) {
+ DEBUG_PRINTLN(F("Success! DMP configuration written and verified."));
+
+ DEBUG_PRINTLN(F("Setting DMP and FIFO_OFLOW interrupts enabled..."));
+ setIntEnabled(1< setMode(1);
+ I2Cdev::writeByte(0x0E, 0x0A, 0x01, wireObj);
+
+ // setup AK8975 (0x0E) as Slave 0 in read mode
+ DEBUG_PRINTLN(F("Setting up AK8975 read slave 0..."));
+ I2Cdev::writeByte(0x68, MPU6050_RA_I2C_SLV0_ADDR, 0x8E, wireObj);
+ I2Cdev::writeByte(0x68, MPU6050_RA_I2C_SLV0_REG, 0x01, wireObj);
+ I2Cdev::writeByte(0x68, MPU6050_RA_I2C_SLV0_CTRL, 0xDA, wireObj);
+
+ // setup AK8975 (0x0E) as Slave 2 in write mode
+ DEBUG_PRINTLN(F("Setting up AK8975 write slave 2..."));
+ I2Cdev::writeByte(0x68, MPU6050_RA_I2C_SLV2_ADDR, 0x0E, wireObj);
+ I2Cdev::writeByte(0x68, MPU6050_RA_I2C_SLV2_REG, 0x0A, wireObj);
+ I2Cdev::writeByte(0x68, MPU6050_RA_I2C_SLV2_CTRL, 0x81, wireObj);
+ I2Cdev::writeByte(0x68, MPU6050_RA_I2C_SLV2_DO, 0x01, wireObj);
+
+ // setup I2C timing/delay control
+ DEBUG_PRINTLN(F("Setting up slave access delay..."));
+ I2Cdev::writeByte(0x68, MPU6050_RA_I2C_SLV4_CTRL, 0x18, wireObj);
+ I2Cdev::writeByte(0x68, MPU6050_RA_I2C_MST_DELAY_CTRL, 0x05, wireObj);
+
+ // enable interrupts
+ DEBUG_PRINTLN(F("Enabling default interrupt behavior/no bypass..."));
+ I2Cdev::writeByte(0x68, MPU6050_RA_INT_PIN_CFG, 0x00, wireObj);
+
+ // enable I2C master mode and reset DMP/FIFO
+ DEBUG_PRINTLN(F("Enabling I2C master mode..."));
+ I2Cdev::writeByte(0x68, MPU6050_RA_USER_CTRL, 0x20, wireObj);
+ DEBUG_PRINTLN(F("Resetting FIFO..."));
+ I2Cdev::writeByte(0x68, MPU6050_RA_USER_CTRL, 0x24, wireObj);
+ DEBUG_PRINTLN(F("Rewriting I2C master mode enabled because...I don't know"));
+ I2Cdev::writeByte(0x68, MPU6050_RA_USER_CTRL, 0x20, wireObj);
+ DEBUG_PRINTLN(F("Enabling and resetting DMP/FIFO..."));
+ I2Cdev::writeByte(0x68, MPU6050_RA_USER_CTRL, 0xE8, wireObj);
+
+ DEBUG_PRINTLN(F("Writing final memory update 5/19 (function unknown)..."));
+ for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+ writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+ DEBUG_PRINTLN(F("Writing final memory update 6/19 (function unknown)..."));
+ for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+ writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+ DEBUG_PRINTLN(F("Writing final memory update 7/19 (function unknown)..."));
+ for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+ writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+ DEBUG_PRINTLN(F("Writing final memory update 8/19 (function unknown)..."));
+ for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+ writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+ DEBUG_PRINTLN(F("Writing final memory update 9/19 (function unknown)..."));
+ for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+ writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+ DEBUG_PRINTLN(F("Writing final memory update 10/19 (function unknown)..."));
+ for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+ writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+ DEBUG_PRINTLN(F("Writing final memory update 11/19 (function unknown)..."));
+ for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+ writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+
+ DEBUG_PRINTLN(F("Reading final memory update 12/19 (function unknown)..."));
+ for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+ readMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+ #ifdef DEBUG
+ DEBUG_PRINT(F("Read bytes: "));
+ for (j = 0; j < 4; j++) {
+ DEBUG_PRINT(dmpUpdate[3 + j], HEX);
+ DEBUG_PRINT(" ");
+ }
+ DEBUG_PRINTLN("");
+ #endif
+
+ DEBUG_PRINTLN(F("Writing final memory update 13/19 (function unknown)..."));
+ for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+ writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+ DEBUG_PRINTLN(F("Writing final memory update 14/19 (function unknown)..."));
+ for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+ writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+ DEBUG_PRINTLN(F("Writing final memory update 15/19 (function unknown)..."));
+ for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+ writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+ DEBUG_PRINTLN(F("Writing final memory update 16/19 (function unknown)..."));
+ for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+ writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+ DEBUG_PRINTLN(F("Writing final memory update 17/19 (function unknown)..."));
+ for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+ writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+
+ DEBUG_PRINTLN(F("Waiting for FIRO count >= 46..."));
+ while ((fifoCount = getFIFOCount()) < 46);
+ DEBUG_PRINTLN(F("Reading FIFO..."));
+ getFIFOBytes(fifoBuffer, (fifoCount < 128) ? fifoCount : 128); // safeguard only 128 bytes
+ DEBUG_PRINTLN(F("Reading interrupt status..."));
+ getIntStatus();
+
+ DEBUG_PRINTLN(F("Writing final memory update 18/19 (function unknown)..."));
+ for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+ writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+
+ DEBUG_PRINTLN(F("Waiting for FIRO count >= 48..."));
+ while ((fifoCount = getFIFOCount()) < 48);
+ DEBUG_PRINTLN(F("Reading FIFO..."));
+ getFIFOBytes(fifoBuffer, (fifoCount < 128) ? fifoCount : 128); // safeguard only 128 bytes
+ DEBUG_PRINTLN(F("Reading interrupt status..."));
+ getIntStatus();
+ DEBUG_PRINTLN(F("Waiting for FIRO count >= 48..."));
+ while ((fifoCount = getFIFOCount()) < 48);
+ DEBUG_PRINTLN(F("Reading FIFO..."));
+ getFIFOBytes(fifoBuffer, (fifoCount < 128) ? fifoCount : 128); // safeguard only 128 bytes
+ DEBUG_PRINTLN(F("Reading interrupt status..."));
+ getIntStatus();
+
+ DEBUG_PRINTLN(F("Writing final memory update 19/19 (function unknown)..."));
+ for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+ writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+
+ DEBUG_PRINTLN(F("Disabling DMP (you turn it on later)..."));
+ setDMPEnabled(false);
+
+ DEBUG_PRINTLN(F("Setting up internal 48-byte (default) DMP packet buffer..."));
+ dmpPacketSize = 48;
+ /*if ((dmpPacketBuffer = (uint8_t *)malloc(42)) == 0) {
+ return 3; // TODO: proper error code for no memory
+ }*/
+
+ DEBUG_PRINTLN(F("Resetting FIFO and clearing INT status one last time..."));
+ resetFIFO();
+ getIntStatus();
+ } else {
+ DEBUG_PRINTLN(F("ERROR! DMP configuration verification failed."));
+ return 2; // configuration block loading failed
+ }
+ } else {
+ DEBUG_PRINTLN(F("ERROR! DMP code verification failed."));
+ return 1; // main binary block loading failed
+ }
+ return 0; // success
+}
+
+bool MPU6050_9Axis_MotionApps41::dmpPacketAvailable() {
+ return getFIFOCount() >= dmpGetFIFOPacketSize();
+}
+
+// uint8_t MPU6050_9Axis_MotionApps41::dmpSetFIFORate(uint8_t fifoRate);
+// uint8_t MPU6050_9Axis_MotionApps41::dmpGetFIFORate();
+// uint8_t MPU6050_9Axis_MotionApps41::dmpGetSampleStepSizeMS();
+// uint8_t MPU6050_9Axis_MotionApps41::dmpGetSampleFrequency();
+// int32_t MPU6050_9Axis_MotionApps41::dmpDecodeTemperature(int8_t tempReg);
+
+//uint8_t MPU6050_9Axis_MotionApps41::dmpRegisterFIFORateProcess(inv_obj_func func, int16_t priority);
+//uint8_t MPU6050_9Axis_MotionApps41::dmpUnregisterFIFORateProcess(inv_obj_func func);
+//uint8_t MPU6050_9Axis_MotionApps41::dmpRunFIFORateProcesses();
+
+// uint8_t MPU6050_9Axis_MotionApps41::dmpSendQuaternion(uint_fast16_t accuracy);
+// uint8_t MPU6050_9Axis_MotionApps41::dmpSendGyro(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050_9Axis_MotionApps41::dmpSendAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050_9Axis_MotionApps41::dmpSendLinearAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050_9Axis_MotionApps41::dmpSendLinearAccelInWorld(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050_9Axis_MotionApps41::dmpSendControlData(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050_9Axis_MotionApps41::dmpSendSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050_9Axis_MotionApps41::dmpSendExternalSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050_9Axis_MotionApps41::dmpSendGravity(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050_9Axis_MotionApps41::dmpSendPacketNumber(uint_fast16_t accuracy);
+// uint8_t MPU6050_9Axis_MotionApps41::dmpSendQuantizedAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050_9Axis_MotionApps41::dmpSendEIS(uint_fast16_t elements, uint_fast16_t accuracy);
+
+uint8_t MPU6050_9Axis_MotionApps41::dmpGetAccel(int32_t *data, const uint8_t* packet) {
+ // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+ if (packet == 0) packet = dmpPacketBuffer;
+ data[0] = (((uint32_t)packet[34] << 24) | ((uint32_t)packet[35] << 16) | ((uint32_t)packet[36] << 8) | packet[37]);
+ data[1] = (((uint32_t)packet[38] << 24) | ((uint32_t)packet[39] << 16) | ((uint32_t)packet[40] << 8) | packet[41]);
+ data[2] = (((uint32_t)packet[42] << 24) | ((uint32_t)packet[43] << 16) | ((uint32_t)packet[44] << 8) | packet[45]);
+ return 0;
+}
+uint8_t MPU6050_9Axis_MotionApps41::dmpGetAccel(int16_t *data, const uint8_t* packet) {
+ // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+ if (packet == 0) packet = dmpPacketBuffer;
+ data[0] = (packet[34] << 8) | packet[35];
+ data[1] = (packet[38] << 8) | packet[39];
+ data[2] = (packet[42] << 8) | packet[43];
+ return 0;
+}
+uint8_t MPU6050_9Axis_MotionApps41::dmpGetAccel(VectorInt16 *v, const uint8_t* packet) {
+ // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+ if (packet == 0) packet = dmpPacketBuffer;
+ v -> x = (packet[34] << 8) | packet[35];
+ v -> y = (packet[38] << 8) | packet[39];
+ v -> z = (packet[42] << 8) | packet[43];
+ return 0;
+}
+uint8_t MPU6050_9Axis_MotionApps41::dmpGetQuaternion(int32_t *data, const uint8_t* packet) {
+ // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+ if (packet == 0) packet = dmpPacketBuffer;
+ data[0] = (((uint32_t)packet[0] << 24) | ((uint32_t)packet[1] << 16) | ((uint32_t)packet[2] << 8) | packet[3]);
+ data[1] = (((uint32_t)packet[4] << 24) | ((uint32_t)packet[5] << 16) | ((uint32_t)packet[6] << 8) | packet[7]);
+ data[2] = (((uint32_t)packet[8] << 24) | ((uint32_t)packet[9] << 16) | ((uint32_t)packet[10] << 8) | packet[11]);
+ data[3] = (((uint32_t)packet[12] << 24) | ((uint32_t)packet[13] << 16) | ((uint32_t)packet[14] << 8) | packet[15]);
+ return 0;
+}
+uint8_t MPU6050_9Axis_MotionApps41::dmpGetQuaternion(int16_t *data, const uint8_t* packet) {
+ // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+ if (packet == 0) packet = dmpPacketBuffer;
+ data[0] = ((packet[0] << 8) | packet[1]);
+ data[1] = ((packet[4] << 8) | packet[5]);
+ data[2] = ((packet[8] << 8) | packet[9]);
+ data[3] = ((packet[12] << 8) | packet[13]);
+ return 0;
+}
+uint8_t MPU6050_9Axis_MotionApps41::dmpGetQuaternion(Quaternion *q, const uint8_t* packet) {
+ // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+ int16_t qI[4];
+ uint8_t status = dmpGetQuaternion(qI, packet);
+ if (status == 0) {
+ q -> w = (float)qI[0] / 16384.0f;
+ q -> x = (float)qI[1] / 16384.0f;
+ q -> y = (float)qI[2] / 16384.0f;
+ q -> z = (float)qI[3] / 16384.0f;
+ return 0;
+ }
+ return status; // int16 return value, indicates error if this line is reached
+}
+// uint8_t MPU6050_9Axis_MotionApps41::dmpGet6AxisQuaternion(long *data, const uint8_t* packet);
+// uint8_t MPU6050_9Axis_MotionApps41::dmpGetRelativeQuaternion(long *data, const uint8_t* packet);
+uint8_t MPU6050_9Axis_MotionApps41::dmpGetGyro(int32_t *data, const uint8_t* packet) {
+ // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+ if (packet == 0) packet = dmpPacketBuffer;
+ data[0] = (((uint32_t)packet[16] << 24) | ((uint32_t)packet[17] << 16) | ((uint32_t)packet[18] << 8) | packet[19]);
+ data[1] = (((uint32_t)packet[20] << 24) | ((uint32_t)packet[21] << 16) | ((uint32_t)packet[22] << 8) | packet[23]);
+ data[2] = (((uint32_t)packet[24] << 24) | ((uint32_t)packet[25] << 16) | ((uint32_t)packet[26] << 8) | packet[27]);
+ return 0;
+}
+uint8_t MPU6050_9Axis_MotionApps41::dmpGetGyro(int16_t *data, const uint8_t* packet) {
+ // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+ if (packet == 0) packet = dmpPacketBuffer;
+ data[0] = (packet[16] << 8) | packet[17];
+ data[1] = (packet[20] << 8) | packet[21];
+ data[2] = (packet[24] << 8) | packet[25];
+ return 0;
+}
+uint8_t MPU6050_9Axis_MotionApps41::dmpGetMag(int16_t *data, const uint8_t* packet) {
+ // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+ if (packet == 0) packet = dmpPacketBuffer;
+ data[0] = (packet[28] << 8) | packet[29];
+ data[1] = (packet[30] << 8) | packet[31];
+ data[2] = (packet[32] << 8) | packet[33];
+ return 0;
+}
+// uint8_t MPU6050_9Axis_MotionApps41::dmpSetLinearAccelFilterCoefficient(float coef);
+// uint8_t MPU6050_9Axis_MotionApps41::dmpGetLinearAccel(long *data, const uint8_t* packet);
+uint8_t MPU6050_9Axis_MotionApps41::dmpGetLinearAccel(VectorInt16 *v, VectorInt16 *vRaw, VectorFloat *gravity) {
+ // get rid of the gravity component (+1g = +4096 in standard DMP FIFO packet)
+ v -> x = vRaw -> x - gravity -> x*4096;
+ v -> y = vRaw -> y - gravity -> y*4096;
+ v -> z = vRaw -> z - gravity -> z*4096;
+ return 0;
+}
+// uint8_t MPU6050_9Axis_MotionApps41::dmpGetLinearAccelInWorld(long *data, const uint8_t* packet);
+uint8_t MPU6050_9Axis_MotionApps41::dmpGetLinearAccelInWorld(VectorInt16 *v, VectorInt16 *vReal, Quaternion *q) {
+ // rotate measured 3D acceleration vector into original state
+ // frame of reference based on orientation quaternion
+ memcpy(v, vReal, sizeof(VectorInt16));
+ v -> rotate(q);
+ return 0;
+}
+// uint8_t MPU6050_9Axis_MotionApps41::dmpGetGyroAndAccelSensor(long *data, const uint8_t* packet);
+// uint8_t MPU6050_9Axis_MotionApps41::dmpGetGyroSensor(long *data, const uint8_t* packet);
+// uint8_t MPU6050_9Axis_MotionApps41::dmpGetControlData(long *data, const uint8_t* packet);
+// uint8_t MPU6050_9Axis_MotionApps41::dmpGetTemperature(long *data, const uint8_t* packet);
+// uint8_t MPU6050_9Axis_MotionApps41::dmpGetGravity(long *data, const uint8_t* packet);
+uint8_t MPU6050_9Axis_MotionApps41::dmpGetGravity(int16_t *data, const uint8_t* packet) {
+ /* +1g corresponds to +8192, sensitivity is 2g. */
+ int16_t qI[4];
+ uint8_t status = dmpGetQuaternion(qI, packet);
+ data[0] = ((int32_t)qI[1] * qI[3] - (int32_t)qI[0] * qI[2]) / 16384;
+ data[1] = ((int32_t)qI[0] * qI[1] + (int32_t)qI[2] * qI[3]) / 16384;
+ data[2] = ((int32_t)qI[0] * qI[0] - (int32_t)qI[1] * qI[1]
+ - (int32_t)qI[2] * qI[2] + (int32_t)qI[3] * qI[3]) / (int32_t)(2 * 16384L);
+ return status;
+}
+
+uint8_t MPU6050_9Axis_MotionApps41::dmpGetGravity(VectorFloat *v, Quaternion *q) {
+ v -> x = 2 * (q -> x*q -> z - q -> w*q -> y);
+ v -> y = 2 * (q -> w*q -> x + q -> y*q -> z);
+ v -> z = q -> w*q -> w - q -> x*q -> x - q -> y*q -> y + q -> z*q -> z;
+ return 0;
+}
+// uint8_t MPU6050_9Axis_MotionApps41::dmpGetUnquantizedAccel(long *data, const uint8_t* packet);
+// uint8_t MPU6050_9Axis_MotionApps41::dmpGetQuantizedAccel(long *data, const uint8_t* packet);
+// uint8_t MPU6050_9Axis_MotionApps41::dmpGetExternalSensorData(long *data, int size, const uint8_t* packet);
+// uint8_t MPU6050_9Axis_MotionApps41::dmpGetEIS(long *data, const uint8_t* packet);
+
+uint8_t MPU6050_9Axis_MotionApps41::dmpGetEuler(float *data, Quaternion *q) {
+ data[0] = atan2(2*q -> x*q -> y - 2*q -> w*q -> z, 2*q -> w*q -> w + 2*q -> x*q -> x - 1); // psi
+ data[1] = -asin(2*q -> x*q -> z + 2*q -> w*q -> y); // theta
+ data[2] = atan2(2*q -> y*q -> z - 2*q -> w*q -> x, 2*q -> w*q -> w + 2*q -> z*q -> z - 1); // phi
+ return 0;
+}
+
+#ifdef USE_OLD_DMPGETYAWPITCHROLL
+uint8_t MPU6050_9Axis_MotionApps41::dmpGetYawPitchRoll(float *data, Quaternion *q, VectorFloat *gravity) {
+ // yaw: (about Z axis)
+ data[0] = atan2(2*q -> x*q -> y - 2*q -> w*q -> z, 2*q -> w*q -> w + 2*q -> x*q -> x - 1);
+ // pitch: (nose up/down, about Y axis)
+ data[1] = atan(gravity -> x / sqrt(gravity -> y*gravity -> y + gravity -> z*gravity -> z));
+ // roll: (tilt left/right, about X axis)
+ data[2] = atan(gravity -> y / sqrt(gravity -> x*gravity -> x + gravity -> z*gravity -> z));
+ return 0;
+}
+#else
+uint8_t MPU6050_9Axis_MotionApps41::dmpGetYawPitchRoll(float *data, Quaternion *q, VectorFloat *gravity) {
+ // yaw: (about Z axis)
+ data[0] = atan2(2*q -> x*q -> y - 2*q -> w*q -> z, 2*q -> w*q -> w + 2*q -> x*q -> x - 1);
+ // pitch: (nose up/down, about Y axis)
+ data[1] = atan2(gravity -> x , sqrt(gravity -> y*gravity -> y + gravity -> z*gravity -> z));
+ // roll: (tilt left/right, about X axis)
+ data[2] = atan2(gravity -> y , gravity -> z);
+ if(gravity->z<0) {
+ if(data[1]>0) {
+ data[1] = PI - data[1];
+ } else {
+ data[1] = -PI - data[1];
+ }
+ }
+ return 0;
+}
+#endif
+
+// uint8_t MPU6050_9Axis_MotionApps41::dmpGetAccelFloat(float *data, const uint8_t* packet);
+// uint8_t MPU6050_9Axis_MotionApps41::dmpGetQuaternionFloat(float *data, const uint8_t* packet);
+
+uint8_t MPU6050_9Axis_MotionApps41::dmpProcessFIFOPacket(const unsigned char *dmpData) {
+ (void)dmpData; // suppress unused variable compiler warning
+ /*for (uint8_t k = 0; k < dmpPacketSize; k++) {
+ if (dmpData[k] < 0x10) Serial.print("0");
+ Serial.print(dmpData[k], HEX);
+ Serial.print(" ");
+ }
+ Serial.print("\n");*/
+ //Serial.println((uint16_t)dmpPacketBuffer);
+ return 0;
+}
+uint8_t MPU6050_9Axis_MotionApps41::dmpReadAndProcessFIFOPacket(uint8_t numPackets, uint8_t *processed) {
+ uint8_t status;
+ uint8_t buf[dmpPacketSize];
+ for (uint8_t i = 0; i < numPackets; i++) {
+ // read packet from FIFO
+ getFIFOBytes(buf, dmpPacketSize);
+
+ // process packet
+ if ((status = dmpProcessFIFOPacket(buf)) > 0) return status;
+
+ // increment external process count variable, if supplied
+ if (processed != 0) (*processed)++;
+ }
+ return 0;
+}
+
+// uint8_t MPU6050_9Axis_MotionApps41::dmpSetFIFOProcessedCallback(void (*func) (void));
+
+// uint8_t MPU6050_9Axis_MotionApps41::dmpInitFIFOParam();
+// uint8_t MPU6050_9Axis_MotionApps41::dmpCloseFIFO();
+// uint8_t MPU6050_9Axis_MotionApps41::dmpSetGyroDataSource(uint_fast8_t source);
+// uint8_t MPU6050_9Axis_MotionApps41::dmpDecodeQuantizedAccel();
+// uint32_t MPU6050_9Axis_MotionApps41::dmpGetGyroSumOfSquare();
+// uint32_t MPU6050_9Axis_MotionApps41::dmpGetAccelSumOfSquare();
+// void MPU6050_9Axis_MotionApps41::dmpOverrideQuaternion(long *q);
+uint16_t MPU6050_9Axis_MotionApps41::dmpGetFIFOPacketSize() {
+ return dmpPacketSize;
+}
\ No newline at end of file
diff --git a/lib/MPU6050/src/MPU6050_9Axis_MotionApps41.h b/lib/MPU6050/src/MPU6050_9Axis_MotionApps41.h
new file mode 100644
index 0000000..f9569e9
--- /dev/null
+++ b/lib/MPU6050/src/MPU6050_9Axis_MotionApps41.h
@@ -0,0 +1,153 @@
+// I2Cdev library collection - MPU6050 I2C device class
+// Based on InvenSense MPU-6050 register map document rev. 2.0, 5/19/2011 (RM-MPU-6000A-00)
+// 10/3/2011 by Jeff Rowberg
+// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
+//
+// Changelog:
+// 2021/09/27 - split implementations out of header files, finally
+// ... - ongoing debug release
+
+// NOTE: THIS IS ONLY A PARIAL RELEASE. THIS DEVICE CLASS IS CURRENTLY UNDERGOING ACTIVE
+// DEVELOPMENT AND IS STILL MISSING SOME IMPORTANT FEATURES. PLEASE KEEP THIS IN MIND IF
+// YOU DECIDE TO USE THIS PARTICULAR CODE FOR ANYTHING.
+
+/* ============================================
+I2Cdev device library code is placed under the MIT license
+Copyright (c) 2012 Jeff Rowberg
+
+Permission is hereby granted, free of charge, to any person obtaining a copy
+of this software and associated documentation files (the "Software"), to deal
+in the Software without restriction, including without limitation the rights
+to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+copies of the Software, and to permit persons to whom the Software is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in
+all copies or substantial portions of the Software.
+
+THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+THE SOFTWARE.
+===============================================
+*/
+
+#ifndef _MPU6050_6AXIS_MOTIONAPPS41_H_
+#define _MPU6050_6AXIS_MOTIONAPPS41_H_
+
+// take ownership of the "MPU6050" typedef
+#define I2CDEVLIB_MPU6050_TYPEDEF
+
+#include "MPU6050.h"
+
+class MPU6050_9Axis_MotionApps41 : public MPU6050_Base {
+ public:
+ MPU6050_9Axis_MotionApps41(uint8_t address=MPU6050_DEFAULT_ADDRESS, void *wireObj=0) : MPU6050_Base(address, wireObj) { }
+
+ uint8_t dmpInitialize();
+ bool dmpPacketAvailable();
+
+ uint8_t dmpSetFIFORate(uint8_t fifoRate);
+ uint8_t dmpGetFIFORate();
+ uint8_t dmpGetSampleStepSizeMS();
+ uint8_t dmpGetSampleFrequency();
+ int32_t dmpDecodeTemperature(int8_t tempReg);
+
+ // Register callbacks after a packet of FIFO data is processed
+ //uint8_t dmpRegisterFIFORateProcess(inv_obj_func func, int16_t priority);
+ //uint8_t dmpUnregisterFIFORateProcess(inv_obj_func func);
+ uint8_t dmpRunFIFORateProcesses();
+
+ // Setup FIFO for various output
+ uint8_t dmpSendQuaternion(uint_fast16_t accuracy);
+ uint8_t dmpSendGyro(uint_fast16_t elements, uint_fast16_t accuracy);
+ uint8_t dmpSendAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+ uint8_t dmpSendLinearAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+ uint8_t dmpSendLinearAccelInWorld(uint_fast16_t elements, uint_fast16_t accuracy);
+ uint8_t dmpSendControlData(uint_fast16_t elements, uint_fast16_t accuracy);
+ uint8_t dmpSendSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
+ uint8_t dmpSendExternalSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
+ uint8_t dmpSendGravity(uint_fast16_t elements, uint_fast16_t accuracy);
+ uint8_t dmpSendPacketNumber(uint_fast16_t accuracy);
+ uint8_t dmpSendQuantizedAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+ uint8_t dmpSendEIS(uint_fast16_t elements, uint_fast16_t accuracy);
+
+ // Get Fixed Point data from FIFO
+ uint8_t dmpGetAccel(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetAccel(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetAccel(VectorInt16 *v, const uint8_t* packet=0);
+ uint8_t dmpGetQuaternion(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetQuaternion(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetQuaternion(Quaternion *q, const uint8_t* packet=0);
+ uint8_t dmpGet6AxisQuaternion(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGet6AxisQuaternion(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGet6AxisQuaternion(Quaternion *q, const uint8_t* packet=0);
+ uint8_t dmpGetRelativeQuaternion(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetRelativeQuaternion(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetRelativeQuaternion(Quaternion *data, const uint8_t* packet=0);
+ uint8_t dmpGetGyro(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetGyro(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetGyro(VectorInt16 *v, const uint8_t* packet=0);
+ uint8_t dmpGetMag(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpSetLinearAccelFilterCoefficient(float coef);
+ uint8_t dmpGetLinearAccel(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetLinearAccel(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetLinearAccel(VectorInt16 *v, const uint8_t* packet=0);
+ uint8_t dmpGetLinearAccel(VectorInt16 *v, VectorInt16 *vRaw, VectorFloat *gravity);
+ uint8_t dmpGetLinearAccelInWorld(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetLinearAccelInWorld(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetLinearAccelInWorld(VectorInt16 *v, const uint8_t* packet=0);
+ uint8_t dmpGetLinearAccelInWorld(VectorInt16 *v, VectorInt16 *vReal, Quaternion *q);
+ uint8_t dmpGetGyroAndAccelSensor(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetGyroAndAccelSensor(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetGyroAndAccelSensor(VectorInt16 *g, VectorInt16 *a, const uint8_t* packet=0);
+ uint8_t dmpGetGyroSensor(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetGyroSensor(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetGyroSensor(VectorInt16 *v, const uint8_t* packet=0);
+ uint8_t dmpGetControlData(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetTemperature(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetGravity(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetGravity(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetGravity(VectorInt16 *v, const uint8_t* packet=0);
+ uint8_t dmpGetGravity(VectorFloat *v, Quaternion *q);
+ uint8_t dmpGetUnquantizedAccel(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetUnquantizedAccel(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetUnquantizedAccel(VectorInt16 *v, const uint8_t* packet=0);
+ uint8_t dmpGetQuantizedAccel(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetQuantizedAccel(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetQuantizedAccel(VectorInt16 *v, const uint8_t* packet=0);
+ uint8_t dmpGetExternalSensorData(int32_t *data, uint16_t size, const uint8_t* packet=0);
+ uint8_t dmpGetEIS(int32_t *data, const uint8_t* packet=0);
+
+ uint8_t dmpGetEuler(float *data, Quaternion *q);
+ uint8_t dmpGetYawPitchRoll(float *data, Quaternion *q, VectorFloat *gravity);
+
+ // Get Floating Point data from FIFO
+ uint8_t dmpGetAccelFloat(float *data, const uint8_t* packet=0);
+ uint8_t dmpGetQuaternionFloat(float *data, const uint8_t* packet=0);
+
+ uint8_t dmpProcessFIFOPacket(const unsigned char *dmpData);
+ uint8_t dmpReadAndProcessFIFOPacket(uint8_t numPackets, uint8_t *processed=NULL);
+
+ uint8_t dmpSetFIFOProcessedCallback(void (*func) (void));
+
+ uint8_t dmpInitFIFOParam();
+ uint8_t dmpCloseFIFO();
+ uint8_t dmpSetGyroDataSource(uint8_t source);
+ uint8_t dmpDecodeQuantizedAccel();
+ uint32_t dmpGetGyroSumOfSquare();
+ uint32_t dmpGetAccelSumOfSquare();
+ void dmpOverrideQuaternion(long *q);
+ uint16_t dmpGetFIFOPacketSize();
+
+ private:
+ uint8_t *dmpPacketBuffer;
+ uint16_t dmpPacketSize;
+};
+
+typedef MPU6050_9Axis_MotionApps41 MPU6050;
+
+#endif /* _MPU6050_6AXIS_MOTIONAPPS41_H_ */
\ No newline at end of file
diff --git a/lib/MPU6050/src/helper_3dmath.h b/lib/MPU6050/src/helper_3dmath.h
new file mode 100755
index 0000000..9f431a2
--- /dev/null
+++ b/lib/MPU6050/src/helper_3dmath.h
@@ -0,0 +1,216 @@
+// I2C device class (I2Cdev) demonstration Arduino sketch for MPU6050 class, 3D math helper
+// 6/5/2012 by Jeff Rowberg
+// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
+//
+// Changelog:
+// 2012-06-05 - add 3D math helper file to DMP6 example sketch
+
+/* ============================================
+I2Cdev device library code is placed under the MIT license
+Copyright (c) 2012 Jeff Rowberg
+
+Permission is hereby granted, free of charge, to any person obtaining a copy
+of this software and associated documentation files (the "Software"), to deal
+in the Software without restriction, including without limitation the rights
+to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+copies of the Software, and to permit persons to whom the Software is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in
+all copies or substantial portions of the Software.
+
+THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+THE SOFTWARE.
+===============================================
+*/
+
+#ifndef _HELPER_3DMATH_H_
+#define _HELPER_3DMATH_H_
+
+class Quaternion {
+ public:
+ float w;
+ float x;
+ float y;
+ float z;
+
+ Quaternion() {
+ w = 1.0f;
+ x = 0.0f;
+ y = 0.0f;
+ z = 0.0f;
+ }
+
+ Quaternion(float nw, float nx, float ny, float nz) {
+ w = nw;
+ x = nx;
+ y = ny;
+ z = nz;
+ }
+
+ Quaternion getProduct(Quaternion q) {
+ // Quaternion multiplication is defined by:
+ // (Q1 * Q2).w = (w1w2 - x1x2 - y1y2 - z1z2)
+ // (Q1 * Q2).x = (w1x2 + x1w2 + y1z2 - z1y2)
+ // (Q1 * Q2).y = (w1y2 - x1z2 + y1w2 + z1x2)
+ // (Q1 * Q2).z = (w1z2 + x1y2 - y1x2 + z1w2
+ return Quaternion(
+ w*q.w - x*q.x - y*q.y - z*q.z, // new w
+ w*q.x + x*q.w + y*q.z - z*q.y, // new x
+ w*q.y - x*q.z + y*q.w + z*q.x, // new y
+ w*q.z + x*q.y - y*q.x + z*q.w); // new z
+ }
+
+ Quaternion getConjugate() {
+ return Quaternion(w, -x, -y, -z);
+ }
+
+ float getMagnitude() {
+ return sqrt(w*w + x*x + y*y + z*z);
+ }
+
+ void normalize() {
+ const float im = 1.0f / getMagnitude();
+ w *= im;
+ x *= im;
+ y *= im;
+ z *= im;
+ }
+
+ Quaternion getNormalized() {
+ Quaternion r(w, x, y, z);
+ r.normalize();
+ return r;
+ }
+};
+
+class VectorInt16 {
+ public:
+ int16_t x;
+ int16_t y;
+ int16_t z;
+
+ VectorInt16() {
+ x = 0;
+ y = 0;
+ z = 0;
+ }
+
+ VectorInt16(int16_t nx, int16_t ny, int16_t nz) {
+ x = nx;
+ y = ny;
+ z = nz;
+ }
+
+ float getMagnitude() {
+ return sqrt(x*x + y*y + z*z);
+ }
+
+ void normalize() {
+ const float im = 1.0f / getMagnitude();
+ x *= im;
+ y *= im;
+ z *= im;
+ }
+
+ VectorInt16 getNormalized() {
+ VectorInt16 r(x, y, z);
+ r.normalize();
+ return r;
+ }
+
+ void rotate(Quaternion *q) {
+ // http://www.cprogramming.com/tutorial/3d/quaternions.html
+ // http://www.euclideanspace.com/maths/algebra/realNormedAlgebra/quaternions/transforms/index.htm
+ // http://content.gpwiki.org/index.php/OpenGL:Tutorials:Using_Quaternions_to_represent_rotation
+ // ^ or: http://webcache.googleusercontent.com/search?q=cache:xgJAp3bDNhQJ:content.gpwiki.org/index.php/OpenGL:Tutorials:Using_Quaternions_to_represent_rotation&hl=en&gl=us&strip=1
+
+ // P_out = q * P_in * conj(q)
+ // - P_out is the output vector
+ // - q is the orientation quaternion
+ // - P_in is the input vector (a*aReal)
+ // - conj(q) is the conjugate of the orientation quaternion (q=[w,x,y,z], q*=[w,-x,-y,-z])
+ Quaternion p(0, x, y, z);
+
+ // quaternion multiplication: q * p, stored back in p
+ p = q -> getProduct(p);
+
+ // quaternion multiplication: p * conj(q), stored back in p
+ p = p.getProduct(q -> getConjugate());
+
+ // p quaternion is now [0, x', y', z']
+ x = p.x;
+ y = p.y;
+ z = p.z;
+ }
+
+ VectorInt16 getRotated(Quaternion *q) {
+ VectorInt16 r(x, y, z);
+ r.rotate(q);
+ return r;
+ }
+};
+
+class VectorFloat {
+ public:
+ float x;
+ float y;
+ float z;
+
+ VectorFloat() {
+ x = 0;
+ y = 0;
+ z = 0;
+ }
+
+ VectorFloat(float nx, float ny, float nz) {
+ x = nx;
+ y = ny;
+ z = nz;
+ }
+
+ float getMagnitude() {
+ return sqrt(x*x + y*y + z*z);
+ }
+
+ void normalize() {
+ const float m = 1.0f / getMagnitude();
+ x *= m;
+ y *= m;
+ z *= m;
+ }
+
+ VectorFloat getNormalized() {
+ VectorFloat r(x, y, z);
+ r.normalize();
+ return r;
+ }
+
+ void rotate(Quaternion *q) {
+ Quaternion p(0, x, y, z);
+
+ // quaternion multiplication: q * p, stored back in p
+ p = q -> getProduct(p);
+
+ // quaternion multiplication: p * conj(q), stored back in p
+ p = p.getProduct(q -> getConjugate());
+
+ // p quaternion is now [0, x', y', z']
+ x = p.x;
+ y = p.y;
+ z = p.z;
+ }
+
+ VectorFloat getRotated(Quaternion *q) {
+ VectorFloat r(x, y, z);
+ r.rotate(q);
+ return r;
+ }
+};
+
+#endif /* _HELPER_3DMATH_H_ */
\ No newline at end of file
diff --git a/lib/OSC/API.md b/lib/OSC/API.md
new file mode 100644
index 0000000..6941485
--- /dev/null
+++ b/lib/OSC/API.md
@@ -0,0 +1,395 @@
+# OSCMessage
+
+An OSCMessage is an address followed by any number of data. Messages can have mixed data types like an integer followed by a string followed by a float, etc.
+
+## Constructor
+
+OSCMessages can be constructed with or without an address.
+
+### `OSCMessage(const char *)`
+
+Set the address of the message in the constructor
+
+```C++
+OSCMessage msg("/address");
+```
+
+### `OSCMessage()`
+
+An OSCMessage constructed without an address is not valid until it is given an address.
+
+## Add/Set Data
+
+
+### `OSCMessage& add(int i)`
+
+Append an integer to the OSCMessage.
+
+```C++
+msg.add(1);
+```
+
+
+### `OSCMessage& add(float f)`
+
+Append a float to the OSCMessage.
+
+
+
+### `OSCMessage& add(bool b)`
+
+Append a boolean to the OSCMessage.
+
+
+
+### `OSCMessage& add(const char * str)`
+
+Append a string to the OSCMessage.
+
+```C++
+msg.add("hello");
+```
+
+
+### `OSCMessage& add(uint8_t * blob, int length)`
+
+Append a [blob](https://en.wikipedia.org/wiki/Binary_large_object) to the OSCMessage. Pass in the length of the blob as the second argument.
+
+
+
+### `OSCMessage& set(int position, Type data)`
+
+Replace the data at the given position with the data. `Type` can be any of the supported data types.
+
+```C++
+//replace the data at the 0th position with a string
+msg.set(0, "string");
+```
+
+
+### `OSCMessage& set(int position, uint8_t * data, int length)`
+
+Set the data at the given position to be a blob of the given length.
+
+
+### `OSCMessage& add(double d)`
+
+Append a double precision floating point value to the OSCMessage. NOTE: double is not supported on most Arduino platforms. It will fall back to float, when double is not supported.
+
+## Get Data
+
+
+### `int getInt(int position)`
+
+Returns the integer at the given position
+
+```C++
+//returns the integer at the third position
+msg.getInt(2);
+```
+
+### `float getFloat(int position)`
+
+Returns the float at the given position
+
+
+
+### `bool getBoolean(int position)`
+
+Returns the boolean at the given position
+
+
+
+### `double getDouble(int position)`
+
+Returns the double at the given position. NOTE: double is not supported by most Arduino platforms. This will fail silently if double is not supported.
+
+### `int getString(int position, char * strBuffer)`
+
+Copy the string’s characters into the `strBuffer`, without any safety check.
+Returns the number of copied characters.
+
+### `int getString(int position, char * strBuffer, int length)`
+
+Copy the string’s characters into the `strBuffer`, after checking that this doesn’t exceed the buffer’s `length`.
+Returns the number of copied characters. NOTE that if the string length is greater than the available buffer length, then NO characters are copied.
+
+### `int getString(int position, char * strBuffer, int length, int offset, int size)`
+
+Copy `size` number of characters from the given `offset` into the `strBuffer`, after checking that this doesn’t exceed the buffer’s `length`. Returns `size`, even if the number of copied characters is lower.
+```C++
+char str[8];
+//fill str with 8 characters from the 0th datum
+msg.getString(0, str, 8, 0, 8);
+```
+
+### `int getBlob(int position, uint8_t * blobBuffer)`
+
+Directly copy the blob’s bytes into the `blob` buffer (without safety-check).
+Returns the number of bytes from the blob.
+
+
+### `int getBlob(int position, uint8_t * blobBuffer, int length)`
+
+Copy the blob's bytes into the given `blobBuffer`, if the blob's size doesn’t exceed the blobBuffer's `length`.
+Returns the number of bytes copied from the blob. NOTE that if the blob length is greater than the available buffer length, then NO bytes are copied.
+
+### `int getBlob(int position, uint8_t * blobBuffer, int length, int offset, int size)`
+
+Copy `size` bytes from the blob, starting from `offset`, into the given `blobBuffer`, if the size doesn’t exceed the buffer’s `length` or the blob’s data length.
+Returns the number of bytes copied from the blob. NOTE that if the requested size is greater than *either* the available buffer length *or* the (partial) blob length, then NO bytes are copied.
+
+
+### `const uint8_t* getBlob(int position)`
+
+Get a pointer to blob data.
+
+
+### `int getBlobLength(int position)`
+
+Returns the length of the blob in bytes.
+
+
+### `char getType(int position)`
+
+Returns the type of the data at the given position.
+
+```C++
+OSCMessage msg("/address");
+msg.add(1);
+msg.getType(0); //-> returns 'i'
+```
+
+
+## Query Data
+
+### `bool isInt(int position)`
+
+Returns `true` when the data at the given position is an integer.
+
+### `bool isFloat(int position)`
+
+Returns `true` when the data at the given position is a float.
+
+### `bool isBoolean(int position)`
+
+Returns `true` when the data at the given position is a boolean.
+
+### `bool isString(int position)`
+
+Returns `true` when the data at the given position is a string.
+
+### `bool isBlob(int position)`
+
+Returns `true` when the data at the given position is a blob.
+
+### `bool isDouble(int position)`
+
+Returns `true` when the data at the given position is a double.
+
+### `int size()`
+
+Returns the number of data the OSCMessage has.
+
+### `int bytes()`
+
+Returns the size of the OSCMessage in bytes (if everything is 32-bit aligned).
+
+
+
+## Address
+
+### `OSCMessage& setAddress(const char * address)`
+
+Set the address of the OSCMessage.
+
+### `int getAddress(char * str, int offset=0)`
+
+Copy the address of the OSCMessage into the `str` buffer. Copy after the given address `offset` (defaults to 0). Returns the length of the resulting string. If the offset is past the end of the address an empty string / zero length are returned.
+
+### `int getAddress(char * str, int offset, int len)`
+
+Copy a maximum of len characters of the address of the OSCMessage into the `str` buffer, starting at at the given address `offset`. Returns the length of the resulting string. If the offset is past the end of the address an empty string / zero length are returned.
+
+### `int getAddressLength(int offset=0)`
+
+Returns the length of the OSCMessage's address, starting after the given address `offset` (defaults to 0). If the offset is
+greater than the address length then it returns zero.
+
+### `const char* getAddress()`
+
+Get a pointer to the address as a C string.
+
+## Send Receive
+
+### `OSCMessage& send(Print &p)`
+
+Output the message to the given transport layer which extends Arduino's [Print class](http://playground.arduino.cc/Code/Printclass) like the `Serial` out.
+
+```C++
+msg.send(SLIPSerial);
+```
+
+### `OSCMessage& fill(uint8_t incomingByte)`
+
+Add the incoming byte to the OSCMessage where it will be decoded.
+
+### `OSCMessage& fill(uint8_t * bytes, int length)`
+
+Add and decode the array of `bytes` as an OSCMessage.
+
+
+
+## Matching / Routing
+
+### `bool fullMatch( const char * pattern, int offset = 0)`
+
+Returns true if the message's address is a full match to the given `pattern` after the `offset`.
+
+```C++
+OSCMessage msg("/a/0");
+msg.fullMatch("/0", 2); // ->returns true
+```
+
+### `int match( const char * pattern, int offset = 0)`
+
+Returns the number of matched characters of the message's address against the given `pattern` (optionally with an `offset`). Unlike `fullMatch`, `match` allows for partial matches
+
+```C++
+OSCMessage msg("/a/0");
+msg.match("/a"); // ->returns 2
+```
+
+### `bool dispatch(const char * pattern, void (*callback)(OSCMessage &), int offset = 0)`
+
+Invoke the given `callback` if the address is a full match with the `pattern` (after the `offset`). The message is passed into the callback function. Returns true if the pattern was a match and the callback function was invoked.
+
+### `bool route(const char * pattern, void (*callback)(OSCMessage &, int), int offset = 0)`
+
+Invoke the given `callback` if the address if a match with the `pattern` (after the `offset`). The OSCMessage and the address offset is passed into the callback function. Returns true if the pattern was a match and the callback function was invoked.
+
+```C++
+//define a callback function for matching messages
+void routeCallback(OSCMessage & message, int addressOffset){
+ //do something with the message...
+
+ //with the message below, the addressOffset will equal 2.
+}
+
+OSCMessage msg("/a/0");
+msg.route("/a", routeCallback);
+```
+
+
+## Address Patterns
+
+OSCMessages can be constructed with patterns and later routed or dispatched against addresses.
+
+```C++
+OSCMessage msg("/{a,b}/[0-9]");
+msg.route("/a/0", a0_callback); //matches the address
+msg.route("/b/2", b2_callback); //matches the address
+msg.route("/c/11", c11_callback); //not invoked
+```
+
+# OSCBundle
+
+A bundle is a group of OSCMessages with a timetag.
+
+
+## Constructor
+
+### `OSCBundle()`
+
+Construct an empty OSCBundle.
+
+### `OSCBundle(osctime_t = zerotime)`
+
+Construct the bundle with a timetag. timetag defaults to 0 (immediate).
+
+
+
+## Add OSCMessage
+
+### `OSCMessage & add(char * address)`
+
+Create a new message with the given `address` in the bundle. Returns the newly created OSCMessage.
+
+```C++
+//create a new OSCMessage and add some data to it
+bundle.add("/message").add("data");
+```
+
+
+## Get OSCMessage
+
+### `OSCMessage * getOSCMessage(int position)`
+
+Return the OSCMessage in the bundle at the given `position`.
+
+```C++
+OSCBundle bundle
+bundle.add("/a");
+bundle.add("/b");
+bundle.getOSCMessage(0);//returns the OSCMessage with the address "/a".
+```
+
+### `OSCMessage * getOSCMessage(char * address)`
+
+Return the OSCMessage in the bundle which matches the given address.
+
+```C++
+OSCBundle bundle
+bundle.add("/a");
+bundle.add("/b");
+bundle.getOSCMessage("/b");//returns the second OSCMessage in the bundle
+```
+
+
+## Routing
+
+### `bool dispatch(const char * pattern, void (*callback)(OSCMessage&), int offset = 0)`
+
+Invoke the `callback` function with all messages in the bundle which match the given pattern after the offset.
+
+```C++
+bundle.add("/a/0");
+bundle.add("/b/0");
+bundle.dispatch("/0", dispatchZero, 2);
+```
+
+### `bool route(const char * pattern, void (*callback)(OSCMessage &, int), int offset = 0)`
+
+Invoke the `callback` with all the OSCMessages in the bundle which match the given `pattern`. `route` allows for partial matches.
+
+
+
+## Send/Receive
+
+### `OSCBundle& send(Print &p)`
+
+Output the bundle to the given transport layer which extends Arduino's [Print class](http://playground.arduino.cc/Code/Printclass) (such as `SLIPSerial` out).
+
+```C++
+bundle.send(SLIPSerial);
+```
+
+### `OSCBundle& fill(uint8_t incomingByte)`
+
+Add the incoming byte to the OSCBundle where it will be decoded.
+
+### `OSCBundle& fill(uint8_t * bytes, int length)`
+
+Add and decode the array of bytes as an OSCBundle.
+
+
+
+# Chaining
+
+Many methods return `this` which enables you to string together multiple commands.
+
+This technique allows multiple lines to be condensed into one:
+
+```C++
+bundle.add("/address").add("data").add(0).send(SLIPSerial).empty();
+```
diff --git a/lib/OSC/Applications/MaxMSP/examples/OSCEsplora.maxpat b/lib/OSC/Applications/MaxMSP/examples/OSCEsplora.maxpat
new file mode 100644
index 0000000..01631f3
--- /dev/null
+++ b/lib/OSC/Applications/MaxMSP/examples/OSCEsplora.maxpat
@@ -0,0 +1,306 @@
+{
+ "patcher" : {
+ "fileversion" : 1,
+ "appversion" : {
+ "major" : 7,
+ "minor" : 0,
+ "revision" : 4,
+ "architecture" : "x86",
+ "modernui" : 1
+ }
+,
+ "rect" : [ 130.0, 174.0, 983.0, 623.0 ],
+ "bglocked" : 0,
+ "openinpresentation" : 0,
+ "default_fontsize" : 12.0,
+ "default_fontface" : 0,
+ "default_fontname" : "Arial",
+ "gridonopen" : 1,
+ "gridsize" : [ 15.0, 15.0 ],
+ "gridsnaponopen" : 1,
+ "objectsnaponopen" : 1,
+ "statusbarvisible" : 2,
+ "toolbarvisible" : 1,
+ "lefttoolbarpinned" : 0,
+ "toptoolbarpinned" : 0,
+ "righttoolbarpinned" : 0,
+ "bottomtoolbarpinned" : 0,
+ "toolbars_unpinned_last_save" : 0,
+ "tallnewobj" : 0,
+ "boxanimatetime" : 200,
+ "enablehscroll" : 1,
+ "enablevscroll" : 1,
+ "devicewidth" : 0.0,
+ "description" : "",
+ "digest" : "",
+ "tags" : "",
+ "style" : "",
+ "subpatcher_template" : "",
+ "boxes" : [ {
+ "box" : {
+ "fontface" : 0,
+ "fontsize" : 12.0,
+ "id" : "obj-5",
+ "maxclass" : "o.display",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 141.0, 266.0, 150.0, 34.0 ],
+ "textcolor" : [ 1.0, 1.0, 1.0, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-3",
+ "linecount" : 6,
+ "maxclass" : "o.display",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 422.5, 125.0, 158.0, 101.0 ],
+ "text" : "/port : \"usbmodemOSCes41\",\n/rate/output : 0,\n/rate/input : 0,\n/mediansize/received : -1,\n/baud",
+ "textcolor" : [ 1.0, 1.0, 1.0, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-2",
+ "linecount" : 2,
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 389.5, -32.5, 170.0, 33.0 ],
+ "style" : "",
+ "text" : "Look for your device in the menu list of serial USB"
+ }
+
+ }
+, {
+ "box" : {
+ "bgmode" : 0,
+ "border" : 0,
+ "clickthrough" : 0,
+ "enablehscroll" : 0,
+ "enablevscroll" : 0,
+ "id" : "obj-7",
+ "lockeddragscroll" : 0,
+ "maxclass" : "bpatcher",
+ "name" : "o.io.serial.display.maxpat",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "offset" : [ 3.0, 0.0 ],
+ "outlettype" : [ "FullPacket" ],
+ "patching_rect" : [ 81.5, 29.0, 340.5, 25.0 ],
+ "viewvisibility" : 1
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-23",
+ "maxclass" : "newobj",
+ "numinlets" : 2,
+ "numoutlets" : 2,
+ "outlettype" : [ "FullPacket", "FullPacket" ],
+ "patching_rect" : [ 20.5, 68.0, 80.0, 22.0 ],
+ "style" : "",
+ "text" : "o.io.slipserial"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-11",
+ "linecount" : 3,
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 471.0, 29.0, 150.0, 54.0 ],
+ "style" : "",
+ "text" : "stats on serial OSC communications"
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontsize" : 12.0,
+ "id" : "obj-6",
+ "maxclass" : "o.display",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 214.0, 285.0, 150.0, 34.0 ],
+ "textcolor" : [ 1.0, 1.0, 1.0, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontsize" : 12.0,
+ "id" : "obj-4",
+ "maxclass" : "o.display",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 23.0, 285.0, 150.0, 34.0 ],
+ "textcolor" : [ 1.0, 1.0, 1.0, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-1",
+ "maxclass" : "newobj",
+ "numinlets" : 1,
+ "numoutlets" : 3,
+ "outlettype" : [ "", "", "FullPacket" ],
+ "patching_rect" : [ 23.0, 176.0, 119.0, 22.0 ],
+ "style" : "",
+ "text" : "o.route /raw /cooked"
+ }
+
+ }
+ ],
+ "lines" : [ {
+ "patchline" : {
+ "destination" : [ "obj-4", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-1", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-6", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-1", 1 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-1", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-23", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-3", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "midpoints" : [ 91.0, 109.0, 432.0, 109.0 ],
+ "source" : [ "obj-23", 1 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-5", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-23", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-7", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "midpoints" : [ 91.0, 95.0, 433.0, 95.0, 433.0, 5.0, 91.0, 5.0 ],
+ "source" : [ "obj-23", 1 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-23", 1 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-7", 0 ]
+ }
+
+ }
+ ],
+ "dependency_cache" : [ {
+ "name" : "o.io.slipserial.maxpat",
+ "bootpath" : "~/Documents/Max/Packages/o.io/experimental/Protocols/serial",
+ "type" : "JSON",
+ "implicit" : 1
+ }
+, {
+ "name" : "o.righttoleft.maxpat",
+ "bootpath" : "~/Documents/Max/Packages/odot/patchers/ordering",
+ "type" : "JSON",
+ "implicit" : 1
+ }
+, {
+ "name" : "o.io.serial.display.maxpat",
+ "bootpath" : "~/Documents/Max/Packages/o.io/experimental/Protocols/serial",
+ "type" : "JSON",
+ "implicit" : 1
+ }
+, {
+ "name" : "o.route.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.display.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.pack.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.union.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.validate.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.print.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.slip.encode.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.slip.decode.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.if.mxo",
+ "type" : "iLaX"
+ }
+ ],
+ "embedsnapshot" : 0
+ }
+
+}
diff --git a/lib/OSC/Applications/MaxMSP/examples/SerialCallResponse.maxpat b/lib/OSC/Applications/MaxMSP/examples/SerialCallResponse.maxpat
new file mode 100644
index 0000000..a799bc8
--- /dev/null
+++ b/lib/OSC/Applications/MaxMSP/examples/SerialCallResponse.maxpat
@@ -0,0 +1,974 @@
+{
+ "patcher" : {
+ "fileversion" : 1,
+ "appversion" : {
+ "major" : 7,
+ "minor" : 0,
+ "revision" : 4,
+ "architecture" : "x86",
+ "modernui" : 1
+ }
+,
+ "rect" : [ 140.0, 78.0, 1266.0, 737.0 ],
+ "bglocked" : 0,
+ "openinpresentation" : 0,
+ "default_fontsize" : 14.0,
+ "default_fontface" : 0,
+ "default_fontname" : "Andale Mono",
+ "gridonopen" : 1,
+ "gridsize" : [ 5.0, 5.0 ],
+ "gridsnaponopen" : 1,
+ "objectsnaponopen" : 1,
+ "statusbarvisible" : 2,
+ "toolbarvisible" : 1,
+ "lefttoolbarpinned" : 0,
+ "toptoolbarpinned" : 0,
+ "righttoolbarpinned" : 0,
+ "bottomtoolbarpinned" : 0,
+ "toolbars_unpinned_last_save" : 0,
+ "tallnewobj" : 0,
+ "boxanimatetime" : 200,
+ "enablehscroll" : 1,
+ "enablevscroll" : 1,
+ "devicewidth" : 0.0,
+ "description" : "",
+ "digest" : "",
+ "tags" : "",
+ "style" : "",
+ "subpatcher_template" : "",
+ "boxes" : [ {
+ "box" : {
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-6",
+ "linecount" : 2,
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 725.5, 158.0, 170.0, 33.0 ],
+ "style" : "",
+ "text" : "Look for your device in the menu list of serial USB"
+ }
+
+ }
+, {
+ "box" : {
+ "bgmode" : 0,
+ "border" : 0,
+ "clickthrough" : 0,
+ "enablehscroll" : 0,
+ "enablevscroll" : 0,
+ "id" : "obj-9",
+ "lockeddragscroll" : 0,
+ "maxclass" : "bpatcher",
+ "name" : "o.io.serial.display.maxpat",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "offset" : [ 3.0, 0.0 ],
+ "outlettype" : [ "FullPacket" ],
+ "patching_rect" : [ 338.5, 162.0, 340.5, 25.0 ],
+ "viewvisibility" : 1
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontsize" : 14.0,
+ "id" : "obj-8",
+ "maxclass" : "o.display",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 240.5, 252.0, 150.0, 36.0 ],
+ "textcolor" : [ 1.0, 1.0, 1.0, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontsize" : 14.0,
+ "id" : "obj-5",
+ "maxclass" : "o.display",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 491.0, 252.0, 150.0, 36.0 ],
+ "textcolor" : [ 1.0, 1.0, 1.0, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-7",
+ "maxclass" : "o.message",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 521.0, 81.0, 150.0, 20.0 ],
+ "text" : "/analog/{2,3}/u",
+ "textcolor" : [ 0.0, 0.0, 0.0, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-1",
+ "linecount" : 2,
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 524.5, 16.0, 222.0, 38.0 ],
+ "style" : "",
+ "text" : "read analog pins 2 and 3 with pullup turned on"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-78",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 504.5, 15.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-79",
+ "maxclass" : "newobj",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 504.5, 46.0, 86.0, 24.0 ],
+ "style" : "",
+ "text" : "qmetro 20"
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-55",
+ "maxclass" : "o.message",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 266.0, 81.0, 150.0, 20.0 ],
+ "text" : "/analog/[0-3]/u",
+ "textcolor" : [ 0.0, 0.0, 0.0, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-28",
+ "maxclass" : "o.message",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 19.0, 81.0, 150.0, 20.0 ],
+ "text" : "/analog/*",
+ "textcolor" : [ 0.0, 0.0, 0.0, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-56",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 174.0, 455.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-64",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 172.0, 350.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[37]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[25]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-13",
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 3.0, 493.0, 145.0, 22.0 ],
+ "style" : "",
+ "text" : "analog readings"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-110",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 135.0, 454.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-109",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 102.0, 454.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-108",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 69.0, 454.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-107",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 36.0, 454.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-105",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 135.0, 350.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[19]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[4]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-104",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 102.0, 350.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[20]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[3]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-103",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 69.0, 350.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[21]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[2]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-102",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 36.0, 350.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[22]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[1]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-101",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 3.0, 350.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[23]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-84",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 3.0, 454.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-81",
+ "maxclass" : "newobj",
+ "numinlets" : 1,
+ "numoutlets" : 7,
+ "outlettype" : [ "", "", "", "", "", "", "FullPacket" ],
+ "patching_rect" : [ 8.0, 310.0, 221.0, 24.0 ],
+ "style" : "",
+ "text" : "o.route /0 /1 /2 /3 /4 /5"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-45",
+ "maxclass" : "newobj",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "FullPacket" ],
+ "patching_rect" : [ 3.0, 252.0, 137.0, 24.0 ],
+ "style" : "",
+ "text" : "o.route /analog"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-15",
+ "linecount" : 2,
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 269.5, 17.0, 187.0, 38.0 ],
+ "style" : "",
+ "text" : "read analog pins 0-3 with pullup turned on"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-18",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 249.5, 17.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-22",
+ "maxclass" : "newobj",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 249.5, 47.0, 86.0, 24.0 ],
+ "style" : "",
+ "text" : "qmetro 20"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-46",
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 32.5, 18.0, 187.0, 22.0 ],
+ "style" : "",
+ "text" : "read all analog pins"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-60",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 12.5, 18.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-61",
+ "maxclass" : "newobj",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 12.5, 47.0, 95.0, 24.0 ],
+ "style" : "",
+ "text" : "qmetro 100"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-4",
+ "linecount" : 3,
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 702.5, 243.0, 150.0, 54.0 ],
+ "style" : "",
+ "text" : "stats on serial OSC communications"
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-26",
+ "maxclass" : "newobj",
+ "numinlets" : 2,
+ "numoutlets" : 2,
+ "outlettype" : [ "FullPacket", "FullPacket" ],
+ "patching_rect" : [ 220.5, 201.0, 137.0, 24.0 ],
+ "style" : "",
+ "text" : "o.io.slipserial"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-91",
+ "maxclass" : "newobj",
+ "numinlets" : 0,
+ "numoutlets" : 0,
+ "patcher" : {
+ "fileversion" : 1,
+ "appversion" : {
+ "major" : 7,
+ "minor" : 0,
+ "revision" : 4,
+ "architecture" : "x86",
+ "modernui" : 1
+ }
+,
+ "rect" : [ 34.0, 78.0, 738.0, 421.0 ],
+ "bglocked" : 0,
+ "openinpresentation" : 0,
+ "default_fontsize" : 14.0,
+ "default_fontface" : 0,
+ "default_fontname" : "Andale Mono",
+ "gridonopen" : 1,
+ "gridsize" : [ 5.0, 5.0 ],
+ "gridsnaponopen" : 1,
+ "objectsnaponopen" : 1,
+ "statusbarvisible" : 2,
+ "toolbarvisible" : 1,
+ "lefttoolbarpinned" : 0,
+ "toptoolbarpinned" : 0,
+ "righttoolbarpinned" : 0,
+ "bottomtoolbarpinned" : 0,
+ "toolbars_unpinned_last_save" : 0,
+ "tallnewobj" : 0,
+ "boxanimatetime" : 200,
+ "enablehscroll" : 1,
+ "enablevscroll" : 1,
+ "devicewidth" : 0.0,
+ "description" : "",
+ "digest" : "",
+ "tags" : "",
+ "style" : "",
+ "subpatcher_template" : "",
+ "boxes" : [ {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-2",
+ "linecount" : 25,
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 15.0, 20.0, 768.0, 400.0 ],
+ "style" : "",
+ "text" : "/*\n Written by Yotam Mann and Adrian freed,\n The Center for New Music and Audio Technologies,\n University of California, Berkeley. Copyright (c) 2012, The Regents of\n the University of California (Regents).\n \n Permission to use, copy, modify, distribute, and distribute modified versions\n of this software and its documentation without fee and without a signed\n licensing agreement, is hereby granted, provided that the above copyright\n notice, this paragraph and the following two paragraphs appear in all copies,\n modifications, and distributions.\n \n IN NO EVENT SHALL REGENTS BE LIABLE TO ANY PARTY FOR DIRECT, INDIRECT,\n SPECIAL, INCIDENTAL, OR CONSEQUENTIAL DAMAGES, INCLUDING LOST PROFITS, ARISING\n OUT OF THE USE OF THIS SOFTWARE AND ITS DOCUMENTATION, EVEN IF REGENTS HAS\n BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.\n \n REGENTS SPECIFICALLY DISCLAIMS ANY WARRANTIES, INCLUDING, BUT NOT LIMITED TO,\n THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR\n PURPOSE. THE SOFTWARE AND ACCOMPANYING DOCUMENTATION, IF ANY, PROVIDED\n HEREUNDER IS PROVIDED \"AS IS\". REGENTS HAS NO OBLIGATION TO PROVIDE\n MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.\n \n For bug reports and feature requests please email me at yotam@cnmat.berkeley.edu\n */"
+ }
+
+ }
+ ],
+ "lines" : [ ]
+ }
+,
+ "patching_rect" : [ 8.0, 570.0, 111.0, 24.0 ],
+ "saved_object_attributes" : {
+ "description" : "",
+ "digest" : "",
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "globalpatchername" : "",
+ "style" : "",
+ "tags" : ""
+ }
+,
+ "style" : "",
+ "text" : "p disclaimer"
+ }
+
+ }
+ ],
+ "lines" : [ {
+ "patchline" : {
+ "destination" : [ "obj-84", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-101", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-107", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-102", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-108", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-103", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-109", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-104", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-110", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-105", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-22", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-18", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-55", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-22", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-45", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-26", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-5", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-26", 1 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-8", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-26", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-9", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "midpoints" : [ 348.0, 229.0, 717.0, 229.0, 717.0, 131.0, 348.0, 131.0 ],
+ "source" : [ "obj-26", 1 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-26", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-28", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-81", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-45", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-26", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-55", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-61", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-60", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-28", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-61", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-56", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-64", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-26", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-7", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-79", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-78", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-7", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-79", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-101", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-102", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 1 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-103", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 2 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-104", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 3 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-105", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 4 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-64", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 5 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-26", 1 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-9", 0 ]
+ }
+
+ }
+ ],
+ "parameters" : {
+ "obj-105" : [ "a[19]", "a", 0 ],
+ "obj-104" : [ "a[20]", "a", 0 ],
+ "obj-103" : [ "a[21]", "a", 0 ],
+ "obj-64" : [ "a[37]", "a", 0 ],
+ "obj-102" : [ "a[22]", "a", 0 ],
+ "obj-101" : [ "a[23]", "a", 0 ]
+ }
+,
+ "dependency_cache" : [ {
+ "name" : "o.io.slipserial.maxpat",
+ "bootpath" : "~/Documents/Max/Packages/o.io/experimental/Protocols/serial",
+ "type" : "JSON",
+ "implicit" : 1
+ }
+, {
+ "name" : "o.righttoleft.maxpat",
+ "bootpath" : "~/Documents/Max/Packages/odot/patchers/ordering",
+ "type" : "JSON",
+ "implicit" : 1
+ }
+, {
+ "name" : "o.io.serial.display.maxpat",
+ "bootpath" : "~/Documents/Max/Packages/o.io/experimental/Protocols/serial",
+ "type" : "JSON",
+ "implicit" : 1
+ }
+, {
+ "name" : "o.pack.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.route.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.union.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.validate.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.print.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.slip.encode.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.slip.decode.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.if.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.message.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.display.mxo",
+ "type" : "iLaX"
+ }
+ ],
+ "embedsnapshot" : 0
+ }
+
+}
diff --git a/lib/OSC/Applications/MaxMSP/examples/SerialEcho.maxpat b/lib/OSC/Applications/MaxMSP/examples/SerialEcho.maxpat
new file mode 100644
index 0000000..7ef0315
--- /dev/null
+++ b/lib/OSC/Applications/MaxMSP/examples/SerialEcho.maxpat
@@ -0,0 +1,304 @@
+{
+ "patcher" : {
+ "fileversion" : 1,
+ "appversion" : {
+ "major" : 6,
+ "minor" : 1,
+ "revision" : 6,
+ "architecture" : "x86"
+ }
+,
+ "rect" : [ 608.0, 81.0, 1202.0, 749.0 ],
+ "bglocked" : 0,
+ "openinpresentation" : 0,
+ "default_fontsize" : 14.0,
+ "default_fontface" : 0,
+ "default_fontname" : "Andale Mono",
+ "gridonopen" : 0,
+ "gridsize" : [ 5.0, 5.0 ],
+ "gridsnaponopen" : 0,
+ "statusbarvisible" : 2,
+ "toolbarvisible" : 1,
+ "boxanimatetime" : 200,
+ "imprint" : 0,
+ "enablehscroll" : 1,
+ "enablevscroll" : 1,
+ "devicewidth" : 0.0,
+ "description" : "",
+ "digest" : "",
+ "tags" : "",
+ "boxes" : [ {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-1",
+ "maxclass" : "newobj",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "FullPacket" ],
+ "patching_rect" : [ 218.0, 295.0, 95.0, 22.0 ],
+ "text" : "o.downcast"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-18",
+ "linecount" : 10,
+ "maxclass" : "o.display",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 28.5, 425.0, 267.0, 155.0 ],
+ "text" : "/ping : 100,\n/thing : [2., 3.04, 1242., 23., \"thing\"],\n/stuff : [1, 2, 3, 4, 5],\n/fsakjfskfsdkasfk : [234, 242, 234, 234, 4],\n/decision : 1,\n/notdecision : 0,\n/micros : 616229100,\n/sequencenumber : 20557,\n/digital/5 : false,\n/lsb : false",
+ "textcolor" : [ 0.0, 0.0, 0.0, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-3",
+ "linecount" : 5,
+ "maxclass" : "o.display",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 404.5, 425.0, 158.0, 88.0 ],
+ "text" : "/port : \"usbmodem12341\",\n/rate/output : 32,\n/rate/input : 39,\n/mediansize/received : -1,\n/baud",
+ "textcolor" : [ 0.0, 0.0, 0.0, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "frgb" : 0.0,
+ "id" : "obj-19",
+ "linecount" : 2,
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 424.5, 269.5, 170.0, 33.0 ],
+ "text" : "Look for your device in the menu list of serial USB"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-20",
+ "maxclass" : "bpatcher",
+ "name" : "o.io.serial.display.maxpat",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "offset" : [ 3.0, 0.0 ],
+ "outlettype" : [ "FullPacket" ],
+ "patching_rect" : [ 404.5, 340.0, 164.0, 24.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-23",
+ "maxclass" : "newobj",
+ "numinlets" : 2,
+ "numoutlets" : 2,
+ "outlettype" : [ "FullPacket", "FullPacket" ],
+ "patching_rect" : [ 343.5, 379.0, 80.0, 20.0 ],
+ "text" : "o.io.slipserial"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-2",
+ "linecount" : 6,
+ "maxclass" : "o.compose",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 45.0, 90.166656, 964.0, 105.0 ],
+ "text" : "/ping : 100,\n/thing : [2., 3.04, 1242., 23., \"thing\"],\n/stuff : [1, 2, 3, 4, 5],\n/fsakjfskfsdkasfk : [234, 242, 234, 234, 4],\n/decision : true,\n/notdecision : false",
+ "textcolor" : [ 0.0, 0.0, 0.0, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "frgb" : 0.0,
+ "id" : "obj-4",
+ "linecount" : 3,
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 595.0, 415.0, 150.0, 54.0 ],
+ "text" : "stats on serial OSC communications"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-61",
+ "maxclass" : "newobj",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 45.0, 38.166656, 162.0, 22.0 ],
+ "text" : "metro 22 @active 1"
+ }
+
+ }
+ ],
+ "lines" : [ {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-23", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-1", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-1", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-2", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-23", 1 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-20", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-18", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-23", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-20", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "midpoints" : [ 414.0, 406.0, 583.0, 406.0, 583.0, 316.0, 414.0, 316.0 ],
+ "source" : [ "obj-23", 1 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-3", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "midpoints" : [ 414.0, 420.0, 414.0, 420.0 ],
+ "source" : [ "obj-23", 1 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-2", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-61", 0 ]
+ }
+
+ }
+ ],
+ "dependency_cache" : [ {
+ "name" : "o.io.slipserial.maxpat",
+ "bootpath" : "/Users/adrian2013/Documents/Max/Packages/CNMAT-MMJSS/patchers/esplora",
+ "patcherrelativepath" : "../../../../../Documents/Max/Packages/CNMAT-MMJSS/patchers/esplora",
+ "type" : "JSON",
+ "implicit" : 1
+ }
+, {
+ "name" : "o.righttoleft.maxpat",
+ "bootpath" : "/Users/adrian2013/Documents/Max/Packages/CNMAT-odot/patchers/ordering",
+ "patcherrelativepath" : "../../../../../Documents/Max/Packages/CNMAT-odot/patchers/ordering",
+ "type" : "JSON",
+ "implicit" : 1
+ }
+, {
+ "name" : "o.io.serial.display.maxpat",
+ "bootpath" : "/Users/adrian2013/Documents/Max/Packages/CNMAT-MMJSS/patchers/esplora",
+ "patcherrelativepath" : "../../../../../Documents/Max/Packages/CNMAT-MMJSS/patchers/esplora",
+ "type" : "JSON",
+ "implicit" : 1
+ }
+, {
+ "name" : "o.compose.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.pack.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.route.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.union.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.validate.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.print.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.slip.encode.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.slip.decode.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.if.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.display.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.downcast.mxo",
+ "type" : "iLaX"
+ }
+ ]
+ }
+
+}
diff --git a/lib/OSC/Applications/MaxMSP/examples/SerialOscuino.maxpat b/lib/OSC/Applications/MaxMSP/examples/SerialOscuino.maxpat
new file mode 100644
index 0000000..81a211f
--- /dev/null
+++ b/lib/OSC/Applications/MaxMSP/examples/SerialOscuino.maxpat
@@ -0,0 +1,6632 @@
+{
+ "patcher" : {
+ "fileversion" : 1,
+ "appversion" : {
+ "major" : 7,
+ "minor" : 2,
+ "revision" : 1,
+ "architecture" : "x86",
+ "modernui" : 1
+ }
+,
+ "rect" : [ 260.0, 117.0, 1158.0, 548.0 ],
+ "bglocked" : 0,
+ "openinpresentation" : 0,
+ "default_fontsize" : 14.0,
+ "default_fontface" : 0,
+ "default_fontname" : "Andale Mono",
+ "gridonopen" : 1,
+ "gridsize" : [ 5.0, 5.0 ],
+ "gridsnaponopen" : 1,
+ "objectsnaponopen" : 1,
+ "statusbarvisible" : 2,
+ "toolbarvisible" : 1,
+ "lefttoolbarpinned" : 0,
+ "toptoolbarpinned" : 0,
+ "righttoolbarpinned" : 0,
+ "bottomtoolbarpinned" : 0,
+ "toolbars_unpinned_last_save" : 0,
+ "tallnewobj" : 0,
+ "boxanimatetime" : 200,
+ "enablehscroll" : 1,
+ "enablevscroll" : 1,
+ "devicewidth" : 0.0,
+ "description" : "",
+ "digest" : "",
+ "tags" : "",
+ "style" : "",
+ "subpatcher_template" : "",
+ "boxes" : [ {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-5",
+ "maxclass" : "newobj",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "FullPacket" ],
+ "patching_rect" : [ 35.5, 219.0, 95.0, 24.0 ],
+ "style" : "",
+ "text" : "o.downcast"
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-3",
+ "linecount" : 8,
+ "maxclass" : "o.display",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 408.5, 390.0, 150.0, 146.0 ],
+ "text" : "/port : \"usbmodem1\",\n/rate/output : 3,\n/rate/input : 3,\n/mediansize/received : -1,\n/baud",
+ "textcolor" : [ 1.0, 1.0, 1.0, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-2",
+ "linecount" : 23,
+ "maxclass" : "o.display",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 35.5, 382.0, 150.0, 383.0 ],
+ "text" : "/a/0 : 275,\n/a/1 : 352,\n/a/2 : 356,\n/a/3 : 296,\n/a/4 : 326,\n/a/5 : 285,\n/a/6 : 333,\n/a/7 : 403,\n/a/8 : 305,\n/a/9 : 312,\n/a/10 : 266,\n/a/11 : 485,\n/a/12 : 588,\n/a/13 : 479,\n/a/14 : 348,\n/a/15 : 327,\n/a/16 : 222,\n/a/17 : 262,\n/a/18 : 273,\n/a/19 : 265,\n/a/20 : 365,\n/a/21 : 301,\n/a/22 : 295",
+ "textcolor" : [ 1.0, 1.0, 1.0, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "bgmode" : 0,
+ "border" : 0,
+ "clickthrough" : 0,
+ "enablehscroll" : 0,
+ "enablevscroll" : 0,
+ "id" : "obj-16",
+ "lockeddragscroll" : 0,
+ "maxclass" : "bpatcher",
+ "name" : "o.io.serial.display.maxpat",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "offset" : [ 0.0, 0.0 ],
+ "outlettype" : [ "FullPacket" ],
+ "patching_rect" : [ 427.0, 224.0, 341.0, 30.0 ],
+ "viewvisibility" : 1
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-9",
+ "linecount" : 3,
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 453.5, 157.0, 288.0, 54.0 ],
+ "style" : "",
+ "text" : "Increase baud rate from 9600\nfor better performance:\nchange the rate in the sketch too"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-1",
+ "maxclass" : "newobj",
+ "numinlets" : 0,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patcher" : {
+ "fileversion" : 1,
+ "appversion" : {
+ "major" : 7,
+ "minor" : 2,
+ "revision" : 1,
+ "architecture" : "x86",
+ "modernui" : 1
+ }
+,
+ "rect" : [ 618.0, 79.0, 788.0, 503.0 ],
+ "bglocked" : 0,
+ "openinpresentation" : 0,
+ "default_fontsize" : 12.0,
+ "default_fontface" : 0,
+ "default_fontname" : "Arial",
+ "gridonopen" : 1,
+ "gridsize" : [ 15.0, 15.0 ],
+ "gridsnaponopen" : 1,
+ "objectsnaponopen" : 1,
+ "statusbarvisible" : 2,
+ "toolbarvisible" : 1,
+ "lefttoolbarpinned" : 0,
+ "toptoolbarpinned" : 0,
+ "righttoolbarpinned" : 0,
+ "bottomtoolbarpinned" : 0,
+ "toolbars_unpinned_last_save" : 0,
+ "tallnewobj" : 0,
+ "boxanimatetime" : 200,
+ "enablehscroll" : 1,
+ "enablevscroll" : 1,
+ "devicewidth" : 0.0,
+ "description" : "",
+ "digest" : "",
+ "tags" : "",
+ "style" : "",
+ "subpatcher_template" : "",
+ "visible" : 1,
+ "boxes" : [ {
+ "box" : {
+ "id" : "obj-3",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 595.25, 423.0, 20.0, 20.0 ],
+ "presentation_rect" : [ 595.25, 422.0, 0.0, 0.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-4",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 558.833313, 417.0, 20.0, 20.0 ],
+ "presentation_rect" : [ 558.833313, 416.0, 0.0, 0.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-5",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 522.416626, 417.0, 20.0, 20.0 ],
+ "presentation_rect" : [ 522.416626, 416.0, 0.0, 0.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-9",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 477.333344, 424.0, 20.0, 20.0 ],
+ "presentation_rect" : [ 477.333344, 423.0, 0.0, 0.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-10",
+ "ignoreclick" : 1,
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 595.25, 313.0, 34.0, 95.0 ],
+ "presentation_rect" : [ 595.25, 312.0, 0.0, 0.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[75]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 2048.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[6]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-12",
+ "ignoreclick" : 1,
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 558.833313, 313.0, 34.0, 95.0 ],
+ "presentation_rect" : [ 558.833313, 312.0, 0.0, 0.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[76]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 2048.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[7]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-15",
+ "ignoreclick" : 1,
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 522.416626, 313.0, 34.0, 95.0 ],
+ "presentation_rect" : [ 522.416626, 312.0, 0.0, 0.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[77]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 2048.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[8]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-22",
+ "ignoreclick" : 1,
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 486.0, 313.0, 34.0, 95.0 ],
+ "presentation_rect" : [ 486.0, 312.0, 0.0, 0.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[78]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 2048.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[9]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-8",
+ "linecount" : 12,
+ "maxclass" : "o.display",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 652.0, 213.0, 150.0, 181.0 ],
+ "text" : "/22 : 674,\n/23 : 722,\n/19 : 560,\n/18 : 553,\n/17 : 754,\n/16 : 590,\n/15 : 627,\n/0 : 639,\n/1 : 640,\n/25 : 0,\n/32 : 0,\n/33 : 0",
+ "textcolor" : [ 1.0, 1.0, 1.0, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-7",
+ "maxclass" : "o.compose",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 329.0, 104.0, 150.0, 24.0 ],
+ "saved_bundle_data" : [ 35, 98, 117, 110, 100, 108, 101, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 12, 47, 99, 47, 42, 0, 0, 0, 0, 44, 0, 0, 0 ],
+ "saved_bundle_length" : 32,
+ "text" : "/c/*",
+ "textcolor" : [ 0.188, 0.188, 0.188, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-18",
+ "linecount" : 3,
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 33.0, 33.0, 90.0, 47.0 ],
+ "style" : "",
+ "text" : "Capacitance from touch pins\n"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-13",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 329.0, 26.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-11",
+ "maxclass" : "newobj",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 329.0, 68.0, 65.0, 22.0 ],
+ "style" : "",
+ "text" : "qmetro 30"
+ }
+
+ }
+, {
+ "box" : {
+ "comment" : "",
+ "id" : "obj-6",
+ "maxclass" : "outlet",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 329.0, 148.0, 25.0, 25.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-45",
+ "maxclass" : "newobj",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "FullPacket" ],
+ "patching_rect" : [ 29.0, 148.0, 95.0, 24.0 ],
+ "style" : "",
+ "text" : "o.route /c"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-60",
+ "maxclass" : "newobj",
+ "numinlets" : 0,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 29.0, 99.0, 170.0, 24.0 ],
+ "style" : "",
+ "text" : "r from_oscuino"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-1",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 438.25, 423.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-2",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 401.833313, 417.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-14",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 365.416656, 417.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-16",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 320.333344, 424.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-17",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 283.916656, 423.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-19",
+ "ignoreclick" : 1,
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 438.25, 313.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[50]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 2048.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[12]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-20",
+ "ignoreclick" : 1,
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 401.833313, 313.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[51]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 2048.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[13]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-21",
+ "ignoreclick" : 1,
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 365.416656, 313.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[52]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 2048.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[14]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-23",
+ "ignoreclick" : 1,
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 329.0, 313.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[53]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 2048.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[15]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-24",
+ "ignoreclick" : 1,
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 283.916656, 320.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[54]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 2048.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[16]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-25",
+ "ignoreclick" : 1,
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 247.5, 320.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[55]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 2048.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[17]"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-26",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 247.5, 423.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-111",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 211.083328, 423.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-110",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 174.666672, 423.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-109",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 138.25, 423.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-108",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 101.833336, 423.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-107",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 65.416664, 423.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-106",
+ "ignoreclick" : 1,
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 211.083328, 319.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[56]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 2048.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[5]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-105",
+ "ignoreclick" : 1,
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 174.666672, 319.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[57]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 2048.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[4]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-104",
+ "ignoreclick" : 1,
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 138.25, 319.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[58]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 2048.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[3]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-103",
+ "ignoreclick" : 1,
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 101.833336, 319.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[59]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 2048.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[2]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-102",
+ "ignoreclick" : 1,
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 65.416664, 319.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[60]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 2048.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[1]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-101",
+ "ignoreclick" : 1,
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 29.0, 319.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[61]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 2048.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-84",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 29.0, 423.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-81",
+ "maxclass" : "newobj",
+ "numinlets" : 1,
+ "numoutlets" : 17,
+ "outlettype" : [ "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "FullPacket" ],
+ "patching_rect" : [ 29.0, 220.0, 573.0, 24.0 ],
+ "style" : "",
+ "text" : "o.route /0 /1 /3 /4 /16 /17 /18 /19 /22 /23 /25 /32 /33 /15 /29 /30"
+ }
+
+ }
+ ],
+ "lines" : [ {
+ "patchline" : {
+ "destination" : [ "obj-3", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-10", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-84", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-101", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-107", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-102", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-108", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-103", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-109", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-104", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-110", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-105", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-111", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-106", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-7", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-11", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-4", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-12", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-11", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-13", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-5", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-15", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-1", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-19", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-2", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-20", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-14", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-21", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-9", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-22", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-16", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-23", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-17", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-24", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-26", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-25", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-8", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-45", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-81", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-45", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-45", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-60", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-6", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-7", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-10", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 15 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-101", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-102", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 1 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-103", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 2 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-104", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 3 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-105", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 4 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-106", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 5 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-12", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 14 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-15", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 13 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-19", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 11 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-20", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 10 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-21", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 9 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-22", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 12 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-23", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 8 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-24", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 7 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-25", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 6 ]
+ }
+
+ }
+ ]
+ }
+,
+ "patching_rect" : [ 408.5, 110.0, 145.0, 24.0 ],
+ "saved_object_attributes" : {
+ "description" : "",
+ "digest" : "",
+ "globalpatchername" : "",
+ "style" : "",
+ "tags" : ""
+ }
+,
+ "style" : "",
+ "text" : "p teensy 3 touch"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-4",
+ "linecount" : 3,
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 427.0, 323.0, 150.0, 54.0 ],
+ "style" : "",
+ "text" : "stats on serial OSC communications"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-60",
+ "maxclass" : "newobj",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 247.5, 355.0, 128.0, 24.0 ],
+ "style" : "",
+ "text" : "s from_oscuino"
+ }
+
+ }
+, {
+ "box" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-58",
+ "maxclass" : "newobj",
+ "numinlets" : 0,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patcher" : {
+ "fileversion" : 1,
+ "appversion" : {
+ "major" : 7,
+ "minor" : 2,
+ "revision" : 1,
+ "architecture" : "x86",
+ "modernui" : 1
+ }
+,
+ "rect" : [ 572.0, 102.0, 834.0, 483.0 ],
+ "bglocked" : 0,
+ "openinpresentation" : 0,
+ "default_fontsize" : 12.0,
+ "default_fontface" : 0,
+ "default_fontname" : "Arial",
+ "gridonopen" : 1,
+ "gridsize" : [ 15.0, 15.0 ],
+ "gridsnaponopen" : 1,
+ "objectsnaponopen" : 1,
+ "statusbarvisible" : 2,
+ "toolbarvisible" : 1,
+ "lefttoolbarpinned" : 0,
+ "toptoolbarpinned" : 0,
+ "righttoolbarpinned" : 0,
+ "bottomtoolbarpinned" : 0,
+ "toolbars_unpinned_last_save" : 0,
+ "tallnewobj" : 0,
+ "boxanimatetime" : 200,
+ "enablehscroll" : 1,
+ "enablevscroll" : 1,
+ "devicewidth" : 0.0,
+ "description" : "",
+ "digest" : "",
+ "tags" : "",
+ "style" : "",
+ "subpatcher_template" : "",
+ "visible" : 1,
+ "boxes" : [ {
+ "box" : {
+ "fontface" : 0,
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-32",
+ "maxclass" : "o.compose",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 119.5, 296.0, 41.0, 24.0 ],
+ "saved_bundle_data" : [ 35, 98, 117, 110, 100, 108, 101, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 12, 47, 115, 47, 115, 0, 0, 0, 0, 44, 0, 0, 0 ],
+ "saved_bundle_length" : 32,
+ "text" : "/s/s",
+ "textcolor" : [ 0.188, 0.188, 0.188, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-30",
+ "maxclass" : "o.compose",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 104.0, 234.0, 39.0, 24.0 ],
+ "saved_bundle_data" : [ 35, 98, 117, 110, 100, 108, 101, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 12, 47, 115, 47, 116, 0, 0, 0, 0, 44, 0, 0, 0 ],
+ "saved_bundle_length" : 32,
+ "text" : "/s/t",
+ "textcolor" : [ 0.188, 0.188, 0.188, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-28",
+ "maxclass" : "o.compose",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 76.0, 179.0, 45.0, 24.0 ],
+ "saved_bundle_data" : [ 35, 98, 117, 110, 100, 108, 101, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 12, 47, 115, 47, 109, 0, 0, 0, 0, 44, 0, 0, 0 ],
+ "saved_bundle_length" : 32,
+ "text" : "/s/m",
+ "textcolor" : [ 0.188, 0.188, 0.188, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-26",
+ "maxclass" : "o.compose",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 40.0, 122.0, 42.0, 24.0 ],
+ "saved_bundle_data" : [ 35, 98, 117, 110, 100, 108, 101, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 12, 47, 115, 47, 100, 0, 0, 0, 0, 44, 0, 0, 0 ],
+ "saved_bundle_length" : 32,
+ "text" : "/s/d",
+ "textcolor" : [ 0.188, 0.188, 0.188, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-20",
+ "maxclass" : "o.compose",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 14.0, 68.0, 42.0, 24.0 ],
+ "saved_bundle_data" : [ 35, 98, 117, 110, 100, 108, 101, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 12, 47, 115, 47, 97, 0, 0, 0, 0, 44, 0, 0, 0 ],
+ "saved_bundle_length" : 32,
+ "text" : "/s/a",
+ "textcolor" : [ 0.188, 0.188, 0.188, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-16",
+ "maxclass" : "o.display",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 415.0, 122.0, 150.0, 34.0 ],
+ "text" : "/s : 1.83224",
+ "textcolor" : [ 1.0, 1.0, 1.0, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-15",
+ "maxclass" : "newobj",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "FullPacket" ],
+ "patching_rect" : [ 166.5, 370.0, 65.0, 22.0 ],
+ "style" : "",
+ "text" : "o.pack /s/l"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-9",
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 119.5, 266.0, 179.0, 22.0 ],
+ "style" : "",
+ "text" : "Power Supply Voltage"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-13",
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 104.0, 212.0, 103.0, 22.0 ],
+ "style" : "",
+ "text" : "Temperature"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-45",
+ "maxclass" : "newobj",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "FullPacket" ],
+ "patching_rect" : [ 415.0, 95.0, 95.0, 24.0 ],
+ "style" : "",
+ "text" : "o.route /s"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-60",
+ "maxclass" : "newobj",
+ "numinlets" : 0,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 414.0, 64.0, 170.0, 24.0 ],
+ "style" : "",
+ "text" : "r from_oscuino"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-8",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 166.5, 329.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-5",
+ "linecount" : 2,
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 224.5, 320.0, 381.0, 38.0 ],
+ "style" : "",
+ "text" : "toggle the LED (don't do this on Teensy 3.0 with Wiznet Ethernet that uses pin 13)"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-1",
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 76.0, 152.0, 246.0, 22.0 ],
+ "style" : "",
+ "text" : "Arduino time in microseconds"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-3",
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 23.0, 46.0, 288.0, 22.0 ],
+ "style" : "",
+ "text" : "Returns the number of analog pins"
+ }
+
+ }
+, {
+ "box" : {
+ "comment" : "",
+ "id" : "obj-2",
+ "maxclass" : "outlet",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 14.0, 432.0, 25.0, 25.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-10",
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 40.0, 96.0, 296.0, 22.0 ],
+ "style" : "",
+ "text" : "Returns the number of digital pins"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-46",
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 19.0, 15.0, 792.0, 22.0 ],
+ "style" : "",
+ "text" : "QUERIES AND PARAMS"
+ }
+
+ }
+ ],
+ "lines" : [ {
+ "patchline" : {
+ "destination" : [ "obj-2", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-15", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-2", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-20", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-2", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-26", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-2", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-28", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-2", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-30", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-2", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-32", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-16", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-45", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-45", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-60", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-15", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-8", 0 ]
+ }
+
+ }
+ ]
+ }
+,
+ "patching_rect" : [ 222.0, 110.0, 179.0, 24.0 ],
+ "saved_object_attributes" : {
+ "description" : "",
+ "digest" : "",
+ "globalpatchername" : "",
+ "style" : "",
+ "tags" : ""
+ }
+,
+ "style" : "",
+ "text" : "p queries-and-params"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-52",
+ "maxclass" : "newobj",
+ "numinlets" : 0,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patcher" : {
+ "fileversion" : 1,
+ "appversion" : {
+ "major" : 7,
+ "minor" : 2,
+ "revision" : 1,
+ "architecture" : "x86",
+ "modernui" : 1
+ }
+,
+ "rect" : [ 56.0, 79.0, 1321.0, 589.0 ],
+ "bglocked" : 0,
+ "openinpresentation" : 0,
+ "default_fontsize" : 12.0,
+ "default_fontface" : 0,
+ "default_fontname" : "Arial",
+ "gridonopen" : 1,
+ "gridsize" : [ 15.0, 15.0 ],
+ "gridsnaponopen" : 1,
+ "objectsnaponopen" : 1,
+ "statusbarvisible" : 2,
+ "toolbarvisible" : 1,
+ "lefttoolbarpinned" : 0,
+ "toptoolbarpinned" : 0,
+ "righttoolbarpinned" : 0,
+ "bottomtoolbarpinned" : 0,
+ "toolbars_unpinned_last_save" : 0,
+ "tallnewobj" : 0,
+ "boxanimatetime" : 200,
+ "enablehscroll" : 1,
+ "enablevscroll" : 1,
+ "devicewidth" : 0.0,
+ "description" : "",
+ "digest" : "",
+ "tags" : "",
+ "style" : "",
+ "subpatcher_template" : "",
+ "boxes" : [ {
+ "box" : {
+ "id" : "obj-51",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 1290.5, 337.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-52",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 1274.088257, 501.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-53",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 1247.676514, 501.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-3",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 1209.5, 497.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-5",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 1183.088257, 497.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-7",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 1156.676514, 497.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-9",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 1130.264648, 497.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-12",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 1103.853027, 497.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-33",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 1077.441162, 497.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-34",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 1051.029419, 497.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-37",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 1024.617676, 497.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-38",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 998.205811, 497.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-39",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 971.794189, 497.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-41",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 945.382324, 497.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-42",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 918.970581, 497.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-43",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 892.558838, 497.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-44",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 866.147095, 497.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-47",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 839.735291, 497.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-48",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 813.323486, 497.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-49",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 786.911743, 497.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-50",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 760.5, 497.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontsize" : 12.0,
+ "id" : "obj-40",
+ "maxclass" : "o.compose",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 15.0, 383.0, 150.0, 24.0 ],
+ "saved_bundle_data" : [ 35, 98, 117, 110, 100, 108, 101, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 12, 47, 100, 47, 42, 0, 0, 0, 0, 44, 0, 0, 0 ],
+ "saved_bundle_length" : 32,
+ "text" : "/d/*",
+ "textcolor" : [ 0.188, 0.188, 0.188, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontsize" : 12.0,
+ "id" : "obj-15",
+ "maxclass" : "o.compose",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 326.5, 263.0, 150.0, 24.0 ],
+ "saved_bundle_data" : [ 35, 98, 117, 110, 100, 108, 101, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 20, 47, 100, 47, 49, 91, 51, 56, 57, 93, 0, 0, 0, 44, 105, 0, 0, 0, 0, 0, 1 ],
+ "saved_bundle_length" : 40,
+ "text" : "/d/1[389] : 1",
+ "textcolor" : [ 0.188, 0.188, 0.188, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontsize" : 12.0,
+ "id" : "obj-14",
+ "maxclass" : "o.compose",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 353.0, 306.0, 150.0, 24.0 ],
+ "saved_bundle_data" : [ 35, 98, 117, 110, 100, 108, 101, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 12, 47, 100, 47, 49, 48, 47, 117, 0, 44, 0, 0, 0 ],
+ "saved_bundle_length" : 32,
+ "text" : "/d/10/u",
+ "textcolor" : [ 0.188, 0.188, 0.188, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontsize" : 12.0,
+ "id" : "obj-11",
+ "maxclass" : "o.compose",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 80.0, 263.0, 150.0, 24.0 ],
+ "saved_bundle_data" : [ 35, 98, 117, 110, 100, 108, 101, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 20, 47, 100, 47, 49, 91, 48, 45, 57, 93, 0, 0, 0, 44, 105, 0, 0, 0, 0, 0, 1 ],
+ "saved_bundle_length" : 40,
+ "text" : "/d/1[0-9] : 1",
+ "textcolor" : [ 0.188, 0.188, 0.188, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-2",
+ "maxclass" : "newobj",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "FullPacket" ],
+ "patching_rect" : [ 197.0, 352.0, 76.0, 22.0 ],
+ "style" : "",
+ "text" : "o.pack /d/13"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-10",
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 82.5, 395.0, 83.0, 20.0 ],
+ "style" : "",
+ "text" : "report all pins"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-8",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 15.0, 320.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-4",
+ "maxclass" : "newobj",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 15.0, 351.0, 72.0, 22.0 ],
+ "style" : "",
+ "text" : "qmetro 100"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-35",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 730.5, 497.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-36",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 704.088257, 497.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-28",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 677.676453, 497.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-30",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 651.264709, 497.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-31",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 624.852966, 497.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-32",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 598.441162, 497.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-24",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 572.029419, 497.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-25",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 545.617676, 497.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-26",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 519.205872, 497.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-27",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 492.794128, 497.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-20",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 466.382324, 497.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-21",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 439.970581, 497.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-22",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 413.558838, 497.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-23",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 387.147064, 497.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-19",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 360.735291, 497.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-18",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 334.323517, 497.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-17",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 307.911774, 497.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-16",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 281.5, 497.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-81",
+ "linecount" : 2,
+ "maxclass" : "newobj",
+ "numinlets" : 1,
+ "numoutlets" : 39,
+ "outlettype" : [ "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "FullPacket" ],
+ "patching_rect" : [ 298.756958, 411.0, 968.0, 40.0 ],
+ "style" : "",
+ "text" : "o.route /0 /1 /2 /3 /4 /5 /6 /7 /8 /9 /10 /11 /12 /13 /14 /15 /16 /17 /18 /19 /20 /21 /22 /23 /24 /25 /26 /27 /28 /29 /30 /31 /32 /33 /34 /35 /36 /37"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-45",
+ "maxclass" : "newobj",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "FullPacket" ],
+ "patching_rect" : [ 354.0, 383.0, 95.0, 24.0 ],
+ "style" : "",
+ "text" : "o.route /d"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-60",
+ "maxclass" : "newobj",
+ "numinlets" : 0,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 354.0, 352.0, 170.0, 24.0 ],
+ "style" : "",
+ "text" : "r from_oscuino"
+ }
+
+ }
+, {
+ "box" : {
+ "comment" : "",
+ "id" : "obj-1",
+ "maxclass" : "outlet",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 241.0, 469.0, 25.0, 25.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-29",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 197.0, 313.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-6",
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 281.5, 229.0, 313.0, 22.0 ],
+ "style" : "",
+ "text" : "Set digital pins 3, 8, and 9 to HIGH"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-13",
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 15.0, 229.0, 254.0, 22.0 ],
+ "style" : "",
+ "text" : "Set digital pin 0 to HIGH/LOW"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-46",
+ "linecount" : 12,
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 15.0, 11.0, 801.0, 195.0 ],
+ "style" : "",
+ "text" : "DIGITAL\nThe basic digital Arduino functions with the option of using the internal pullup available on most Arduinos. \n\n/d/(pin #)\n\t(no data) = digitalRead with pullup off\n\t/u = digitalRead with pullup on\n\t(value 0/1) = digitalWrite with that value\n\nexample:\n\"/d/1\" performs digitalRead with pullup off on pin 0. \n\"/d/[0-4] 0\" performs digitalWrite LOW on pins 0 through 4."
+ }
+
+ }
+ ],
+ "lines" : [ {
+ "patchline" : {
+ "destination" : [ "obj-1", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-11", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-1", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-14", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-1", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-15", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-1", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-2", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-2", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-29", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-40", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-4", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-1", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-40", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-81", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-45", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-45", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-60", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-4", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-8", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-12", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 31 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-16", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-17", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 1 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-18", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 2 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-19", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 3 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-20", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 7 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-21", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 6 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-22", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 5 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-23", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 4 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-24", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 11 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-25", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 10 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-26", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 9 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-27", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 8 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-28", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 15 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-3", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 35 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-30", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 14 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-31", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 13 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-32", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 12 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-33", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 30 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-34", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 29 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-35", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 17 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-36", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 16 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-37", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 28 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-38", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 27 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-39", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 26 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-41", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 25 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-42", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 24 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-43", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 23 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-44", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 22 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-47", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 21 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-48", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 20 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-49", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 19 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-5", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 34 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-50", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 18 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-52", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 37 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-53", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 36 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-7", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 33 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-9", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 32 ]
+ }
+
+ }
+ ]
+ }
+,
+ "patching_rect" : [ 35.5, 110.0, 86.0, 24.0 ],
+ "saved_object_attributes" : {
+ "description" : "",
+ "digest" : "",
+ "globalpatchername" : "",
+ "style" : "",
+ "tags" : ""
+ }
+,
+ "style" : "",
+ "text" : "p digital"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-47",
+ "maxclass" : "newobj",
+ "numinlets" : 0,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patcher" : {
+ "fileversion" : 1,
+ "appversion" : {
+ "major" : 7,
+ "minor" : 2,
+ "revision" : 1,
+ "architecture" : "x86",
+ "modernui" : 1
+ }
+,
+ "rect" : [ 34.0, 79.0, 1372.0, 769.0 ],
+ "bglocked" : 0,
+ "openinpresentation" : 0,
+ "default_fontsize" : 12.0,
+ "default_fontface" : 0,
+ "default_fontname" : "Arial",
+ "gridonopen" : 1,
+ "gridsize" : [ 15.0, 15.0 ],
+ "gridsnaponopen" : 1,
+ "objectsnaponopen" : 1,
+ "statusbarvisible" : 2,
+ "toolbarvisible" : 1,
+ "lefttoolbarpinned" : 0,
+ "toptoolbarpinned" : 0,
+ "righttoolbarpinned" : 0,
+ "bottomtoolbarpinned" : 0,
+ "toolbars_unpinned_last_save" : 0,
+ "tallnewobj" : 0,
+ "boxanimatetime" : 200,
+ "enablehscroll" : 1,
+ "enablevscroll" : 1,
+ "devicewidth" : 0.0,
+ "description" : "",
+ "digest" : "",
+ "tags" : "",
+ "style" : "",
+ "subpatcher_template" : "",
+ "boxes" : [ {
+ "box" : {
+ "id" : "obj-125",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 682.533325, 563.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-126",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 682.533325, 446.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[46]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[33]"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-127",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 646.333313, 562.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-128",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 646.266663, 445.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[47]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[34]"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-129",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 609.133301, 563.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-130",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 610.0, 446.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[74]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[35]"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-55",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 1009.0, 796.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-87",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 1009.0, 692.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[48]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[36]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-88",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 976.0, 692.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[62]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[37]"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-89",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 976.0, 796.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-90",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 940.0, 795.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-91",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 907.0, 795.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-92",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 874.0, 795.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-93",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 841.0, 795.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-94",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 808.0, 795.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-95",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 940.0, 689.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[49]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[38]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-96",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 907.0, 691.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[63]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[39]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-97",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 874.0, 691.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[64]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[40]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-98",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 841.0, 691.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[65]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[41]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-99",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 808.0, 691.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[66]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[42]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-100",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 775.0, 691.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[67]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[43]"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-112",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 775.0, 795.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-113",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 745.0, 794.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-114",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 709.0, 794.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-115",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 676.0, 794.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-116",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 643.0, 794.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-117",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 610.0, 794.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-118",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 742.0, 690.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[68]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[44]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-119",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 709.0, 690.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[69]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[45]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-120",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 676.0, 690.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[70]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[46]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-121",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 643.0, 690.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[71]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[47]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-122",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 610.0, 690.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[72]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[48]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-123",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 577.0, 690.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[73]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[49]"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-124",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 577.0, 794.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-82",
+ "maxclass" : "o.compose",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 769.5, 275.0, 150.0, 24.0 ],
+ "saved_bundle_data" : [ 35, 98, 117, 110, 100, 108, 101, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 20, 47, 97, 47, 92, 123, 50, 92, 44, 51, 92, 125, 47, 117, 0, 0, 0, 44, 0, 0, 0 ],
+ "saved_bundle_length" : 40,
+ "text" : "/a/\\{2\\,3\\}/u ",
+ "textcolor" : [ 0.188, 0.188, 0.188, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-80",
+ "maxclass" : "o.compose",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 450.0, 273.0, 150.0, 24.0 ],
+ "saved_bundle_data" : [ 35, 98, 117, 110, 100, 108, 101, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 16, 47, 97, 47, 91, 48, 45, 51, 93, 47, 117, 0, 0, 44, 0, 0, 0 ],
+ "saved_bundle_length" : 36,
+ "text" : "/a/[0-3]/u",
+ "textcolor" : [ 0.188, 0.188, 0.188, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-62",
+ "maxclass" : "o.compose",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 238.5, 273.0, 150.0, 24.0 ],
+ "saved_bundle_data" : [ 35, 98, 117, 110, 100, 108, 101, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 12, 47, 97, 47, 42, 0, 0, 0, 0, 44, 0, 0, 0 ],
+ "saved_bundle_length" : 32,
+ "text" : "/a/*",
+ "textcolor" : [ 0.188, 0.188, 0.188, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-61",
+ "maxclass" : "o.compose",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 21.5, 275.0, 150.0, 24.0 ],
+ "saved_bundle_data" : [ 35, 98, 117, 110, 100, 108, 101, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 16, 47, 97, 47, 49, 0, 0, 0, 0, 44, 105, 0, 0, 0, 0, 0, 1 ],
+ "saved_bundle_length" : 36,
+ "text" : "/a/1 : 1",
+ "textcolor" : [ 0.188, 0.188, 0.188, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-63",
+ "linecount" : 2,
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 789.5, 212.0, 222.0, 38.0 ],
+ "style" : "",
+ "text" : "read analog pins 2 and 3 with pullup turned on"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-78",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 769.5, 212.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-79",
+ "maxclass" : "newobj",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 769.5, 242.0, 86.0, 24.0 ],
+ "style" : "",
+ "text" : "qmetro 20"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-76",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 570.0, 563.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-77",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 570.0, 446.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[45]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[32]"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-74",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 533.799988, 562.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-75",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 533.733337, 445.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[44]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[31]"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-72",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 496.600006, 563.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-73",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 497.466675, 446.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[43]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[30]"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-70",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 461.399994, 561.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-71",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 461.200012, 444.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[42]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[24]"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-56",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 537.0, 785.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-57",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 503.0, 785.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-58",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 471.0, 786.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-59",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 444.0, 785.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-64",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 524.354858, 682.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[37]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[25]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-65",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 499.0, 682.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[38]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[26]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-66",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 471.0, 680.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[39]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[27]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-67",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 444.0, 681.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[40]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[28]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-68",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 411.0, 681.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[41]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[29]"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-69",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 411.0, 785.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-27",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 425.200012, 559.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-29",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 389.0, 559.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-30",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 351.799988, 559.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-31",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 315.600006, 559.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-47",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 280.399994, 559.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-48",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 424.933319, 442.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[30]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[18]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-49",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 388.666656, 442.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[31]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[19]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-50",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 352.399994, 442.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[32]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[20]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-51",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 316.133331, 442.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[33]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[21]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-52",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 279.866669, 442.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[34]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[22]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-53",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 243.600006, 442.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[35]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[23]"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-54",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 244.199997, 559.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-1",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 375.0, 784.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-2",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 342.0, 784.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-14",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 309.0, 784.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-16",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 276.0, 784.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-17",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 243.0, 784.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-19",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 375.0, 678.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[24]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[12]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-20",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 342.0, 680.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[25]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[13]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-21",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 309.0, 680.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[26]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[14]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-23",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 276.0, 680.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[27]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[15]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-24",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 243.0, 680.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[28]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[16]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-25",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 210.0, 680.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[29]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[17]"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-26",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 210.0, 784.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-13",
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 545.0, 338.0, 447.0, 22.0 ],
+ "style" : "",
+ "text" : "analog readings come out of the SLIP_oscuino patcher"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-32",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 207.0, 558.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-33",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 170.800003, 558.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-34",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 134.600006, 558.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-35",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 99.400002, 555.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-36",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 62.200001, 556.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-37",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 207.333328, 441.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[12]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[6]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-38",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 171.066666, 441.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[13]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[7]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-39",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 134.800003, 441.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[14]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[8]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-40",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 98.533333, 441.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[15]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[9]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-41",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 62.266666, 441.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[16]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[10]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-42",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 26.0, 441.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[17]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[11]"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-43",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 26.0, 556.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-44",
+ "maxclass" : "newobj",
+ "numinlets" : 1,
+ "numoutlets" : 20,
+ "outlettype" : [ "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "FullPacket" ],
+ "patching_rect" : [ 26.75, 384.0, 943.0, 24.0 ],
+ "style" : "",
+ "text" : "o.route /0/u /1/u /2/u /3/u /4/u /5/u /6/u /7/u /8/u /9/u /10/u /11/u /12/u /13/u /14/u /15/u /16/u /17/u /18/u"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-111",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 180.0, 783.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-110",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 144.0, 783.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-109",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 111.0, 783.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-108",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 78.0, 783.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-107",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 45.0, 783.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-106",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 177.0, 679.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[18]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[5]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-105",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 144.0, 679.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[19]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[4]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-104",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 111.0, 679.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[20]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[3]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-103",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 78.0, 679.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[21]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[2]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-102",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 45.0, 679.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[22]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[1]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-101",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 12.0, 679.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[23]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-84",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 12.0, 783.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-81",
+ "linecount" : 2,
+ "maxclass" : "newobj",
+ "numinlets" : 1,
+ "numoutlets" : 32,
+ "outlettype" : [ "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "FullPacket" ],
+ "patching_rect" : [ 31.774193, 618.0, 1002.0, 40.0 ],
+ "style" : "",
+ "text" : "o.route /0 /1 /2 /3 /4 /5 /6 /7 /8 /9 /10 /11 /12 /13 /14 /15 /16 /17 /18 /19 /20 /21 /22 /23 /24 /25 /26 /27 /28 /29 /30"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-45",
+ "maxclass" : "newobj",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "FullPacket" ],
+ "patching_rect" : [ 26.75, 349.0, 95.0, 24.0 ],
+ "style" : "",
+ "text" : "o.route /a"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-60",
+ "maxclass" : "newobj",
+ "numinlets" : 0,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 26.75, 317.0, 170.0, 24.0 ],
+ "style" : "",
+ "text" : "r from_oscuino"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-9",
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 42.5, 210.0, 187.0, 22.0 ],
+ "style" : "",
+ "text" : "analog write on 1"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-10",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 21.5, 210.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-11",
+ "maxclass" : "newobj",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 21.5, 240.0, 86.0, 24.0 ],
+ "style" : "",
+ "text" : "qmetro 20"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-8",
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 301.5, 327.0, 259.0, 22.0 ],
+ "style" : "",
+ "text" : "to SLIP_oscuino"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-4",
+ "linecount" : 2,
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 480.5, 210.0, 187.0, 38.0 ],
+ "style" : "",
+ "text" : "read analog pins 0-3 with pullup turned on"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-5",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 460.5, 210.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-6",
+ "maxclass" : "newobj",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 460.5, 240.0, 86.0, 24.0 ],
+ "style" : "",
+ "text" : "qmetro 20"
+ }
+
+ }
+, {
+ "box" : {
+ "comment" : "",
+ "id" : "obj-3",
+ "maxclass" : "outlet",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 257.0, 319.0, 25.0, 25.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-15",
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 258.5, 210.0, 187.0, 22.0 ],
+ "style" : "",
+ "text" : "read all analog pins"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-18",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 238.5, 210.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-22",
+ "maxclass" : "newobj",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 238.5, 240.0, 86.0, 24.0 ],
+ "style" : "",
+ "text" : "qmetro 20"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-46",
+ "linecount" : 12,
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 24.0, 6.0, 792.0, 195.0 ],
+ "style" : "",
+ "text" : "ANALOG\nThese are the basic analog Arduino functions with the option of using the internal pullup available on most Arduinos. All analog pins can be used as digital outputs also. \n\n/a/(pin #)\n\t(no data) = analogRead with pullup off\n\t/u = analogRead with pullup on\n\t(value 0/1) = digitalWrite with that value\n\nexample:\n\"/a/0/u\" performs analogRead with pullup on on pin 0. \n\"/a/8 1\" performs digitalWrite on pin 8 with HIGH."
+ }
+
+ }
+ ],
+ "lines" : [ {
+ "patchline" : {
+ "destination" : [ "obj-11", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-10", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-112", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-100", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-84", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-101", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-107", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-102", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-108", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-103", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-109", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-104", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-110", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-105", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-111", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-106", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-61", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-11", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-113", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-118", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-114", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-119", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-115", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-120", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-116", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-121", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-117", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-122", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-124", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-123", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-125", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-126", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-127", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-128", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-129", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-130", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-22", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-18", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-1", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-19", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-2", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-20", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-14", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-21", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-62", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-22", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-16", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-23", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-17", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-24", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-26", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-25", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-32", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-37", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-33", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-38", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-34", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-39", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-35", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-40", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-36", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-41", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-43", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-42", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-126", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-44", 18 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-128", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-44", 17 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-130", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-44", 16 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-37", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-44", 5 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-38", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-44", 4 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-39", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-44", 3 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-40", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-44", 2 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-41", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-44", 1 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-42", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-44", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-48", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-44", 11 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-49", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-44", 10 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-50", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-44", 9 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-51", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-44", 8 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-52", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-44", 7 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-53", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-44", 6 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-71", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-44", 12 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-73", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-44", 13 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-75", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-44", 14 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-77", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-44", 15 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-81", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-44", 19 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-44", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-45", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-27", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-48", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-29", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-49", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-6", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-5", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-30", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-50", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-31", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-51", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-47", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-52", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-54", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-53", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-80", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-6", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-45", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-60", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-3", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-61", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-3", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-62", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-56", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-64", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-57", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-65", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-58", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-66", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-59", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-67", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-69", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-68", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-70", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-71", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-72", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-73", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-74", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-75", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-76", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-77", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-79", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-78", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-82", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-79", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-3", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-80", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-100", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 23 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-101", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-102", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 1 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-103", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 2 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-104", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 3 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-105", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 4 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-106", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 5 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-118", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 22 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-119", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 21 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-120", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 20 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-121", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 19 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-122", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 18 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-123", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 17 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-19", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 11 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-20", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 10 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-21", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 9 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-23", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 8 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-24", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 7 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-25", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 6 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-64", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 16 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-65", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 15 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-66", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 14 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-67", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 13 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-68", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 12 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-87", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 30 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-88", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 29 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-95", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 28 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-96", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 27 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-97", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 26 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-98", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 25 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-99", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 24 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-3", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-82", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-55", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-87", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-89", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-88", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-90", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-95", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-91", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-96", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-92", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-97", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-93", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-98", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-94", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-99", 0 ]
+ }
+
+ }
+ ]
+ }
+,
+ "patching_rect" : [ 136.0, 110.0, 78.0, 24.0 ],
+ "saved_object_attributes" : {
+ "description" : "",
+ "digest" : "",
+ "globalpatchername" : "",
+ "style" : "",
+ "tags" : ""
+ }
+,
+ "style" : "",
+ "text" : "p analog"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-26",
+ "maxclass" : "newobj",
+ "numinlets" : 2,
+ "numoutlets" : 2,
+ "outlettype" : [ "FullPacket", "FullPacket" ],
+ "patching_rect" : [ 247.5, 284.0, 137.0, 24.0 ],
+ "style" : "",
+ "text" : "o.io.slipserial"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-27",
+ "linecount" : 3,
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 15.0, 35.0, 860.0, 54.0 ],
+ "style" : "",
+ "text" : "Serial Oscuino sends and receives OSC packets over SLIPSerial \nto and from an Arduino or Teensy running the oscuinoSerial Sketch \n\n"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-91",
+ "maxclass" : "newobj",
+ "numinlets" : 0,
+ "numoutlets" : 0,
+ "patcher" : {
+ "fileversion" : 1,
+ "appversion" : {
+ "major" : 7,
+ "minor" : 2,
+ "revision" : 1,
+ "architecture" : "x86",
+ "modernui" : 1
+ }
+,
+ "rect" : [ 25.0, 69.0, 738.0, 421.0 ],
+ "bglocked" : 0,
+ "openinpresentation" : 0,
+ "default_fontsize" : 14.0,
+ "default_fontface" : 0,
+ "default_fontname" : "Andale Mono",
+ "gridonopen" : 1,
+ "gridsize" : [ 5.0, 5.0 ],
+ "gridsnaponopen" : 1,
+ "objectsnaponopen" : 1,
+ "statusbarvisible" : 2,
+ "toolbarvisible" : 1,
+ "lefttoolbarpinned" : 0,
+ "toptoolbarpinned" : 0,
+ "righttoolbarpinned" : 0,
+ "bottomtoolbarpinned" : 0,
+ "toolbars_unpinned_last_save" : 0,
+ "tallnewobj" : 0,
+ "boxanimatetime" : 200,
+ "enablehscroll" : 1,
+ "enablevscroll" : 1,
+ "devicewidth" : 0.0,
+ "description" : "",
+ "digest" : "",
+ "tags" : "",
+ "style" : "",
+ "subpatcher_template" : "",
+ "boxes" : [ {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-2",
+ "linecount" : 24,
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 15.0, 20.0, 697.0, 386.0 ],
+ "style" : "",
+ "text" : "/*\n Written by Yotam Mann, The Center for New Music and Audio Technologies,\n University of California, Berkeley. Copyright (c) 2012, The Regents of\n the University of California (Regents).\n \n Permission to use, copy, modify, distribute, and distribute modified versions\n of this software and its documentation without fee and without a signed\n licensing agreement, is hereby granted, provided that the above copyright\n notice, this paragraph and the following two paragraphs appear in all copies,\n modifications, and distributions.\n \n IN NO EVENT SHALL REGENTS BE LIABLE TO ANY PARTY FOR DIRECT, INDIRECT,\n SPECIAL, INCIDENTAL, OR CONSEQUENTIAL DAMAGES, INCLUDING LOST PROFITS, ARISING\n OUT OF THE USE OF THIS SOFTWARE AND ITS DOCUMENTATION, EVEN IF REGENTS HAS\n BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.\n \n REGENTS SPECIFICALLY DISCLAIMS ANY WARRANTIES, INCLUDING, BUT NOT LIMITED TO,\n THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR\n PURPOSE. THE SOFTWARE AND ACCOMPANYING DOCUMENTATION, IF ANY, PROVIDED\n HEREUNDER IS PROVIDED \"AS IS\". REGENTS HAS NO OBLIGATION TO PROVIDE\n MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.\n \n For bug reports and feature requests please email me at yotam@cnmat.berkeley.edu\n */"
+ }
+
+ }
+ ],
+ "lines" : [ ]
+ }
+,
+ "patching_rect" : [ 749.5, 10.0, 111.0, 24.0 ],
+ "saved_object_attributes" : {
+ "description" : "",
+ "digest" : "",
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "globalpatchername" : "",
+ "style" : "",
+ "tags" : ""
+ }
+,
+ "style" : "",
+ "text" : "p disclaimer"
+ }
+
+ }
+ ],
+ "lines" : [ {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-5", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-1", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-26", 1 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-16", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-16", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-26", 1 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-2", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-26", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-3", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-26", 1 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-60", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-26", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-5", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-47", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-26", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-5", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-5", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-52", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-5", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-58", 0 ]
+ }
+
+ }
+ ],
+ "parameters" : {
+ "obj-47::obj-50" : [ "a[32]", "a", 0 ],
+ "obj-1::obj-23" : [ "a[53]", "a", 0 ],
+ "obj-47::obj-106" : [ "a[18]", "a", 0 ],
+ "obj-1::obj-15" : [ "a[77]", "a", 0 ],
+ "obj-47::obj-88" : [ "a[62]", "a", 0 ],
+ "obj-1::obj-104" : [ "a[58]", "a", 0 ],
+ "obj-47::obj-101" : [ "a[23]", "a", 0 ],
+ "obj-47::obj-51" : [ "a[33]", "a", 0 ],
+ "obj-47::obj-67" : [ "a[40]", "a", 0 ],
+ "obj-1::obj-25" : [ "a[55]", "a", 0 ],
+ "obj-47::obj-98" : [ "a[65]", "a", 0 ],
+ "obj-47::obj-39" : [ "a[14]", "a", 0 ],
+ "obj-47::obj-130" : [ "a[74]", "a", 0 ],
+ "obj-1::obj-24" : [ "a[54]", "a", 0 ],
+ "obj-1::obj-10" : [ "a[75]", "a", 0 ],
+ "obj-47::obj-64" : [ "a[37]", "a", 0 ],
+ "obj-47::obj-118" : [ "a[68]", "a", 0 ],
+ "obj-47::obj-19" : [ "a[24]", "a", 0 ],
+ "obj-47::obj-102" : [ "a[22]", "a", 0 ],
+ "obj-1::obj-103" : [ "a[59]", "a", 0 ],
+ "obj-47::obj-68" : [ "a[41]", "a", 0 ],
+ "obj-47::obj-53" : [ "a[35]", "a", 0 ],
+ "obj-47::obj-40" : [ "a[15]", "a", 0 ],
+ "obj-47::obj-99" : [ "a[66]", "a", 0 ],
+ "obj-47::obj-41" : [ "a[16]", "a", 0 ],
+ "obj-47::obj-49" : [ "a[31]", "a", 0 ],
+ "obj-47::obj-37" : [ "a[12]", "a", 0 ],
+ "obj-1::obj-22" : [ "a[78]", "a", 0 ],
+ "obj-47::obj-103" : [ "a[21]", "a", 0 ],
+ "obj-47::obj-75" : [ "a[44]", "a", 0 ],
+ "obj-47::obj-119" : [ "a[69]", "a", 0 ],
+ "obj-1::obj-102" : [ "a[60]", "a", 0 ],
+ "obj-47::obj-95" : [ "a[49]", "a", 0 ],
+ "obj-47::obj-120" : [ "a[70]", "a", 0 ],
+ "obj-1::obj-101" : [ "a[61]", "a", 0 ],
+ "obj-47::obj-121" : [ "a[71]", "a", 0 ],
+ "obj-47::obj-122" : [ "a[72]", "a", 0 ],
+ "obj-47::obj-123" : [ "a[73]", "a", 0 ],
+ "obj-47::obj-128" : [ "a[47]", "a", 0 ],
+ "obj-47::obj-71" : [ "a[42]", "a", 0 ],
+ "obj-47::obj-100" : [ "a[67]", "a", 0 ],
+ "obj-1::obj-106" : [ "a[56]", "a", 0 ],
+ "obj-47::obj-42" : [ "a[17]", "a", 0 ],
+ "obj-1::obj-12" : [ "a[76]", "a", 0 ],
+ "obj-47::obj-104" : [ "a[20]", "a", 0 ],
+ "obj-47::obj-77" : [ "a[45]", "a", 0 ],
+ "obj-47::obj-65" : [ "a[38]", "a", 0 ],
+ "obj-47::obj-20" : [ "a[25]", "a", 0 ],
+ "obj-47::obj-21" : [ "a[26]", "a", 0 ],
+ "obj-47::obj-96" : [ "a[63]", "a", 0 ],
+ "obj-47::obj-23" : [ "a[27]", "a", 0 ],
+ "obj-47::obj-24" : [ "a[28]", "a", 0 ],
+ "obj-47::obj-52" : [ "a[34]", "a", 0 ],
+ "obj-1::obj-20" : [ "a[51]", "a", 0 ],
+ "obj-47::obj-25" : [ "a[29]", "a", 0 ],
+ "obj-47::obj-73" : [ "a[43]", "a", 0 ],
+ "obj-47::obj-87" : [ "a[48]", "a", 0 ],
+ "obj-47::obj-105" : [ "a[19]", "a", 0 ],
+ "obj-1::obj-105" : [ "a[57]", "a", 0 ],
+ "obj-47::obj-48" : [ "a[30]", "a", 0 ],
+ "obj-1::obj-19" : [ "a[50]", "a", 0 ],
+ "obj-47::obj-66" : [ "a[39]", "a", 0 ],
+ "obj-47::obj-126" : [ "a[46]", "a", 0 ],
+ "obj-47::obj-38" : [ "a[13]", "a", 0 ],
+ "obj-47::obj-97" : [ "a[64]", "a", 0 ],
+ "obj-1::obj-21" : [ "a[52]", "a", 0 ]
+ }
+,
+ "dependency_cache" : [ {
+ "name" : "o.io.slipserial.maxpat",
+ "bootpath" : "~/Documents/Max/Packages/o.io/experimental/Protocols/serial",
+ "type" : "JSON",
+ "implicit" : 1
+ }
+, {
+ "name" : "o.righttoleft.maxpat",
+ "bootpath" : "~/Documents/Max/Packages/odot/patchers/ordering",
+ "type" : "JSON",
+ "implicit" : 1
+ }
+, {
+ "name" : "o.io.serial.display.maxpat",
+ "bootpath" : "~/Documents/Max/Packages/o.io/experimental/Protocols/serial",
+ "type" : "JSON",
+ "implicit" : 1
+ }
+, {
+ "name" : "o.pack.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.route.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.union.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.validate.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.print.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.slip.encode.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.slip.decode.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.if.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.compose.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.display.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.downcast.mxo",
+ "type" : "iLaX"
+ }
+ ],
+ "autosave" : 0
+ }
+
+}
diff --git a/lib/OSC/Applications/MaxMSP/examples/SerialReceive.maxpat b/lib/OSC/Applications/MaxMSP/examples/SerialReceive.maxpat
new file mode 100644
index 0000000..3a9c242
--- /dev/null
+++ b/lib/OSC/Applications/MaxMSP/examples/SerialReceive.maxpat
@@ -0,0 +1,428 @@
+{
+ "patcher" : {
+ "fileversion" : 1,
+ "appversion" : {
+ "major" : 7,
+ "minor" : 0,
+ "revision" : 4,
+ "architecture" : "x86",
+ "modernui" : 1
+ }
+,
+ "rect" : [ 378.0, 174.0, 792.0, 490.0 ],
+ "bglocked" : 0,
+ "openinpresentation" : 0,
+ "default_fontsize" : 12.0,
+ "default_fontface" : 0,
+ "default_fontname" : "Arial",
+ "gridonopen" : 1,
+ "gridsize" : [ 15.0, 15.0 ],
+ "gridsnaponopen" : 1,
+ "objectsnaponopen" : 1,
+ "statusbarvisible" : 2,
+ "toolbarvisible" : 1,
+ "lefttoolbarpinned" : 0,
+ "toptoolbarpinned" : 0,
+ "righttoolbarpinned" : 0,
+ "bottomtoolbarpinned" : 0,
+ "toolbars_unpinned_last_save" : 0,
+ "tallnewobj" : 0,
+ "boxanimatetime" : 200,
+ "enablehscroll" : 1,
+ "enablevscroll" : 1,
+ "devicewidth" : 0.0,
+ "description" : "",
+ "digest" : "",
+ "tags" : "",
+ "style" : "",
+ "subpatcher_template" : "",
+ "boxes" : [ {
+ "box" : {
+ "fontface" : 0,
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-5",
+ "maxclass" : "o.display",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 68.0, 374.0, 267.0, 34.0 ],
+ "textcolor" : [ 1.0, 1.0, 1.0, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-12",
+ "maxclass" : "newobj",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "FullPacket" ],
+ "patching_rect" : [ 164.0, 202.0, 69.0, 22.0 ],
+ "style" : "",
+ "text" : "o.pack /led"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-1",
+ "maxclass" : "newobj",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "FullPacket" ],
+ "patching_rect" : [ 164.0, 244.0, 95.0, 24.0 ],
+ "style" : "",
+ "text" : "o.downcast"
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-18",
+ "maxclass" : "o.display",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 164.0, 314.0, 92.0, 34.0 ],
+ "textcolor" : [ 1.0, 1.0, 1.0, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-3",
+ "maxclass" : "o.display",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 350.5, 374.0, 158.0, 34.0 ],
+ "textcolor" : [ 1.0, 1.0, 1.0, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-2",
+ "linecount" : 2,
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 370.5, 218.5, 170.0, 33.0 ],
+ "style" : "",
+ "text" : "Look for your device in the menu list of serial USB"
+ }
+
+ }
+, {
+ "box" : {
+ "bgmode" : 0,
+ "border" : 0,
+ "clickthrough" : 0,
+ "enablehscroll" : 0,
+ "enablevscroll" : 0,
+ "id" : "obj-4",
+ "lockeddragscroll" : 0,
+ "maxclass" : "bpatcher",
+ "name" : "o.io.serial.display.maxpat",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "offset" : [ 3.0, 0.0 ],
+ "outlettype" : [ "FullPacket" ],
+ "patching_rect" : [ 350.5, 289.0, 340.5, 25.0 ],
+ "viewvisibility" : 1
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-23",
+ "maxclass" : "newobj",
+ "numinlets" : 2,
+ "numoutlets" : 2,
+ "outlettype" : [ "FullPacket", "FullPacket" ],
+ "patching_rect" : [ 289.5, 328.0, 80.0, 22.0 ],
+ "style" : "",
+ "text" : "o.io.slipserial"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-11",
+ "linecount" : 3,
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 541.0, 364.0, 150.0, 54.0 ],
+ "style" : "",
+ "text" : "stats on serial OSC communications"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-19",
+ "linecount" : 2,
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 43.5, 42.0, 156.0, 33.0 ],
+ "style" : "",
+ "text" : "PWM control of brightness of LED"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-15",
+ "maxclass" : "message",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 114.0, 151.0, 32.5, 22.0 ],
+ "style" : "",
+ "text" : "on"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-13",
+ "maxclass" : "message",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 56.0, 151.0, 32.5, 22.0 ],
+ "style" : "",
+ "text" : "off"
+ }
+
+ }
+, {
+ "box" : {
+ "contdata" : 1,
+ "id" : "obj-9",
+ "maxclass" : "multislider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 220.5, 31.0, 20.0, 140.0 ],
+ "setminmax" : [ 0.0, 1.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-8",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 164.0, 151.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+ ],
+ "lines" : [ {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-18", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-1", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-23", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-1", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-1", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-12", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-12", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-13", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-12", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-15", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-3", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "midpoints" : [ 360.0, 369.0, 360.0, 369.0 ],
+ "source" : [ "obj-23", 1 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-4", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "midpoints" : [ 360.0, 355.0, 702.0, 355.0, 702.0, 265.0, 360.0, 265.0 ],
+ "source" : [ "obj-23", 1 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-5", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-23", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-23", 1 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-4", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-12", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-8", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-12", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-9", 0 ]
+ }
+
+ }
+ ],
+ "dependency_cache" : [ {
+ "name" : "o.io.slipserial.maxpat",
+ "bootpath" : "~/Documents/Max/Packages/o.io/experimental/Protocols/serial",
+ "type" : "JSON",
+ "implicit" : 1
+ }
+, {
+ "name" : "o.righttoleft.maxpat",
+ "bootpath" : "~/Documents/Max/Packages/odot/patchers/ordering",
+ "type" : "JSON",
+ "implicit" : 1
+ }
+, {
+ "name" : "o.io.serial.display.maxpat",
+ "bootpath" : "~/Documents/Max/Packages/o.io/experimental/Protocols/serial",
+ "type" : "JSON",
+ "implicit" : 1
+ }
+, {
+ "name" : "o.pack.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.route.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.union.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.validate.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.print.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.slip.encode.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.slip.decode.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.if.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.display.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.downcast.mxo",
+ "type" : "iLaX"
+ }
+ ],
+ "embedsnapshot" : 0
+ }
+
+}
diff --git a/lib/OSC/Applications/MaxMSP/examples/SerialReceivewithServo.maxpat b/lib/OSC/Applications/MaxMSP/examples/SerialReceivewithServo.maxpat
new file mode 100644
index 0000000..4d8ecd0
--- /dev/null
+++ b/lib/OSC/Applications/MaxMSP/examples/SerialReceivewithServo.maxpat
@@ -0,0 +1,297 @@
+{
+ "patcher" : {
+ "fileversion" : 1,
+ "appversion" : {
+ "major" : 7,
+ "minor" : 0,
+ "revision" : 4,
+ "architecture" : "x86",
+ "modernui" : 1
+ }
+,
+ "rect" : [ 125.0, 78.0, 1072.0, 480.0 ],
+ "bglocked" : 0,
+ "openinpresentation" : 0,
+ "default_fontsize" : 12.0,
+ "default_fontface" : 0,
+ "default_fontname" : "Arial",
+ "gridonopen" : 1,
+ "gridsize" : [ 15.0, 15.0 ],
+ "gridsnaponopen" : 1,
+ "objectsnaponopen" : 1,
+ "statusbarvisible" : 2,
+ "toolbarvisible" : 1,
+ "lefttoolbarpinned" : 0,
+ "toptoolbarpinned" : 0,
+ "righttoolbarpinned" : 0,
+ "bottomtoolbarpinned" : 0,
+ "toolbars_unpinned_last_save" : 0,
+ "tallnewobj" : 0,
+ "boxanimatetime" : 200,
+ "enablehscroll" : 1,
+ "enablevscroll" : 1,
+ "devicewidth" : 0.0,
+ "description" : "",
+ "digest" : "",
+ "tags" : "",
+ "style" : "",
+ "subpatcher_template" : "",
+ "boxes" : [ {
+ "box" : {
+ "fontface" : 0,
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-12",
+ "maxclass" : "o.display",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 27.5, 386.0, 158.0, 34.0 ],
+ "presentation_rect" : [ 534.5, 418.0, 0.0, 0.0 ],
+ "textcolor" : [ 1.0, 1.0, 1.0, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-6",
+ "maxclass" : "newobj",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "FullPacket" ],
+ "patching_rect" : [ 137.5, 194.0, 82.0, 22.0 ],
+ "style" : "",
+ "text" : "o.pack /servo"
+ }
+
+ }
+, {
+ "box" : {
+ "contdata" : 1,
+ "id" : "obj-11",
+ "maxclass" : "multislider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 139.0, 27.0, 20.0, 140.0 ],
+ "setminmax" : [ 0.0, 180.0 ],
+ "settype" : 0,
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-3",
+ "maxclass" : "o.display",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 198.5, 386.0, 158.0, 34.0 ],
+ "textcolor" : [ 1.0, 1.0, 1.0, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-1",
+ "linecount" : 2,
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 218.5, 230.5, 170.0, 33.0 ],
+ "style" : "",
+ "text" : "Look for your device in the menu list of serial USB"
+ }
+
+ }
+, {
+ "box" : {
+ "bgmode" : 0,
+ "border" : 0,
+ "clickthrough" : 0,
+ "enablehscroll" : 0,
+ "enablevscroll" : 0,
+ "id" : "obj-20",
+ "lockeddragscroll" : 0,
+ "maxclass" : "bpatcher",
+ "name" : "o.io.serial.display.maxpat",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "offset" : [ 3.0, 0.0 ],
+ "outlettype" : [ "FullPacket" ],
+ "patching_rect" : [ 198.5, 301.0, 164.0, 24.0 ],
+ "viewvisibility" : 1
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-23",
+ "maxclass" : "newobj",
+ "numinlets" : 2,
+ "numoutlets" : 2,
+ "outlettype" : [ "FullPacket", "FullPacket" ],
+ "patching_rect" : [ 137.5, 337.0, 80.0, 22.0 ],
+ "style" : "",
+ "text" : "o.io.slipserial"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-5",
+ "linecount" : 3,
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 389.0, 376.0, 150.0, 54.0 ],
+ "style" : "",
+ "text" : "stats on serial OSC communications"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-19",
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 335.0, 151.0, 156.0, 20.0 ],
+ "style" : "",
+ "text" : "Servo control (from 0-180)"
+ }
+
+ }
+ ],
+ "lines" : [ {
+ "patchline" : {
+ "destination" : [ "obj-6", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-11", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-23", 1 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-20", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-12", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-23", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-20", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "midpoints" : [ 208.0, 367.0, 377.0, 367.0, 377.0, 277.0, 208.0, 277.0 ],
+ "source" : [ "obj-23", 1 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-3", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "midpoints" : [ 208.0, 381.0, 208.0, 381.0 ],
+ "source" : [ "obj-23", 1 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-23", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-6", 0 ]
+ }
+
+ }
+ ],
+ "dependency_cache" : [ {
+ "name" : "o.io.slipserial.maxpat",
+ "bootpath" : "~/Documents/Max/Packages/o.io/experimental/Protocols/serial",
+ "type" : "JSON",
+ "implicit" : 1
+ }
+, {
+ "name" : "o.righttoleft.maxpat",
+ "bootpath" : "~/Documents/Max/Packages/odot/patchers/ordering",
+ "type" : "JSON",
+ "implicit" : 1
+ }
+, {
+ "name" : "o.io.serial.display.maxpat",
+ "bootpath" : "~/Documents/Max/Packages/o.io/experimental/Protocols/serial",
+ "type" : "JSON",
+ "implicit" : 1
+ }
+, {
+ "name" : "o.pack.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.route.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.union.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.validate.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.print.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.slip.encode.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.slip.decode.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.if.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.display.mxo",
+ "type" : "iLaX"
+ }
+ ],
+ "embedsnapshot" : 0
+ }
+
+}
diff --git a/lib/OSC/Applications/MaxMSP/examples/SerialSend.maxpat b/lib/OSC/Applications/MaxMSP/examples/SerialSend.maxpat
new file mode 100644
index 0000000..3e43bf2
--- /dev/null
+++ b/lib/OSC/Applications/MaxMSP/examples/SerialSend.maxpat
@@ -0,0 +1,227 @@
+{
+ "patcher" : {
+ "fileversion" : 1,
+ "appversion" : {
+ "major" : 6,
+ "minor" : 1,
+ "revision" : 9,
+ "architecture" : "x86"
+ }
+,
+ "rect" : [ 196.0, 152.0, 1072.0, 480.0 ],
+ "bglocked" : 0,
+ "openinpresentation" : 0,
+ "default_fontsize" : 12.0,
+ "default_fontface" : 0,
+ "default_fontname" : "Arial",
+ "gridonopen" : 0,
+ "gridsize" : [ 15.0, 15.0 ],
+ "gridsnaponopen" : 0,
+ "statusbarvisible" : 2,
+ "toolbarvisible" : 1,
+ "boxanimatetime" : 200,
+ "imprint" : 0,
+ "enablehscroll" : 1,
+ "enablevscroll" : 1,
+ "devicewidth" : 0.0,
+ "description" : "",
+ "digest" : "",
+ "tags" : "",
+ "boxes" : [ {
+ "box" : {
+ "fontsize" : 12.0,
+ "id" : "obj-8",
+ "maxclass" : "o.display",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 572.0, 228.0, 207.0, 34.0 ],
+ "textcolor" : [ 0.0, 0.0, 0.0, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontsize" : 12.0,
+ "id" : "obj-6",
+ "maxclass" : "o.display",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 95.0, 228.0, 394.0, 34.0 ],
+ "textcolor" : [ 0.0, 0.0, 0.0, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontsize" : 12.0,
+ "id" : "obj-9",
+ "maxclass" : "o.expr.codebox",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "FullPacket", "FullPacket" ],
+ "patching_rect" : [ 95.0, 172.0, 251.0, 37.0 ],
+ "text" : " /bundle/time = gettimetag()",
+ "textcolor" : [ 0.0, 0.0, 0.0, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-7",
+ "maxclass" : "bpatcher",
+ "name" : "o.io.serial.display.maxpat",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "FullPacket" ],
+ "patching_rect" : [ 271.0, 58.0, 331.0, 28.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "frgb" : 0.0,
+ "id" : "obj-4",
+ "linecount" : 3,
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 592.0, 119.0, 150.0, 54.0 ],
+ "text" : "stats on serial OSC communications"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-26",
+ "maxclass" : "newobj",
+ "numinlets" : 2,
+ "numoutlets" : 2,
+ "outlettype" : [ "FullPacket", "FullPacket" ],
+ "patching_rect" : [ 95.0, 119.0, 195.0, 22.0 ],
+ "text" : "o.io.slipserial f 9600"
+ }
+
+ }
+ ],
+ "lines" : [ {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-7", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "midpoints" : [ 280.5, 141.0, 300.0, 141.0, 300.0, 96.0, 258.0, 96.0, 258.0, 54.0, 280.5, 54.0 ],
+ "source" : [ "obj-26", 1 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-8", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-26", 1 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-9", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-26", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-26", 1 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-7", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-6", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-9", 0 ]
+ }
+
+ }
+ ],
+ "dependency_cache" : [ {
+ "name" : "o.io.slipserial.maxpat",
+ "bootpath" : "/Users/adrian2013/Documents/Max/Packages/o.io/experimental/Protocols/serial",
+ "patcherrelativepath" : "../../../../../../Documents/Max/Packages/o.io/experimental/Protocols/serial",
+ "type" : "JSON",
+ "implicit" : 1
+ }
+, {
+ "name" : "o.righttoleft.maxpat",
+ "bootpath" : "/Users/adrian2013/Documents/Max/Packages/CNMAT-odot/patchers/ordering",
+ "patcherrelativepath" : "../../../../../../Documents/Max/Packages/CNMAT-odot/patchers/ordering",
+ "type" : "JSON",
+ "implicit" : 1
+ }
+, {
+ "name" : "o.io.serial.display.maxpat",
+ "bootpath" : "/Users/adrian2013/Documents/Max/Packages/o.io/experimental/Protocols/serial",
+ "patcherrelativepath" : "../../../../../../Documents/Max/Packages/o.io/experimental/Protocols/serial",
+ "type" : "JSON",
+ "implicit" : 1
+ }
+, {
+ "name" : "o.pack.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.route.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.union.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.validate.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.print.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.slip.encode.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.slip.decode.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.if.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.expr.codebox.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.display.mxo",
+ "type" : "iLaX"
+ }
+ ]
+ }
+
+}
diff --git a/lib/OSC/Applications/MaxMSP/examples/UDPCallResponse.maxpat b/lib/OSC/Applications/MaxMSP/examples/UDPCallResponse.maxpat
new file mode 100644
index 0000000..13ac13b
--- /dev/null
+++ b/lib/OSC/Applications/MaxMSP/examples/UDPCallResponse.maxpat
@@ -0,0 +1,947 @@
+{
+ "patcher" : {
+ "fileversion" : 1,
+ "appversion" : {
+ "major" : 7,
+ "minor" : 0,
+ "revision" : 4,
+ "architecture" : "x86",
+ "modernui" : 1
+ }
+,
+ "rect" : [ 140.0, 78.0, 982.0, 632.0 ],
+ "bglocked" : 0,
+ "openinpresentation" : 0,
+ "default_fontsize" : 14.0,
+ "default_fontface" : 0,
+ "default_fontname" : "Andale Mono",
+ "gridonopen" : 1,
+ "gridsize" : [ 5.0, 5.0 ],
+ "gridsnaponopen" : 1,
+ "objectsnaponopen" : 1,
+ "statusbarvisible" : 2,
+ "toolbarvisible" : 1,
+ "lefttoolbarpinned" : 0,
+ "toptoolbarpinned" : 0,
+ "righttoolbarpinned" : 0,
+ "bottomtoolbarpinned" : 0,
+ "toolbars_unpinned_last_save" : 0,
+ "tallnewobj" : 0,
+ "boxanimatetime" : 200,
+ "enablehscroll" : 1,
+ "enablevscroll" : 1,
+ "devicewidth" : 0.0,
+ "description" : "",
+ "digest" : "",
+ "tags" : "",
+ "style" : "",
+ "subpatcher_template" : "",
+ "boxes" : [ {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-10",
+ "maxclass" : "newobj",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "FullPacket" ],
+ "patching_rect" : [ 246.5, 265.0, 128.0, 24.0 ],
+ "style" : "",
+ "text" : "o.betweentimes"
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontsize" : 14.0,
+ "id" : "obj-9",
+ "maxclass" : "o.compose",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 699.5, 158.0, 157.0, 26.0 ],
+ "saved_bundle_data" : [ 35, 98, 117, 110, 100, 108, 101, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 20, 47, 97, 110, 97, 108, 111, 103, 47, 123, 50, 44, 51, 125, 47, 117, 0, 44, 0, 0, 0 ],
+ "saved_bundle_length" : 40,
+ "text" : "/analog/{2,3}/u",
+ "textcolor" : [ 0.188, 0.188, 0.188, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontsize" : 14.0,
+ "id" : "obj-8",
+ "maxclass" : "o.compose",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 448.5, 159.0, 150.0, 26.0 ],
+ "saved_bundle_data" : [ 35, 98, 117, 110, 100, 108, 101, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 20, 47, 97, 110, 97, 108, 111, 103, 47, 91, 48, 45, 51, 93, 47, 117, 0, 44, 0, 0, 0 ],
+ "saved_bundle_length" : 40,
+ "text" : "/analog/[0-3]/u",
+ "textcolor" : [ 0.188, 0.188, 0.188, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontsize" : 14.0,
+ "id" : "obj-6",
+ "maxclass" : "o.compose",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 246.5, 159.0, 150.0, 26.0 ],
+ "saved_bundle_data" : [ 35, 98, 117, 110, 100, 108, 101, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 16, 47, 97, 110, 97, 108, 111, 103, 47, 42, 0, 0, 0, 44, 0, 0, 0 ],
+ "saved_bundle_length" : 36,
+ "text" : "/analog/*",
+ "textcolor" : [ 0.188, 0.188, 0.188, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontsize" : 14.0,
+ "id" : "obj-4",
+ "maxclass" : "o.display",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 246.5, 308.0, 265.0, 36.0 ],
+ "textcolor" : [ 1.0, 1.0, 1.0, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-3",
+ "maxclass" : "newobj",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 246.5, 55.0, 95.0, 24.0 ],
+ "style" : "",
+ "text" : "loadmess 1"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-1",
+ "linecount" : 2,
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 726.5, 77.0, 222.0, 38.0 ],
+ "style" : "",
+ "text" : "read analog pins 2 and 3 with pullup turned on"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-78",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 699.5, 95.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-79",
+ "maxclass" : "newobj",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 699.5, 126.0, 86.0, 24.0 ],
+ "style" : "",
+ "text" : "qmetro 20"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-56",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 179.333328, 500.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-64",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 179.333328, 396.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[37]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[25]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-13",
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 11.0, 542.0, 137.0, 22.0 ],
+ "style" : "",
+ "text" : "analog readings"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-110",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 145.666672, 500.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-109",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 112.0, 500.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-108",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 78.333336, 500.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-107",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 44.666668, 500.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-105",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 145.666672, 396.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[19]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[4]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-104",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 112.0, 396.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[20]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[3]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-103",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 78.333336, 396.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[21]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[2]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-102",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 44.666668, 396.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[22]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[1]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-101",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 11.0, 396.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[23]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-84",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 11.0, 500.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-81",
+ "maxclass" : "newobj",
+ "numinlets" : 1,
+ "numoutlets" : 7,
+ "outlettype" : [ "", "", "", "", "", "", "FullPacket" ],
+ "patching_rect" : [ 11.0, 323.0, 221.0, 24.0 ],
+ "style" : "",
+ "text" : "o.route /0 /1 /2 /3 /4 /5"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-45",
+ "maxclass" : "newobj",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "FullPacket" ],
+ "patching_rect" : [ 11.0, 265.0, 137.0, 24.0 ],
+ "style" : "",
+ "text" : "o.route /analog"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-15",
+ "linecount" : 2,
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 475.5, 86.0, 187.0, 38.0 ],
+ "style" : "",
+ "text" : "read analog pins 0-3 with pullup turned on"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-18",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 448.5, 95.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-22",
+ "maxclass" : "newobj",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 448.5, 125.0, 86.0, 24.0 ],
+ "style" : "",
+ "text" : "qmetro 20"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-46",
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 261.5, 95.0, 187.0, 22.0 ],
+ "style" : "",
+ "text" : "read all analog pins"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-60",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 246.5, 95.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-61",
+ "maxclass" : "newobj",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 246.5, 124.0, 95.0, 24.0 ],
+ "style" : "",
+ "text" : "qmetro 100"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-26",
+ "maxclass" : "newobj",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 246.5, 214.0, 288.0, 24.0 ],
+ "style" : "",
+ "text" : "o.io.udp 128.32.122.252 8888 9999"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-91",
+ "maxclass" : "newobj",
+ "numinlets" : 0,
+ "numoutlets" : 0,
+ "patcher" : {
+ "fileversion" : 1,
+ "appversion" : {
+ "major" : 7,
+ "minor" : 0,
+ "revision" : 4,
+ "architecture" : "x86",
+ "modernui" : 1
+ }
+,
+ "rect" : [ 34.0, 78.0, 738.0, 421.0 ],
+ "bglocked" : 0,
+ "openinpresentation" : 0,
+ "default_fontsize" : 14.0,
+ "default_fontface" : 0,
+ "default_fontname" : "Andale Mono",
+ "gridonopen" : 1,
+ "gridsize" : [ 5.0, 5.0 ],
+ "gridsnaponopen" : 1,
+ "objectsnaponopen" : 1,
+ "statusbarvisible" : 2,
+ "toolbarvisible" : 1,
+ "lefttoolbarpinned" : 0,
+ "toptoolbarpinned" : 0,
+ "righttoolbarpinned" : 0,
+ "bottomtoolbarpinned" : 0,
+ "toolbars_unpinned_last_save" : 0,
+ "tallnewobj" : 0,
+ "boxanimatetime" : 200,
+ "enablehscroll" : 1,
+ "enablevscroll" : 1,
+ "devicewidth" : 0.0,
+ "description" : "",
+ "digest" : "",
+ "tags" : "",
+ "style" : "",
+ "subpatcher_template" : "",
+ "boxes" : [ {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-2",
+ "linecount" : 25,
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 15.0, 20.0, 768.0, 400.0 ],
+ "style" : "",
+ "text" : "/*\n Written by Yotam Mann and Adrian Freed,\n The Center for New Music and Audio Technologies,\n University of California, Berkeley. Copyright (c) 2012, The Regents of\n the University of California (Regents).\n \n Permission to use, copy, modify, distribute, and distribute modified versions\n of this software and its documentation without fee and without a signed\n licensing agreement, is hereby granted, provided that the above copyright\n notice, this paragraph and the following two paragraphs appear in all copies,\n modifications, and distributions.\n \n IN NO EVENT SHALL REGENTS BE LIABLE TO ANY PARTY FOR DIRECT, INDIRECT,\n SPECIAL, INCIDENTAL, OR CONSEQUENTIAL DAMAGES, INCLUDING LOST PROFITS, ARISING\n OUT OF THE USE OF THIS SOFTWARE AND ITS DOCUMENTATION, EVEN IF REGENTS HAS\n BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.\n \n REGENTS SPECIFICALLY DISCLAIMS ANY WARRANTIES, INCLUDING, BUT NOT LIMITED TO,\n THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR\n PURPOSE. THE SOFTWARE AND ACCOMPANYING DOCUMENTATION, IF ANY, PROVIDED\n HEREUNDER IS PROVIDED \"AS IS\". REGENTS HAS NO OBLIGATION TO PROVIDE\n MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.\n \n For bug reports and feature requests please email me at yotam@cnmat.berkeley.edu\n */"
+ }
+
+ }
+ ],
+ "lines" : [ ]
+ }
+,
+ "patching_rect" : [ 666.5, 494.0, 111.0, 24.0 ],
+ "saved_object_attributes" : {
+ "description" : "",
+ "digest" : "",
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "globalpatchername" : "",
+ "style" : "",
+ "tags" : ""
+ }
+,
+ "style" : "",
+ "text" : "p disclaimer"
+ }
+
+ }
+ ],
+ "lines" : [ {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-4", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-10", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-84", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-101", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-107", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-102", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-108", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-103", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-109", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-104", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-110", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-105", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-22", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-18", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-8", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-22", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-10", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-26", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-45", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-26", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-60", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-3", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-81", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-45", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-26", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-6", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-61", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-60", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-6", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-61", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-56", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-64", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-79", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-78", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-9", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-79", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-26", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-8", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-101", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-102", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 1 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-103", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 2 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-104", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 3 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-105", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 4 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-64", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 5 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-26", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-9", 0 ]
+ }
+
+ }
+ ],
+ "parameters" : {
+ "obj-105" : [ "a[19]", "a", 0 ],
+ "obj-104" : [ "a[20]", "a", 0 ],
+ "obj-103" : [ "a[21]", "a", 0 ],
+ "obj-64" : [ "a[37]", "a", 0 ],
+ "obj-102" : [ "a[22]", "a", 0 ],
+ "obj-101" : [ "a[23]", "a", 0 ]
+ }
+,
+ "dependency_cache" : [ {
+ "name" : "o.io.udp.maxpat",
+ "bootpath" : "~/Documents/Max/Packages/o.io/experimental/Protocols/udp",
+ "type" : "JSON",
+ "implicit" : 1
+ }
+, {
+ "name" : "o.betweentimes.maxpat",
+ "bootpath" : "~/Documents/Max/Packages/odot/patchers/time",
+ "type" : "JSON",
+ "implicit" : 1
+ }
+, {
+ "name" : "o.was.maxpat",
+ "bootpath" : "~/Documents/Max/Packages/odot/dev",
+ "type" : "JSON",
+ "implicit" : 1
+ }
+, {
+ "name" : "o.righttoleft.maxpat",
+ "bootpath" : "~/Documents/Max/Packages/odot/patchers/ordering",
+ "type" : "JSON",
+ "implicit" : 1
+ }
+, {
+ "name" : "o.route.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.display.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.compose.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.timetag.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.prepend.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.intersection.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.union.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.var.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.collect.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.if.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.expr.codebox.mxo",
+ "type" : "iLaX"
+ }
+ ],
+ "embedsnapshot" : 0
+ }
+
+}
diff --git a/lib/OSC/Applications/MaxMSP/examples/UDPEcho.maxpat b/lib/OSC/Applications/MaxMSP/examples/UDPEcho.maxpat
new file mode 100644
index 0000000..ca884ba
--- /dev/null
+++ b/lib/OSC/Applications/MaxMSP/examples/UDPEcho.maxpat
@@ -0,0 +1,215 @@
+{
+ "patcher" : {
+ "fileversion" : 1,
+ "appversion" : {
+ "major" : 6,
+ "minor" : 1,
+ "revision" : 9,
+ "architecture" : "x86"
+ }
+,
+ "rect" : [ 153.0, 100.0, 758.0, 531.0 ],
+ "bglocked" : 0,
+ "openinpresentation" : 0,
+ "default_fontsize" : 14.0,
+ "default_fontface" : 0,
+ "default_fontname" : "Andale Mono",
+ "gridonopen" : 0,
+ "gridsize" : [ 5.0, 5.0 ],
+ "gridsnaponopen" : 0,
+ "statusbarvisible" : 2,
+ "toolbarvisible" : 1,
+ "boxanimatetime" : 200,
+ "imprint" : 0,
+ "enablehscroll" : 1,
+ "enablevscroll" : 1,
+ "devicewidth" : 0.0,
+ "description" : "",
+ "digest" : "",
+ "tags" : "",
+ "boxes" : [ {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-8",
+ "maxclass" : "newobj",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "FullPacket" ],
+ "patching_rect" : [ 20.5, 240.0, 128.0, 22.0 ],
+ "text" : "o.betweentimes"
+ }
+
+ }
+, {
+ "box" : {
+ "fontsize" : 14.0,
+ "id" : "obj-7",
+ "linecount" : 2,
+ "maxclass" : "o.compose",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 20.5, 112.0, 510.0, 42.0 ],
+ "saved_bundle_data" : [ 35, 98, 117, 110, 100, 108, 101, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 16, 47, 112, 105, 110, 103, 0, 0, 0, 44, 105, 0, 0, 0, 0, 0, 100, 0, 0, 0, 76, 47, 116, 104, 105, 110, 103, 0, 0, 44, 100, 105, 105, 105, 105, 105, 105, 105, 105, 115, 0, 64, 89, 0, 0, 0, 0, 0, 0, 0, 0, 0, 100, 0, 0, 0, 1, 0, 0, 0, 2, 0, 0, 0, 3, 0, 0, 0, 4, 0, 0, 0, 4, 0, 0, 0, 4, 0, 0, 0, 4, 98, 105, 103, 103, 101, 114, 32, 112, 97, 99, 107, 101, 116, 0, 0, 0 ],
+ "saved_bundle_length" : 116,
+ "text" : "/ping : 100,\n/thing : [100., 100, 1, 2, 3, 4, 4, 4, 4, \"bigger packet\"]",
+ "textcolor" : [ 0.0, 0.0, 0.0, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontsize" : 14.0,
+ "id" : "obj-5",
+ "maxclass" : "o.display",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 20.5, 296.0, 517.0, 36.0 ],
+ "textcolor" : [ 0.0, 0.0, 0.0, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-61",
+ "maxclass" : "newobj",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 20.5, 22.0, 153.0, 22.0 ],
+ "text" : "metro 2 @active 1"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-26",
+ "maxclass" : "newobj",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 20.5, 191.0, 288.0, 22.0 ],
+ "text" : "o.io.udp 128.32.122.252 8888 9999"
+ }
+
+ }
+ ],
+ "lines" : [ {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-8", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-26", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-7", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-61", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-26", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-7", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-5", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-8", 0 ]
+ }
+
+ }
+ ],
+ "dependency_cache" : [ {
+ "name" : "o.io.udp.maxpat",
+ "bootpath" : "/Users/adrian2013/Documents/Max/Packages/o.io/experimental/Protocols/udp",
+ "patcherrelativepath" : "../../../../../../Documents/Max/Packages/o.io/experimental/Protocols/udp",
+ "type" : "JSON",
+ "implicit" : 1
+ }
+, {
+ "name" : "o.betweentimes.maxpat",
+ "bootpath" : "/Users/adrian2013/Documents/Max/Packages/CNMAT-odot/patchers/time",
+ "patcherrelativepath" : "../../../../../../Documents/Max/Packages/CNMAT-odot/patchers/time",
+ "type" : "JSON",
+ "implicit" : 1
+ }
+, {
+ "name" : "o.was.maxpat",
+ "bootpath" : "/Users/adrian2013/Documents/Max/Packages/CNMAT-odot/dev",
+ "patcherrelativepath" : "../../../../../../Documents/Max/Packages/CNMAT-odot/dev",
+ "type" : "JSON",
+ "implicit" : 1
+ }
+, {
+ "name" : "o.righttoleft.maxpat",
+ "bootpath" : "/Users/adrian2013/Documents/Max/Packages/CNMAT-odot/patchers/ordering",
+ "patcherrelativepath" : "../../../../../../Documents/Max/Packages/CNMAT-odot/patchers/ordering",
+ "type" : "JSON",
+ "implicit" : 1
+ }
+, {
+ "name" : "o.display.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.compose.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.timetag.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.prepend.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.intersection.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.union.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.var.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.collect.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.if.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.expr.codebox.mxo",
+ "type" : "iLaX"
+ }
+ ]
+ }
+
+}
diff --git a/lib/OSC/Applications/MaxMSP/examples/UDPOscuino.maxpat b/lib/OSC/Applications/MaxMSP/examples/UDPOscuino.maxpat
new file mode 100644
index 0000000..e44809d
--- /dev/null
+++ b/lib/OSC/Applications/MaxMSP/examples/UDPOscuino.maxpat
@@ -0,0 +1,4894 @@
+{
+ "patcher" : {
+ "fileversion" : 1,
+ "appversion" : {
+ "major" : 7,
+ "minor" : 0,
+ "revision" : 4,
+ "architecture" : "x86",
+ "modernui" : 1
+ }
+,
+ "rect" : [ 87.0, 78.0, 913.0, 425.0 ],
+ "bglocked" : 0,
+ "openinpresentation" : 0,
+ "default_fontsize" : 14.0,
+ "default_fontface" : 0,
+ "default_fontname" : "Andale Mono",
+ "gridonopen" : 1,
+ "gridsize" : [ 5.0, 5.0 ],
+ "gridsnaponopen" : 1,
+ "objectsnaponopen" : 1,
+ "statusbarvisible" : 2,
+ "toolbarvisible" : 1,
+ "lefttoolbarpinned" : 0,
+ "toptoolbarpinned" : 0,
+ "righttoolbarpinned" : 0,
+ "bottomtoolbarpinned" : 0,
+ "toolbars_unpinned_last_save" : 0,
+ "tallnewobj" : 0,
+ "boxanimatetime" : 200,
+ "enablehscroll" : 1,
+ "enablevscroll" : 1,
+ "devicewidth" : 0.0,
+ "description" : "",
+ "digest" : "",
+ "tags" : "",
+ "style" : "",
+ "subpatcher_template" : "",
+ "boxes" : [ {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-3",
+ "maxclass" : "newobj",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "FullPacket" ],
+ "patching_rect" : [ 506.0, 233.0, 95.0, 24.0 ],
+ "style" : "",
+ "text" : "o.downcast"
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontsize" : 14.0,
+ "id" : "obj-9",
+ "maxclass" : "o.compose",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 712.0, 168.0, 150.0, 26.0 ],
+ "saved_bundle_data" : [ 35, 98, 117, 110, 100, 108, 101, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 20, 47, 116, 111, 110, 101, 47, 51, 0, 44, 100, 0, 0, 64, 123, -128, 0, 0, 0, 0, 0 ],
+ "saved_bundle_length" : 40,
+ "text" : "/tone/3 : 440.",
+ "textcolor" : [ 0.188, 0.188, 0.188, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontsize" : 14.0,
+ "id" : "obj-5",
+ "maxclass" : "o.compose",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 712.0, 116.0, 150.0, 26.0 ],
+ "saved_bundle_data" : [ 35, 98, 117, 110, 100, 108, 101, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 12, 47, 116, 111, 110, 101, 47, 51, 0, 44, 0, 0, 0 ],
+ "saved_bundle_length" : 32,
+ "text" : "/tone/3",
+ "textcolor" : [ 0.188, 0.188, 0.188, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontsize" : 14.0,
+ "id" : "obj-2",
+ "maxclass" : "o.display",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 506.0, 348.0, 265.0, 36.0 ],
+ "textcolor" : [ 1.0, 1.0, 1.0, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-8",
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 672.0, 233.0, 150.0, 22.0 ],
+ "style" : "",
+ "text" : "Ethernet"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-6",
+ "maxclass" : "newobj",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 506.0, 279.0, 288.0, 24.0 ],
+ "style" : "",
+ "text" : "o.io.udp 128.32.122.252 8888 9999"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-1",
+ "maxclass" : "newobj",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patcher" : {
+ "fileversion" : 1,
+ "appversion" : {
+ "major" : 7,
+ "minor" : 0,
+ "revision" : 4,
+ "architecture" : "x86",
+ "modernui" : 1
+ }
+,
+ "rect" : [ 624.0, 45.0, 640.0, 480.0 ],
+ "bglocked" : 0,
+ "openinpresentation" : 0,
+ "default_fontsize" : 12.0,
+ "default_fontface" : 0,
+ "default_fontname" : "Arial",
+ "gridonopen" : 1,
+ "gridsize" : [ 15.0, 15.0 ],
+ "gridsnaponopen" : 1,
+ "objectsnaponopen" : 1,
+ "statusbarvisible" : 2,
+ "toolbarvisible" : 1,
+ "lefttoolbarpinned" : 0,
+ "toptoolbarpinned" : 0,
+ "righttoolbarpinned" : 0,
+ "bottomtoolbarpinned" : 0,
+ "toolbars_unpinned_last_save" : 0,
+ "tallnewobj" : 0,
+ "boxanimatetime" : 200,
+ "enablehscroll" : 1,
+ "enablevscroll" : 1,
+ "devicewidth" : 0.0,
+ "description" : "",
+ "digest" : "",
+ "tags" : "",
+ "style" : "",
+ "subpatcher_template" : "",
+ "boxes" : [ {
+ "box" : {
+ "fontface" : 0,
+ "fontsize" : 12.0,
+ "id" : "obj-4",
+ "maxclass" : "o.compose",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 329.0, 106.0, 150.0, 24.0 ],
+ "saved_bundle_data" : [ 35, 98, 117, 110, 100, 108, 101, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 12, 47, 99, 47, 51, 0, 0, 0, 0, 44, 0, 0, 0 ],
+ "saved_bundle_length" : 32,
+ "text" : "/c/3",
+ "textcolor" : [ 0.188, 0.188, 0.188, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-18",
+ "linecount" : 3,
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 33.0, 33.0, 90.0, 47.0 ],
+ "style" : "",
+ "text" : "Capacitance from touch pins\n"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-13",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 312.0, 34.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-11",
+ "maxclass" : "newobj",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 329.0, 68.0, 65.0, 20.0 ],
+ "style" : "",
+ "text" : "qmetro 30"
+ }
+
+ }
+, {
+ "box" : {
+ "comment" : "",
+ "id" : "obj-6",
+ "maxclass" : "outlet",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 311.0, 154.0, 25.0, 25.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-45",
+ "maxclass" : "newobj",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "FullPacket" ],
+ "patching_rect" : [ 48.0, 169.0, 95.0, 22.0 ],
+ "style" : "",
+ "text" : "o.route /c"
+ }
+
+ }
+, {
+ "box" : {
+ "comment" : "",
+ "id" : "obj-60",
+ "maxclass" : "inlet",
+ "numinlets" : 0,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 48.0, 120.0, 25.0, 25.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-1",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 411.0, 430.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-2",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 378.0, 430.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-14",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 345.0, 430.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-16",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 312.0, 430.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-17",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 279.0, 430.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-19",
+ "ignoreclick" : 1,
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 411.0, 324.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[50]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 2048.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[12]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-20",
+ "ignoreclick" : 1,
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 378.0, 326.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[51]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 2048.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[13]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-21",
+ "ignoreclick" : 1,
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 345.0, 326.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[52]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 2048.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[14]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-23",
+ "ignoreclick" : 1,
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 312.0, 326.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[53]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 2048.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[15]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-24",
+ "ignoreclick" : 1,
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 279.0, 326.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[54]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 2048.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[16]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-25",
+ "ignoreclick" : 1,
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 246.0, 326.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[55]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 2048.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[17]"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-26",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 246.0, 430.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-111",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 216.0, 429.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-110",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 180.0, 429.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-109",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 147.0, 429.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-108",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 114.0, 429.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-107",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 81.0, 429.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-106",
+ "ignoreclick" : 1,
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 213.0, 325.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[56]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 2048.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[5]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-105",
+ "ignoreclick" : 1,
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 180.0, 325.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[57]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 2048.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[4]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-104",
+ "ignoreclick" : 1,
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 147.0, 325.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[58]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 2048.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[3]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-103",
+ "ignoreclick" : 1,
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 114.0, 325.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[59]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 2048.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[2]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-102",
+ "ignoreclick" : 1,
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 81.0, 325.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[60]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 2048.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[1]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-101",
+ "ignoreclick" : 1,
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 48.0, 325.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[61]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 2048.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-84",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 48.0, 429.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-81",
+ "maxclass" : "newobj",
+ "numinlets" : 1,
+ "numoutlets" : 13,
+ "outlettype" : [ "", "", "", "", "", "", "", "", "", "", "", "", "FullPacket" ],
+ "patching_rect" : [ 48.0, 219.0, 456.0, 22.0 ],
+ "style" : "",
+ "text" : "o.route /0 /1 /16 /17 /18 /19 /22 /23 /25 /32 /33 /15"
+ }
+
+ }
+ ],
+ "lines" : [ {
+ "patchline" : {
+ "destination" : [ "obj-84", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-101", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-107", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-102", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-108", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-103", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-109", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-104", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-110", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-105", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-111", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-106", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-4", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-11", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-11", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-13", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-1", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-19", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-2", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-20", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-14", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-21", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-16", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-23", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-17", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-24", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-26", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-25", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-6", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-4", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-81", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-45", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-45", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-60", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-101", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-102", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 1 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-103", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 2 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-104", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 3 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-105", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 4 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-106", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 5 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-19", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 11 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-20", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 10 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-21", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 9 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-23", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 8 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-24", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 7 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-25", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 6 ]
+ }
+
+ }
+ ]
+ }
+,
+ "patching_rect" : [ 506.0, 149.0, 145.0, 24.0 ],
+ "saved_object_attributes" : {
+ "description" : "",
+ "digest" : "",
+ "globalpatchername" : "",
+ "style" : "",
+ "tags" : ""
+ }
+,
+ "style" : "",
+ "text" : "p teensy 3 touch"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-58",
+ "maxclass" : "newobj",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patcher" : {
+ "fileversion" : 1,
+ "appversion" : {
+ "major" : 7,
+ "minor" : 0,
+ "revision" : 4,
+ "architecture" : "x86",
+ "modernui" : 1
+ }
+,
+ "rect" : [ 550.0, 69.0, 834.0, 483.0 ],
+ "bglocked" : 0,
+ "openinpresentation" : 0,
+ "default_fontsize" : 12.0,
+ "default_fontface" : 0,
+ "default_fontname" : "Arial",
+ "gridonopen" : 1,
+ "gridsize" : [ 15.0, 15.0 ],
+ "gridsnaponopen" : 1,
+ "objectsnaponopen" : 1,
+ "statusbarvisible" : 2,
+ "toolbarvisible" : 1,
+ "lefttoolbarpinned" : 0,
+ "toptoolbarpinned" : 0,
+ "righttoolbarpinned" : 0,
+ "bottomtoolbarpinned" : 0,
+ "toolbars_unpinned_last_save" : 0,
+ "tallnewobj" : 0,
+ "boxanimatetime" : 200,
+ "enablehscroll" : 1,
+ "enablevscroll" : 1,
+ "devicewidth" : 0.0,
+ "description" : "",
+ "digest" : "",
+ "tags" : "",
+ "style" : "",
+ "subpatcher_template" : "",
+ "boxes" : [ {
+ "box" : {
+ "fontface" : 0,
+ "fontsize" : 12.0,
+ "id" : "obj-4",
+ "maxclass" : "o.display",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 653.0, 419.0, 150.0, 34.0 ],
+ "textcolor" : [ 1.0, 1.0, 1.0, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-32",
+ "maxclass" : "o.compose",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 149.5, 326.0, 41.0, 24.0 ],
+ "saved_bundle_data" : [ 35, 98, 117, 110, 100, 108, 101, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 12, 47, 115, 47, 115, 0, 0, 0, 0, 44, 0, 0, 0 ],
+ "saved_bundle_length" : 32,
+ "text" : "/s/s",
+ "textcolor" : [ 0.188, 0.188, 0.188, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-30",
+ "maxclass" : "o.compose",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 134.0, 264.0, 39.0, 24.0 ],
+ "saved_bundle_data" : [ 35, 98, 117, 110, 100, 108, 101, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 12, 47, 115, 47, 116, 0, 0, 0, 0, 44, 0, 0, 0 ],
+ "saved_bundle_length" : 32,
+ "text" : "/s/t",
+ "textcolor" : [ 0.188, 0.188, 0.188, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-28",
+ "maxclass" : "o.compose",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 106.0, 209.0, 45.0, 24.0 ],
+ "saved_bundle_data" : [ 35, 98, 117, 110, 100, 108, 101, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 12, 47, 115, 47, 109, 0, 0, 0, 0, 44, 0, 0, 0 ],
+ "saved_bundle_length" : 32,
+ "text" : "/s/m",
+ "textcolor" : [ 0.188, 0.188, 0.188, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-26",
+ "maxclass" : "o.compose",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 70.0, 152.0, 42.0, 24.0 ],
+ "saved_bundle_data" : [ 35, 98, 117, 110, 100, 108, 101, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 12, 47, 115, 47, 100, 0, 0, 0, 0, 44, 0, 0, 0 ],
+ "saved_bundle_length" : 32,
+ "text" : "/s/d",
+ "textcolor" : [ 0.188, 0.188, 0.188, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-20",
+ "maxclass" : "o.compose",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 44.0, 98.0, 42.0, 24.0 ],
+ "saved_bundle_data" : [ 35, 98, 117, 110, 100, 108, 101, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 12, 47, 115, 47, 97, 0, 0, 0, 0, 44, 0, 0, 0 ],
+ "saved_bundle_length" : 32,
+ "text" : "/s/a",
+ "textcolor" : [ 0.188, 0.188, 0.188, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-15",
+ "maxclass" : "newobj",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "FullPacket" ],
+ "patching_rect" : [ 196.5, 400.0, 65.0, 20.0 ],
+ "style" : "",
+ "text" : "o.pack /s/l"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-9",
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 149.5, 296.0, 179.0, 22.0 ],
+ "style" : "",
+ "text" : "Power Supply Voltage"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-13",
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 134.0, 242.0, 103.0, 22.0 ],
+ "style" : "",
+ "text" : "Temperature"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-8",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 219.0, 333.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-25",
+ "linecount" : 2,
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 254.5, 350.0, 381.0, 38.0 ],
+ "style" : "",
+ "text" : "toggle the LED (don't do this on Teensy 3.0 with Wiznet Ethernet that uses pin 13)"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-1",
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 106.0, 182.0, 246.0, 22.0 ],
+ "style" : "",
+ "text" : "Arduino time in microseconds"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-3",
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 53.0, 76.0, 288.0, 22.0 ],
+ "style" : "",
+ "text" : "Returns the number of analog pins"
+ }
+
+ }
+, {
+ "box" : {
+ "comment" : "",
+ "id" : "obj-2",
+ "maxclass" : "outlet",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 44.0, 462.0, 25.0, 25.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-10",
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 70.0, 126.0, 296.0, 22.0 ],
+ "style" : "",
+ "text" : "Returns the number of digital pins"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-46",
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 49.0, 45.0, 792.0, 22.0 ],
+ "style" : "",
+ "text" : "QUERIES AND PARAMS"
+ }
+
+ }
+, {
+ "box" : {
+ "comment" : "",
+ "id" : "obj-5",
+ "maxclass" : "inlet",
+ "numinlets" : 0,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 528.0, 324.0, 25.0, 25.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-45",
+ "maxclass" : "newobj",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "FullPacket" ],
+ "patching_rect" : [ 528.0, 378.0, 95.0, 22.0 ],
+ "style" : "",
+ "text" : "o.route /s"
+ }
+
+ }
+ ],
+ "lines" : [ {
+ "patchline" : {
+ "destination" : [ "obj-2", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-15", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-2", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-20", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-2", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-26", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-2", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-28", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-2", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-30", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-2", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-32", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-4", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-45", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-45", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-5", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-15", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-8", 0 ]
+ }
+
+ }
+ ]
+ }
+,
+ "patching_rect" : [ 274.5, 149.0, 179.0, 24.0 ],
+ "saved_object_attributes" : {
+ "description" : "",
+ "digest" : "",
+ "globalpatchername" : "",
+ "style" : "",
+ "tags" : ""
+ }
+,
+ "style" : "",
+ "text" : "p queries-and-params"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-52",
+ "maxclass" : "newobj",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patcher" : {
+ "fileversion" : 1,
+ "appversion" : {
+ "major" : 7,
+ "minor" : 0,
+ "revision" : 4,
+ "architecture" : "x86",
+ "modernui" : 1
+ }
+,
+ "rect" : [ 493.0, 67.0, 947.0, 536.0 ],
+ "bglocked" : 0,
+ "openinpresentation" : 0,
+ "default_fontsize" : 12.0,
+ "default_fontface" : 0,
+ "default_fontname" : "Arial",
+ "gridonopen" : 1,
+ "gridsize" : [ 15.0, 15.0 ],
+ "gridsnaponopen" : 1,
+ "objectsnaponopen" : 1,
+ "statusbarvisible" : 2,
+ "toolbarvisible" : 1,
+ "lefttoolbarpinned" : 0,
+ "toptoolbarpinned" : 0,
+ "righttoolbarpinned" : 0,
+ "bottomtoolbarpinned" : 0,
+ "toolbars_unpinned_last_save" : 0,
+ "tallnewobj" : 0,
+ "boxanimatetime" : 200,
+ "enablehscroll" : 1,
+ "enablevscroll" : 1,
+ "devicewidth" : 0.0,
+ "description" : "",
+ "digest" : "",
+ "tags" : "",
+ "style" : "",
+ "subpatcher_template" : "",
+ "boxes" : [ {
+ "box" : {
+ "fontface" : 0,
+ "fontsize" : 12.0,
+ "id" : "obj-40",
+ "maxclass" : "o.compose",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 45.0, 445.0, 150.0, 24.0 ],
+ "saved_bundle_data" : [ 35, 98, 117, 110, 100, 108, 101, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 12, 47, 100, 47, 42, 0, 0, 0, 0, 44, 0, 0, 0 ],
+ "saved_bundle_length" : 32,
+ "text" : "/d/*",
+ "textcolor" : [ 0.188, 0.188, 0.188, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontsize" : 12.0,
+ "id" : "obj-15",
+ "maxclass" : "o.compose",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 356.5, 293.0, 150.0, 24.0 ],
+ "saved_bundle_data" : [ 35, 98, 117, 110, 100, 108, 101, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 20, 47, 100, 47, 49, 91, 51, 56, 57, 93, 0, 0, 0, 44, 105, 0, 0, 0, 0, 0, 1 ],
+ "saved_bundle_length" : 40,
+ "text" : "/d/1[389] : 1",
+ "textcolor" : [ 0.188, 0.188, 0.188, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontsize" : 12.0,
+ "id" : "obj-14",
+ "maxclass" : "o.compose",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 383.0, 336.0, 150.0, 24.0 ],
+ "saved_bundle_data" : [ 35, 98, 117, 110, 100, 108, 101, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 12, 47, 100, 47, 49, 48, 47, 117, 0, 44, 0, 0, 0 ],
+ "saved_bundle_length" : 32,
+ "text" : "/d/10/u",
+ "textcolor" : [ 0.188, 0.188, 0.188, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontsize" : 12.0,
+ "id" : "obj-11",
+ "maxclass" : "o.compose",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 110.0, 293.0, 150.0, 24.0 ],
+ "saved_bundle_data" : [ 35, 98, 117, 110, 100, 108, 101, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 20, 47, 100, 47, 49, 91, 48, 45, 57, 93, 0, 0, 0, 44, 105, 0, 0, 0, 0, 0, 1 ],
+ "saved_bundle_length" : 40,
+ "text" : "/d/1[0-9] : 1",
+ "textcolor" : [ 0.188, 0.188, 0.188, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-2",
+ "maxclass" : "newobj",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "FullPacket" ],
+ "patching_rect" : [ 220.0, 405.0, 76.0, 20.0 ],
+ "style" : "",
+ "text" : "o.pack /d/13"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-10",
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 112.5, 425.0, 83.0, 20.0 ],
+ "style" : "",
+ "text" : "report all pins"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-1",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 45.0, 382.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-4",
+ "maxclass" : "newobj",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 45.0, 413.0, 72.0, 20.0 ],
+ "style" : "",
+ "text" : "qmetro 100"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-35",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 833.0, 532.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-36",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 808.0, 532.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-28",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 778.0, 533.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-30",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 749.0, 532.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-31",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 723.0, 532.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-32",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 698.0, 532.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-24",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 675.0, 533.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-25",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 646.0, 532.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-26",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 620.0, 532.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-27",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 595.0, 532.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-20",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 573.0, 531.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-21",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 544.0, 530.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-22",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 518.0, 530.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-23",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 493.0, 530.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-19",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 469.0, 532.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-18",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 440.0, 531.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-17",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 414.0, 531.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-16",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 384.0, 531.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-81",
+ "maxclass" : "newobj",
+ "numinlets" : 1,
+ "numoutlets" : 18,
+ "outlettype" : [ "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "FullPacket" ],
+ "patching_rect" : [ 384.0, 471.0, 557.0, 22.0 ],
+ "style" : "",
+ "text" : "o.route /0 /1 /2 /3 /4 /5 /6 /7 /8 /9 /10 /11 /12 /13 /14 /15 /16"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-45",
+ "maxclass" : "newobj",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "FullPacket" ],
+ "patching_rect" : [ 384.0, 413.0, 95.0, 22.0 ],
+ "style" : "",
+ "text" : "o.route /d"
+ }
+
+ }
+, {
+ "box" : {
+ "comment" : "",
+ "id" : "obj-6",
+ "maxclass" : "outlet",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 271.0, 499.0, 25.0, 25.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-7",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 220.0, 366.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-9",
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 311.5, 259.0, 313.0, 22.0 ],
+ "style" : "",
+ "text" : "Set digital pins 3, 8, and 9 to HIGH"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-13",
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 45.0, 259.0, 254.0, 22.0 ],
+ "style" : "",
+ "text" : "Set digital pin 0 to HIGH/LOW"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-46",
+ "linecount" : 12,
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 110.0, 37.0, 801.0, 195.0 ],
+ "style" : "",
+ "text" : "DIGITAL\nThe basic digital Arduino functions with the option of using the internal pullup available on most Arduinos. \n\n/d/(pin #)\n\t(no data) = digitalRead with pullup off\n\t/u = digitalRead with pullup on\n\t(value 0/1) = digitalWrite with that value\n\nexample:\n\"/d/1\" performs digitalRead with pullup off on pin 0. \n\"/d/[0-4] 0\" performs digitalWrite LOW on pins 0 through 4."
+ }
+
+ }
+, {
+ "box" : {
+ "comment" : "",
+ "id" : "obj-60",
+ "maxclass" : "inlet",
+ "numinlets" : 0,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 410.0, 365.0, 25.0, 25.0 ],
+ "style" : ""
+ }
+
+ }
+ ],
+ "lines" : [ {
+ "patchline" : {
+ "destination" : [ "obj-4", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-1", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-6", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-11", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-6", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-14", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-6", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-15", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-6", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-2", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-40", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-4", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-6", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-40", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-81", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-45", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-45", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-60", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-2", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-7", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-16", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-17", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 1 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-18", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 2 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-19", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 3 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-20", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 7 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-21", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 6 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-22", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 5 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-23", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 4 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-24", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 11 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-25", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 10 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-26", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 9 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-27", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 8 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-28", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 15 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-30", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 14 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-31", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 13 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-32", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 12 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-36", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 16 ]
+ }
+
+ }
+ ]
+ }
+,
+ "patching_rect" : [ 46.5, 150.0, 86.0, 24.0 ],
+ "saved_object_attributes" : {
+ "description" : "",
+ "digest" : "",
+ "globalpatchername" : "",
+ "style" : "",
+ "tags" : ""
+ }
+,
+ "style" : "",
+ "text" : "p digital"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-47",
+ "maxclass" : "newobj",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patcher" : {
+ "fileversion" : 1,
+ "appversion" : {
+ "major" : 7,
+ "minor" : 0,
+ "revision" : 4,
+ "architecture" : "x86",
+ "modernui" : 1
+ }
+,
+ "rect" : [ 168.0, 44.0, 1041.0, 838.0 ],
+ "bglocked" : 0,
+ "openinpresentation" : 0,
+ "default_fontsize" : 12.0,
+ "default_fontface" : 0,
+ "default_fontname" : "Arial",
+ "gridonopen" : 1,
+ "gridsize" : [ 15.0, 15.0 ],
+ "gridsnaponopen" : 1,
+ "objectsnaponopen" : 1,
+ "statusbarvisible" : 2,
+ "toolbarvisible" : 1,
+ "lefttoolbarpinned" : 0,
+ "toptoolbarpinned" : 0,
+ "righttoolbarpinned" : 0,
+ "bottomtoolbarpinned" : 0,
+ "toolbars_unpinned_last_save" : 0,
+ "tallnewobj" : 0,
+ "boxanimatetime" : 200,
+ "enablehscroll" : 1,
+ "enablevscroll" : 1,
+ "devicewidth" : 0.0,
+ "description" : "",
+ "digest" : "",
+ "tags" : "",
+ "style" : "",
+ "subpatcher_template" : "",
+ "boxes" : [ {
+ "box" : {
+ "fontface" : 0,
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-82",
+ "maxclass" : "o.compose",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 784.5, 290.0, 150.0, 24.0 ],
+ "saved_bundle_data" : [ 35, 98, 117, 110, 100, 108, 101, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 20, 47, 97, 47, 92, 123, 50, 92, 44, 51, 92, 125, 47, 117, 0, 0, 0, 44, 0, 0, 0 ],
+ "saved_bundle_length" : 40,
+ "text" : "/a/\\{2\\,3\\}/u ",
+ "textcolor" : [ 0.188, 0.188, 0.188, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-80",
+ "maxclass" : "o.compose",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 465.0, 288.0, 150.0, 24.0 ],
+ "saved_bundle_data" : [ 35, 98, 117, 110, 100, 108, 101, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 16, 47, 97, 47, 91, 48, 45, 51, 93, 47, 117, 0, 0, 44, 0, 0, 0 ],
+ "saved_bundle_length" : 36,
+ "text" : "/a/[0-3]/u",
+ "textcolor" : [ 0.188, 0.188, 0.188, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-62",
+ "maxclass" : "o.compose",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 253.5, 288.0, 150.0, 24.0 ],
+ "saved_bundle_data" : [ 35, 98, 117, 110, 100, 108, 101, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 12, 47, 97, 47, 42, 0, 0, 0, 0, 44, 0, 0, 0 ],
+ "saved_bundle_length" : 32,
+ "text" : "/a/*",
+ "textcolor" : [ 0.188, 0.188, 0.188, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-61",
+ "maxclass" : "o.compose",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 36.5, 290.0, 150.0, 24.0 ],
+ "saved_bundle_data" : [ 35, 98, 117, 110, 100, 108, 101, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 16, 47, 97, 47, 49, 0, 0, 0, 0, 44, 105, 0, 0, 0, 0, 0, 1 ],
+ "saved_bundle_length" : 36,
+ "text" : "/a/1 : 1",
+ "textcolor" : [ 0.188, 0.188, 0.188, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-63",
+ "linecount" : 2,
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 804.5, 227.0, 222.0, 38.0 ],
+ "style" : "",
+ "text" : "read analog pins 2 and 3 with pullup turned on"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-78",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 784.5, 227.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-79",
+ "maxclass" : "newobj",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 784.5, 257.0, 86.0, 22.0 ],
+ "style" : "",
+ "text" : "qmetro 20"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-9",
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 57.5, 225.0, 187.0, 22.0 ],
+ "style" : "",
+ "text" : "analog write on 1"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-10",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 36.5, 225.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-11",
+ "maxclass" : "newobj",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 36.5, 255.0, 86.0, 22.0 ],
+ "style" : "",
+ "text" : "qmetro 20"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-3",
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 316.5, 342.0, 259.0, 22.0 ],
+ "style" : "",
+ "text" : "to SLIP_oscuino"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-4",
+ "linecount" : 2,
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 495.5, 225.0, 187.0, 38.0 ],
+ "style" : "",
+ "text" : "read analog pins 0-3 with pullup turned on"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-5",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 475.5, 225.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-6",
+ "maxclass" : "newobj",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 475.5, 255.0, 86.0, 22.0 ],
+ "style" : "",
+ "text" : "qmetro 20"
+ }
+
+ }
+, {
+ "box" : {
+ "comment" : "",
+ "id" : "obj-7",
+ "maxclass" : "outlet",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 272.0, 334.0, 25.0, 25.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-15",
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 273.5, 225.0, 187.0, 22.0 ],
+ "style" : "",
+ "text" : "read all analog pins"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-18",
+ "maxclass" : "toggle",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 253.5, 225.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-22",
+ "maxclass" : "newobj",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 253.5, 255.0, 86.0, 22.0 ],
+ "style" : "",
+ "text" : "qmetro 20"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-76",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 584.0, 604.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-77",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 586.0, 488.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[45]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[32]"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-74",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 543.0, 603.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-75",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 545.0, 487.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[44]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[31]"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-72",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 496.0, 604.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-73",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 498.0, 488.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[43]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[30]"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-70",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 448.0, 602.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-71",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 450.0, 486.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[42]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[24]"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-56",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 537.0, 785.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-57",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 503.0, 785.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-58",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 471.0, 786.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-59",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 444.0, 785.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-64",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 535.0, 677.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[37]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[25]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-65",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 499.0, 682.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[38]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[26]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-66",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 471.0, 680.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[39]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[27]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-67",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 444.0, 681.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[40]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[28]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-68",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 411.0, 681.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[41]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[29]"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-69",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 411.0, 785.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-27",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 404.0, 600.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-29",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 371.0, 600.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-30",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 338.0, 600.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-31",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 305.0, 600.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-47",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 272.0, 600.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-48",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 406.0, 484.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[30]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[18]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-49",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 373.0, 484.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[31]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[19]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-50",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 340.0, 484.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[32]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[20]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-51",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 307.0, 484.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[33]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[21]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-52",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 274.0, 484.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[34]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[22]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-53",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 241.0, 484.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[35]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[23]"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-54",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 239.0, 600.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-1",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 375.0, 784.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-2",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 342.0, 784.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-14",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 309.0, 784.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-16",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 276.0, 784.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-17",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 243.0, 784.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-19",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 375.0, 678.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[24]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[12]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-20",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 342.0, 680.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[25]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[13]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-21",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 309.0, 680.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[26]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[14]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-23",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 276.0, 680.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[27]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[15]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-24",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 243.0, 680.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[28]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[16]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-25",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 210.0, 680.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[29]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[17]"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-26",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 210.0, 784.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-13",
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 545.0, 338.0, 447.0, 22.0 ],
+ "style" : "",
+ "text" : "analog readings come out of the SLIP_oscuino patcher"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-32",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 205.0, 599.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-33",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 172.0, 599.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-34",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 139.0, 599.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-35",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 108.0, 596.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-36",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 70.0, 597.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-37",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 207.0, 483.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[12]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[6]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-38",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 174.0, 483.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[13]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[7]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-39",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 141.0, 483.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[14]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[8]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-40",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 108.0, 483.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[15]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[9]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-41",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 75.0, 483.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[16]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[10]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-42",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 42.0, 483.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[17]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[11]"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-43",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 41.0, 597.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-44",
+ "linecount" : 2,
+ "maxclass" : "newobj",
+ "numinlets" : 1,
+ "numoutlets" : 17,
+ "outlettype" : [ "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "FullPacket" ],
+ "patching_rect" : [ 40.0, 426.0, 599.0, 38.0 ],
+ "style" : "",
+ "text" : "o.route /0/u /1/u /2/u /3/u /4/u /5/u /6/u /7/u /8/u /9/u /10/u /11/u /12/u /13/u /14/u /15/u"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-111",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 180.0, 783.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-110",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 144.0, 783.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-109",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 111.0, 783.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-108",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 78.0, 783.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-107",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 45.0, 783.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-106",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 177.0, 679.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[18]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[5]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-105",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 144.0, 679.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[19]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[4]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-104",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 111.0, 679.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[20]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[3]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-103",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 78.0, 679.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[21]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[2]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-102",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 45.0, 679.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[22]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a[1]"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "id" : "obj-101",
+ "maxclass" : "live.slider",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "float" ],
+ "parameter_enable" : 1,
+ "patching_rect" : [ 12.0, 679.0, 34.0, 95.0 ],
+ "saved_attribute_attributes" : {
+ "valueof" : {
+ "parameter_longname" : "a[23]",
+ "parameter_shortname" : "a",
+ "parameter_type" : 0,
+ "parameter_mmax" : 1023.0,
+ "parameter_unitstyle" : 0
+ }
+
+ }
+,
+ "varname" : "a"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-84",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 12.0, 783.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-81",
+ "maxclass" : "newobj",
+ "numinlets" : 1,
+ "numoutlets" : 18,
+ "outlettype" : [ "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "", "FullPacket" ],
+ "patching_rect" : [ 17.0, 639.0, 557.0, 22.0 ],
+ "style" : "",
+ "text" : "o.route /0 /1 /2 /3 /4 /5 /6 /7 /8 /9 /10 /11 /12 /13 /14 /15 /16"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-45",
+ "maxclass" : "newobj",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "", "FullPacket" ],
+ "patching_rect" : [ 40.0, 380.0, 95.0, 22.0 ],
+ "style" : "",
+ "text" : "o.route /a"
+ }
+
+ }
+, {
+ "box" : {
+ "comment" : "",
+ "id" : "obj-60",
+ "maxclass" : "inlet",
+ "numinlets" : 0,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 40.0, 338.0, 25.0, 25.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-46",
+ "linecount" : 12,
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 24.0, 6.0, 792.0, 195.0 ],
+ "style" : "",
+ "text" : "ANALOG\nThese are the basic analog Arduino functions with the option of using the internal pullup available on most Arduinos. All analog pins can be used as digital outputs also. \n\n/a/(pin #)\n\t(no data) = analogRead with pullup off\n\t/u = analogRead with pullup on\n\t(value 0/1) = digitalWrite with that value\n\nexample:\n\"/a/0/u\" performs analogRead with pullup on on pin 0. \n\"/a/8 1\" performs digitalWrite on pin 8 with HIGH."
+ }
+
+ }
+ ],
+ "lines" : [ {
+ "patchline" : {
+ "destination" : [ "obj-11", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-10", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-84", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-101", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-107", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-102", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-108", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-103", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-109", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-104", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-110", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-105", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-111", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-106", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-61", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-11", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-22", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-18", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-1", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-19", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-2", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-20", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-14", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-21", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-62", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-22", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-16", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-23", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-17", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-24", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-26", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-25", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-32", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-37", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-33", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-38", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-34", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-39", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-35", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-40", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-36", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-41", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-43", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-42", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-37", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-44", 5 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-38", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-44", 4 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-39", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-44", 3 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-40", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-44", 2 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-41", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-44", 1 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-42", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-44", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-48", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-44", 11 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-49", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-44", 10 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-50", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-44", 9 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-51", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-44", 8 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-52", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-44", 7 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-53", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-44", 6 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-71", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-44", 12 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-73", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-44", 13 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-75", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-44", 14 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-77", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-44", 15 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-81", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-44", 16 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-44", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-45", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-27", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-48", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-29", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-49", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-6", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-5", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-30", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-50", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-31", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-51", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-47", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-52", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-54", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-53", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-80", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-6", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-45", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-60", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-7", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-61", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-7", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-62", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-56", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-64", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-57", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-65", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-58", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-66", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-59", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-67", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-69", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-68", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-70", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-71", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-72", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-73", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-74", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-75", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-76", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-77", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-79", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-78", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-82", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-79", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-7", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-80", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-101", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-102", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 1 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-103", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 2 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-104", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 3 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-105", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 4 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-106", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 5 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-19", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 11 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-20", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 10 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-21", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 9 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-23", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 8 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-24", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 7 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-25", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 6 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-64", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 16 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-65", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 15 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-66", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 14 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-67", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 13 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-68", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-81", 12 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-7", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-82", 0 ]
+ }
+
+ }
+ ]
+ }
+,
+ "patching_rect" : [ 165.0, 149.0, 78.0, 24.0 ],
+ "saved_object_attributes" : {
+ "description" : "",
+ "digest" : "",
+ "globalpatchername" : "",
+ "style" : "",
+ "tags" : ""
+ }
+,
+ "style" : "",
+ "text" : "p analog"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-27",
+ "linecount" : 3,
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 15.0, 35.0, 844.0, 54.0 ],
+ "style" : "",
+ "text" : "oscuino sends and receives OSC bundles over Ethernet UDP to and from an Arduino or Teensy\nrunning the oscuinoSerial or oscuino Ethernet Sketch \n\n"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-91",
+ "maxclass" : "newobj",
+ "numinlets" : 0,
+ "numoutlets" : 0,
+ "patcher" : {
+ "fileversion" : 1,
+ "appversion" : {
+ "major" : 7,
+ "minor" : 0,
+ "revision" : 4,
+ "architecture" : "x86",
+ "modernui" : 1
+ }
+,
+ "rect" : [ 25.0, 69.0, 738.0, 421.0 ],
+ "bglocked" : 0,
+ "openinpresentation" : 0,
+ "default_fontsize" : 14.0,
+ "default_fontface" : 0,
+ "default_fontname" : "Andale Mono",
+ "gridonopen" : 1,
+ "gridsize" : [ 5.0, 5.0 ],
+ "gridsnaponopen" : 1,
+ "objectsnaponopen" : 1,
+ "statusbarvisible" : 2,
+ "toolbarvisible" : 1,
+ "lefttoolbarpinned" : 0,
+ "toptoolbarpinned" : 0,
+ "righttoolbarpinned" : 0,
+ "bottomtoolbarpinned" : 0,
+ "toolbars_unpinned_last_save" : 0,
+ "tallnewobj" : 0,
+ "boxanimatetime" : 200,
+ "enablehscroll" : 1,
+ "enablevscroll" : 1,
+ "devicewidth" : 0.0,
+ "description" : "",
+ "digest" : "",
+ "tags" : "",
+ "style" : "",
+ "subpatcher_template" : "",
+ "boxes" : [ {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-2",
+ "linecount" : 24,
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 15.0, 20.0, 697.0, 386.0 ],
+ "style" : "",
+ "text" : "/*\n Written by Yotam Mann, The Center for New Music and Audio Technologies,\n University of California, Berkeley. Copyright (c) 2012, The Regents of\n the University of California (Regents).\n \n Permission to use, copy, modify, distribute, and distribute modified versions\n of this software and its documentation without fee and without a signed\n licensing agreement, is hereby granted, provided that the above copyright\n notice, this paragraph and the following two paragraphs appear in all copies,\n modifications, and distributions.\n \n IN NO EVENT SHALL REGENTS BE LIABLE TO ANY PARTY FOR DIRECT, INDIRECT,\n SPECIAL, INCIDENTAL, OR CONSEQUENTIAL DAMAGES, INCLUDING LOST PROFITS, ARISING\n OUT OF THE USE OF THIS SOFTWARE AND ITS DOCUMENTATION, EVEN IF REGENTS HAS\n BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.\n \n REGENTS SPECIFICALLY DISCLAIMS ANY WARRANTIES, INCLUDING, BUT NOT LIMITED TO,\n THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR\n PURPOSE. THE SOFTWARE AND ACCOMPANYING DOCUMENTATION, IF ANY, PROVIDED\n HEREUNDER IS PROVIDED \"AS IS\". REGENTS HAS NO OBLIGATION TO PROVIDE\n MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.\n \n For bug reports and feature requests please email me at yotam@cnmat.berkeley.edu\n */"
+ }
+
+ }
+ ],
+ "lines" : [ ]
+ }
+,
+ "patching_rect" : [ 749.5, 10.0, 111.0, 24.0 ],
+ "saved_object_attributes" : {
+ "description" : "",
+ "digest" : "",
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "globalpatchername" : "",
+ "style" : "",
+ "tags" : ""
+ }
+,
+ "style" : "",
+ "text" : "p disclaimer"
+ }
+
+ }
+ ],
+ "lines" : [ {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-3", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-1", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-6", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-3", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-3", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "midpoints" : [ 174.5, 202.0, 515.5, 202.0 ],
+ "source" : [ "obj-47", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-3", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "midpoints" : [ 721.5, 155.0, 698.0, 155.0, 698.0, 218.0, 515.5, 218.0 ],
+ "source" : [ "obj-5", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-3", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "midpoints" : [ 56.0, 202.0, 515.5, 202.0 ],
+ "source" : [ "obj-52", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-3", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "midpoints" : [ 284.0, 202.0, 515.5, 202.0 ],
+ "source" : [ "obj-58", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-1", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "midpoints" : [ 515.5, 314.0, 490.0, 314.0, 490.0, 182.0, 489.0, 182.0, 489.0, 119.0, 515.5, 119.0 ],
+ "source" : [ "obj-6", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-2", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-6", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-47", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "midpoints" : [ 515.5, 323.0, 147.0, 323.0, 147.0, 121.0, 174.5, 121.0 ],
+ "source" : [ "obj-6", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-52", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "midpoints" : [ 515.5, 323.0, 24.0, 323.0, 24.0, 120.0, 56.0, 120.0 ],
+ "source" : [ "obj-6", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-58", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "midpoints" : [ 515.5, 323.0, 261.0, 323.0, 261.0, 182.0, 261.0, 182.0, 261.0, 121.0, 284.0, 121.0 ],
+ "source" : [ "obj-6", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "color" : [ 1.0, 0.8, 0.4, 1.0 ],
+ "destination" : [ "obj-3", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "midpoints" : [ 721.5, 218.0, 515.5, 218.0 ],
+ "source" : [ "obj-9", 0 ]
+ }
+
+ }
+ ],
+ "parameters" : {
+ "obj-1::obj-21" : [ "a[52]", "a", 0 ],
+ "obj-47::obj-49" : [ "a[31]", "a", 0 ],
+ "obj-1::obj-105" : [ "a[57]", "a", 0 ],
+ "obj-47::obj-71" : [ "a[42]", "a", 0 ],
+ "obj-47::obj-21" : [ "a[26]", "a", 0 ],
+ "obj-47::obj-39" : [ "a[14]", "a", 0 ],
+ "obj-47::obj-66" : [ "a[39]", "a", 0 ],
+ "obj-47::obj-77" : [ "a[45]", "a", 0 ],
+ "obj-1::obj-23" : [ "a[53]", "a", 0 ],
+ "obj-47::obj-19" : [ "a[24]", "a", 0 ],
+ "obj-1::obj-104" : [ "a[58]", "a", 0 ],
+ "obj-47::obj-23" : [ "a[27]", "a", 0 ],
+ "obj-47::obj-40" : [ "a[15]", "a", 0 ],
+ "obj-47::obj-67" : [ "a[40]", "a", 0 ],
+ "obj-47::obj-50" : [ "a[32]", "a", 0 ],
+ "obj-47::obj-37" : [ "a[12]", "a", 0 ],
+ "obj-1::obj-24" : [ "a[54]", "a", 0 ],
+ "obj-47::obj-73" : [ "a[43]", "a", 0 ],
+ "obj-1::obj-103" : [ "a[59]", "a", 0 ],
+ "obj-47::obj-51" : [ "a[33]", "a", 0 ],
+ "obj-47::obj-52" : [ "a[34]", "a", 0 ],
+ "obj-47::obj-24" : [ "a[28]", "a", 0 ],
+ "obj-47::obj-41" : [ "a[16]", "a", 0 ],
+ "obj-47::obj-68" : [ "a[41]", "a", 0 ],
+ "obj-47::obj-48" : [ "a[30]", "a", 0 ],
+ "obj-47::obj-106" : [ "a[18]", "a", 0 ],
+ "obj-1::obj-25" : [ "a[55]", "a", 0 ],
+ "obj-1::obj-19" : [ "a[50]", "a", 0 ],
+ "obj-47::obj-105" : [ "a[19]", "a", 0 ],
+ "obj-47::obj-104" : [ "a[20]", "a", 0 ],
+ "obj-47::obj-103" : [ "a[21]", "a", 0 ],
+ "obj-1::obj-102" : [ "a[60]", "a", 0 ],
+ "obj-47::obj-64" : [ "a[37]", "a", 0 ],
+ "obj-1::obj-101" : [ "a[61]", "a", 0 ],
+ "obj-47::obj-53" : [ "a[35]", "a", 0 ],
+ "obj-1::obj-20" : [ "a[51]", "a", 0 ],
+ "obj-47::obj-25" : [ "a[29]", "a", 0 ],
+ "obj-47::obj-75" : [ "a[44]", "a", 0 ],
+ "obj-47::obj-42" : [ "a[17]", "a", 0 ],
+ "obj-1::obj-106" : [ "a[56]", "a", 0 ],
+ "obj-47::obj-102" : [ "a[22]", "a", 0 ],
+ "obj-47::obj-20" : [ "a[25]", "a", 0 ],
+ "obj-47::obj-101" : [ "a[23]", "a", 0 ],
+ "obj-47::obj-38" : [ "a[13]", "a", 0 ],
+ "obj-47::obj-65" : [ "a[38]", "a", 0 ]
+ }
+,
+ "dependency_cache" : [ {
+ "name" : "o.io.udp.maxpat",
+ "bootpath" : "~/Documents/Max/Packages/o.io/experimental/Protocols/udp",
+ "type" : "JSON",
+ "implicit" : 1
+ }
+, {
+ "name" : "o.route.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.compose.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.pack.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.display.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.downcast.mxo",
+ "type" : "iLaX"
+ }
+ ],
+ "embedsnapshot" : 0
+ }
+
+}
diff --git a/lib/OSC/Applications/MaxMSP/examples/UDPReceive.maxpat b/lib/OSC/Applications/MaxMSP/examples/UDPReceive.maxpat
new file mode 100644
index 0000000..5598d31
--- /dev/null
+++ b/lib/OSC/Applications/MaxMSP/examples/UDPReceive.maxpat
@@ -0,0 +1,319 @@
+{
+ "patcher" : {
+ "fileversion" : 1,
+ "appversion" : {
+ "major" : 7,
+ "minor" : 0,
+ "revision" : 4,
+ "architecture" : "x86",
+ "modernui" : 1
+ }
+,
+ "rect" : [ 334.0, 78.0, 1072.0, 480.0 ],
+ "bglocked" : 0,
+ "openinpresentation" : 0,
+ "default_fontsize" : 12.0,
+ "default_fontface" : 0,
+ "default_fontname" : "Arial",
+ "gridonopen" : 1,
+ "gridsize" : [ 15.0, 15.0 ],
+ "gridsnaponopen" : 1,
+ "objectsnaponopen" : 1,
+ "statusbarvisible" : 2,
+ "toolbarvisible" : 1,
+ "lefttoolbarpinned" : 0,
+ "toptoolbarpinned" : 0,
+ "righttoolbarpinned" : 0,
+ "bottomtoolbarpinned" : 0,
+ "toolbars_unpinned_last_save" : 0,
+ "tallnewobj" : 0,
+ "boxanimatetime" : 200,
+ "enablehscroll" : 1,
+ "enablevscroll" : 1,
+ "devicewidth" : 0.0,
+ "description" : "",
+ "digest" : "",
+ "tags" : "",
+ "style" : "",
+ "subpatcher_template" : "",
+ "boxes" : [ {
+ "box" : {
+ "fontface" : 0,
+ "fontsize" : 12.0,
+ "id" : "obj-5",
+ "maxclass" : "o.display",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 183.5, 341.0, 150.0, 34.0 ],
+ "textcolor" : [ 1.0, 1.0, 1.0, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-18",
+ "linecount" : 2,
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 498.0, 91.0, 150.0, 33.0 ],
+ "style" : "",
+ "text" : "control Arduino square wave tone on pin 3"
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-15",
+ "maxclass" : "o.message",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 406.0, 168.0, 150.0, 22.0 ],
+ "text" : "/tone/3",
+ "textcolor" : [ 0.0, 0.0, 0.0, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-12",
+ "maxclass" : "newobj",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 134.0, 127.0, 34.0, 22.0 ],
+ "style" : "",
+ "text" : "mtof"
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-11",
+ "maxclass" : "kslider",
+ "numinlets" : 2,
+ "numoutlets" : 2,
+ "outlettype" : [ "int", "int" ],
+ "parameter_enable" : 0,
+ "patching_rect" : [ 132.0, 65.0, 336.0, 53.0 ],
+ "presentation_rect" : [ 0.0, 0.0, 336.0, 53.0 ],
+ "style" : "",
+ "varname" : "kslider"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-9",
+ "maxclass" : "message",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 242.0, 140.0, 32.5, 22.0 ],
+ "style" : "",
+ "text" : "220"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-8",
+ "maxclass" : "message",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 184.0, 137.0, 34.0, 22.0 ],
+ "style" : "",
+ "text" : "440."
+ }
+
+ }
+, {
+ "box" : {
+ "id" : "obj-4",
+ "maxclass" : "button",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "bang" ],
+ "patching_rect" : [ 402.0, 137.0, 20.0, 20.0 ],
+ "style" : ""
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-3",
+ "linecount" : 3,
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 489.0, 279.0, 154.0, 47.0 ],
+ "style" : "",
+ "text" : "8888 is the port sent to on the Arduino node 128.32.122.252"
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-20",
+ "maxclass" : "o.message",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 235.0, 234.0, 150.0, 22.0 ],
+ "text" : "/tone/3 130.813 \n",
+ "textcolor" : [ 0.0, 0.0, 0.0, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-6",
+ "maxclass" : "o.message",
+ "numinlets" : 2,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 185.0, 191.0, 150.0, 22.0 ],
+ "text" : "/tone/3 \"$1\" ",
+ "textcolor" : [ 0.0, 0.0, 0.0, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-26",
+ "maxclass" : "newobj",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 183.5, 290.0, 288.0, 24.0 ],
+ "style" : "",
+ "text" : "o.io.udp 128.32.122.252 8888 9999"
+ }
+
+ }
+ ],
+ "lines" : [ {
+ "patchline" : {
+ "destination" : [ "obj-12", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-11", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-6", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-12", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-26", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-15", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-5", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-26", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-15", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-4", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-20", 1 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-6", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-26", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-6", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-6", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-8", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-6", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-9", 0 ]
+ }
+
+ }
+ ],
+ "dependency_cache" : [ {
+ "name" : "o.io.udp.maxpat",
+ "bootpath" : "~/Documents/Max/Packages/o.io/experimental/Protocols/udp",
+ "type" : "JSON",
+ "implicit" : 1
+ }
+, {
+ "name" : "o.message.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.display.mxo",
+ "type" : "iLaX"
+ }
+ ],
+ "embedsnapshot" : 0
+ }
+
+}
diff --git a/lib/OSC/Applications/MaxMSP/examples/UDPSend.maxpat b/lib/OSC/Applications/MaxMSP/examples/UDPSend.maxpat
new file mode 100644
index 0000000..93c1234
--- /dev/null
+++ b/lib/OSC/Applications/MaxMSP/examples/UDPSend.maxpat
@@ -0,0 +1,159 @@
+{
+ "patcher" : {
+ "fileversion" : 1,
+ "appversion" : {
+ "major" : 7,
+ "minor" : 0,
+ "revision" : 4,
+ "architecture" : "x86",
+ "modernui" : 1
+ }
+,
+ "rect" : [ 443.0, 218.0, 1072.0, 480.0 ],
+ "bglocked" : 0,
+ "openinpresentation" : 0,
+ "default_fontsize" : 12.0,
+ "default_fontface" : 0,
+ "default_fontname" : "Arial",
+ "gridonopen" : 1,
+ "gridsize" : [ 15.0, 15.0 ],
+ "gridsnaponopen" : 1,
+ "objectsnaponopen" : 1,
+ "statusbarvisible" : 2,
+ "toolbarvisible" : 1,
+ "lefttoolbarpinned" : 0,
+ "toptoolbarpinned" : 0,
+ "righttoolbarpinned" : 0,
+ "bottomtoolbarpinned" : 0,
+ "toolbars_unpinned_last_save" : 0,
+ "tallnewobj" : 0,
+ "boxanimatetime" : 200,
+ "enablehscroll" : 1,
+ "enablevscroll" : 1,
+ "devicewidth" : 0.0,
+ "description" : "",
+ "digest" : "",
+ "tags" : "",
+ "style" : "",
+ "subpatcher_template" : "",
+ "boxes" : [ {
+ "box" : {
+ "fontface" : 0,
+ "fontsize" : 12.0,
+ "id" : "obj-8",
+ "maxclass" : "o.display",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 277.0, 243.0, 150.0, 34.0 ],
+ "textcolor" : [ 1.0, 1.0, 1.0, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontface" : 0,
+ "fontsize" : 12.0,
+ "id" : "obj-6",
+ "maxclass" : "o.display",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 91.0, 243.0, 150.0, 34.0 ],
+ "textcolor" : [ 1.0, 1.0, 1.0, 1.0 ]
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-2",
+ "maxclass" : "newobj",
+ "numinlets" : 1,
+ "numoutlets" : 2,
+ "outlettype" : [ "FullPacket", "FullPacket" ],
+ "patching_rect" : [ 91.0, 149.0, 97.0, 22.0 ],
+ "style" : "",
+ "text" : "o.if exists(/units)"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Arial",
+ "fontsize" : 12.0,
+ "id" : "obj-4",
+ "linecount" : 2,
+ "maxclass" : "comment",
+ "numinlets" : 1,
+ "numoutlets" : 0,
+ "patching_rect" : [ 95.0, 62.0, 150.0, 33.0 ],
+ "style" : "",
+ "text" : "Set udp port, send and receive port respectively"
+ }
+
+ }
+, {
+ "box" : {
+ "fontname" : "Andale Mono",
+ "fontsize" : 14.0,
+ "id" : "obj-26",
+ "maxclass" : "newobj",
+ "numinlets" : 1,
+ "numoutlets" : 1,
+ "outlettype" : [ "" ],
+ "patching_rect" : [ 91.0, 107.0, 288.0, 24.0 ],
+ "style" : "",
+ "text" : "o.io.udp 128.32.122.26 8888 9999"
+ }
+
+ }
+ ],
+ "lines" : [ {
+ "patchline" : {
+ "destination" : [ "obj-6", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-2", 0 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-8", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-2", 1 ]
+ }
+
+ }
+, {
+ "patchline" : {
+ "destination" : [ "obj-2", 0 ],
+ "disabled" : 0,
+ "hidden" : 0,
+ "source" : [ "obj-26", 0 ]
+ }
+
+ }
+ ],
+ "dependency_cache" : [ {
+ "name" : "o.io.udp.maxpat",
+ "bootpath" : "~/Documents/Max/Packages/o.io/experimental/Protocols/udp",
+ "type" : "JSON",
+ "implicit" : 1
+ }
+, {
+ "name" : "o.if.mxo",
+ "type" : "iLaX"
+ }
+, {
+ "name" : "o.display.mxo",
+ "type" : "iLaX"
+ }
+ ],
+ "embedsnapshot" : 0
+ }
+
+}
diff --git a/lib/OSC/Applications/PD/SerialOscuino.pd b/lib/OSC/Applications/PD/SerialOscuino.pd
new file mode 100644
index 0000000..1d94544
--- /dev/null
+++ b/lib/OSC/Applications/PD/SerialOscuino.pd
@@ -0,0 +1,312 @@
+#N canvas 33 23 1015 763 10;
+#X msg 272 58 /a/*;
+#X msg 612 30 /s/a;
+#X msg 569 30 /s/d;
+#X msg 675 30 /s/m;
+#X obj 169 339 tgl 15 0 empty empty empty 17 7 0 10 -262144 -1 -1 0
+1;
+#X obj 189 339 tgl 15 0 empty empty empty 17 7 0 10 -262144 -1 -1 0
+1;
+#X obj 210 339 tgl 15 0 empty empty empty 17 7 0 10 -262144 -1 -1 0
+1;
+#X obj 231 339 tgl 15 0 empty empty empty 17 7 0 10 -262144 -1 -1 0
+1;
+#X msg 439 45 /d/[1-3];
+#X obj 27 451 vsl 15 128 0 1023 0 0 empty empty empty 0 -9 0 10 -262144
+-1 -1 0 1;
+#X obj 272 10 tgl 15 0 empty empty empty 17 7 0 10 -262144 -1 -1 0
+1;
+#X obj 107 452 vsl 15 128 0 1023 0 0 empty empty empty 0 -9 0 10 -262144
+-1 -1 0 1;
+#X obj 47 451 vsl 15 128 0 1023 0 0 empty empty empty 0 -9 0 10 -262144
+-1 -1 0 1;
+#X obj 87 451 vsl 15 128 0 1023 0 0 empty empty empty 0 -9 0 10 -262144
+-1 -1 0 1;
+#X obj 67 451 vsl 15 128 0 1023 0 0 empty empty empty 0 -9 0 10 -262144
+-1 -1 0 1;
+#X obj 127 452 vsl 15 128 0 1023 0 0 empty empty empty 0 -9 0 10 -262144
+-1 -1 0 1;
+#X obj 147 452 vsl 15 128 0 1023 0 0 empty empty empty 0 -9 0 10 -262144
+-1 -1 0 1;
+#X obj 167 452 vsl 15 128 0 1023 0 0 empty empty empty 0 -9 0 10 -262144
+-1 -1 0 1;
+#X obj 187 452 vsl 15 128 0 1023 0 0 empty empty empty 0 -9 0 10 -262144
+-1 -1 0 1;
+#X obj 267 452 vsl 15 128 0 1023 0 0 empty empty empty 0 -9 0 10 -262144
+-1 -1 0 1;
+#X obj 207 452 vsl 15 128 0 1023 0 0 empty empty empty 0 -9 0 10 -262144
+-1 -1 0 1;
+#X obj 247 452 vsl 15 128 0 1023 0 0 empty empty empty 0 -9 0 10 -262144
+-1 -1 0 1;
+#X obj 227 452 vsl 15 128 0 1023 0 0 empty empty empty 0 -9 0 10 -262144
+-1 -1 0 1;
+#X obj 327 452 vsl 15 128 0 1023 0 0 empty empty empty 0 -9 0 10 -262144
+-1 -1 0 1;
+#X obj 307 452 vsl 15 128 0 1023 0 0 empty empty empty 0 -9 0 10 -262144
+-1 -1 0 1;
+#X obj 287 452 vsl 15 128 0 1023 0 0 empty empty empty 0 -9 0 10 -262144
+-1 -1 0 1;
+#X obj 212 18 tgl 15 0 empty empty empty 17 7 0 10 -262144 -1 -1 0
+1;
+#X msg 212 37 /s/l \$1;
+#X obj 252 339 tgl 15 0 empty empty empty 17 7 0 10 -262144 -1 -1 0
+1;
+#X obj 273 339 tgl 15 0 empty empty empty 17 7 0 10 -262144 -1 -1 0
+1;
+#X obj 294 339 tgl 15 0 empty empty empty 17 7 0 10 -262144 -1 -1 0
+1;
+#X obj 314 339 tgl 15 0 empty empty empty 17 7 0 10 -262144 -1 -1 0
+1;
+#X obj 335 339 tgl 15 0 empty empty empty 17 7 0 10 -262144 -1 -1 0
+1;
+#X obj 356 339 tgl 15 0 empty empty empty 17 7 0 10 -262144 -1 -1 0
+1;
+#X obj 377 339 tgl 15 0 empty empty empty 17 7 0 10 -262144 -1 -1 0
+1;
+#X obj 398 339 tgl 15 0 empty empty empty 17 7 0 10 -262144 -1 -1 0
+1;
+#X obj 419 339 tgl 15 0 empty empty empty 17 7 0 10 -262144 -1 -1 0
+1;
+#X obj 440 339 tgl 15 0 empty empty empty 17 7 0 10 -262144 -1 -1 0
+1;
+#X obj 460 339 tgl 15 0 empty empty empty 17 7 0 10 -262144 -1 -1 0
+1;
+#X obj 481 339 tgl 15 0 empty empty empty 17 7 0 10 -262144 -1 -1 0
+1;
+#X obj 333 117 o.io.slipserial;
+#X obj 502 339 tgl 15 0 empty empty empty 17 7 0 10 -262144 -1 -1 0
+1;
+#X obj 523 339 tgl 15 0 empty empty empty 17 7 0 10 -262144 -1 -1 0
+1;
+#X obj 544 339 tgl 15 0 empty empty empty 17 7 0 10 -262144 -1 -1 0
+1;
+#X obj 565 339 tgl 15 0 empty empty empty 17 7 0 10 -262144 -1 -1 0
+1;
+#X obj 694 452 vsl 15 128 0 1023 0 0 empty empty empty 0 -9 0 10 -262144
+-1 -1 0 1;
+#X obj 774 452 vsl 15 128 0 1023 0 0 empty empty empty 0 -9 0 10 -262144
+-1 -1 0 1;
+#X obj 714 452 vsl 15 128 0 1023 0 0 empty empty empty 0 -9 0 10 -262144
+-1 -1 0 1;
+#X obj 754 452 vsl 15 128 0 1023 0 0 empty empty empty 0 -9 0 10 -262144
+-1 -1 0 1;
+#X obj 734 452 vsl 15 128 0 1023 0 0 empty empty empty 0 -9 0 10 -262144
+-1 -1 0 1;
+#X obj 794 452 vsl 15 128 0 1023 0 0 empty empty empty 0 -9 0 10 -262144
+-1 -1 0 1;
+#X obj 814 452 vsl 15 128 0 1023 0 0 empty empty empty 0 -9 0 10 -262144
+-1 -1 0 1;
+#X obj 834 452 vsl 15 128 0 1023 0 0 empty empty empty 0 -9 0 10 -262144
+-1 -1 0 1;
+#X obj 854 452 vsl 15 128 0 1023 0 0 empty empty empty 0 -9 0 10 -262144
+-1 -1 0 1;
+#X obj 874 452 vsl 15 128 0 1023 0 0 empty empty empty 0 -9 0 10 -262144
+-1 -1 0 1;
+#X obj 914 452 vsl 15 128 0 1023 0 0 empty empty empty 0 -9 0 10 -262144
+-1 -1 0 1;
+#X obj 894 452 vsl 15 128 0 1023 0 0 empty empty empty 0 -9 0 10 -262144
+-1 -1 0 1;
+#X msg 786 80 /c/*;
+#X obj 360 452 vsl 15 128 0 1023 0 0 empty empty empty 0 -9 0 10 -262144
+-1 -1 0 1;
+#X obj 439 452 vsl 15 128 0 1023 0 0 empty empty empty 0 -9 0 10 -262144
+-1 -1 0 1;
+#X obj 380 452 vsl 15 128 0 1023 0 0 empty empty empty 0 -9 0 10 -262144
+-1 -1 0 1;
+#X obj 420 452 vsl 15 128 0 1023 0 0 empty empty empty 0 -9 0 10 -262144
+-1 -1 0 1;
+#X obj 400 452 vsl 15 128 0 1023 0 0 empty empty empty 0 -9 0 10 -262144
+-1 -1 0 1;
+#X obj 459 452 vsl 15 128 0 1023 0 0 empty empty empty 0 -9 0 10 -262144
+-1 -1 0 1;
+#X obj 479 452 vsl 15 128 0 1023 0 0 empty empty empty 0 -9 0 10 -262144
+-1 -1 0 1;
+#X obj 499 452 vsl 15 128 0 1023 0 0 empty empty empty 0 -9 0 10 -262144
+-1 -1 0 1;
+#X obj 519 452 vsl 15 128 0 1023 0 0 empty empty empty 0 -9 0 10 -262144
+-1 -1 0 1;
+#X obj 599 452 vsl 15 128 0 1023 0 0 empty empty empty 0 -9 0 10 -262144
+-1 -1 0 1;
+#X obj 539 452 vsl 15 128 0 1023 0 0 empty empty empty 0 -9 0 10 -262144
+-1 -1 0 1;
+#X obj 579 452 vsl 15 128 0 1023 0 0 empty empty empty 0 -9 0 10 -262144
+-1 -1 0 1;
+#X obj 559 452 vsl 15 128 0 1023 0 0 empty empty empty 0 -9 0 10 -262144
+-1 -1 0 1;
+#X obj 659 452 vsl 15 128 0 1023 0 0 empty empty empty 0 -9 0 10 -262144
+-1 -1 0 1;
+#X obj 639 452 vsl 15 128 0 1023 0 0 empty empty empty 0 -9 0 10 -262144
+-1 -1 0 1;
+#X obj 619 452 vsl 15 128 0 1023 0 0 empty empty empty 0 -9 0 10 -262144
+-1 -1 0 1;
+#X msg 333 64 /a/*/u;
+#X text 340 48 Pull up;
+#X text 567 10 How many pins?;
+#X text 675 9 How many milliseconds ?;
+#X text 215 -1 LED;
+#X text 749 369 Touch Pins on Teensy 3;
+#X text 341 211 System message responses;
+#X text 356 370 Analog Values;
+#X text 27 369 Analog Values with Pullups Enabled;
+#N canvas 0 50 450 278 (subpatch) 0;
+#X array AnalogArray 16 float 2 black black;
+#X coords 0 1023 16 0 200 140 1;
+#X restore 31 605 graph;
+#X obj 272 35 metro 60;
+#X obj 786 39 tgl 15 0 empty empty empty 17 7 0 10 -262144 -1 -1 0
+1;
+#X obj 786 59 metro 60;
+#X obj 200 214 print;
+#X obj 253 115 print;
+#X msg 459 107 devicename /dev/tty.usbmodem122611 \, baud 9600 \, pollintervall
+4 \, verbose 1;
+#X obj 333 96 mrpeach/packOSC;
+#X obj 333 138 mrpeach/unpackOSC;
+#X obj 333 159 mrpeach/routeOSC /a /d /s /c;
+#X obj 169 297 mrpeach/routeOSC /1 /2 /3 /4 /5 /6 /7 /8 /9 /10 /11
+/12 /13 /14 /15 /16 /17 /18 /19 /20, f 70;
+#X obj 694 387 mrpeach/routeOSC /0 /1 /16 /17 /18 /19 /22 /23 /25 /32
+/33 /15, f 40;
+#X obj 359 387 mrpeach/routeOSC /1 /2 /3 /4 /5 /6 /7 /8 /9 /10 /11
+/12 /13 /14 /15 /16, f 54;
+#X obj 27 387 mrpeach/routeOSC /0/u /1/u /2/u /3/u /4/u /5/u /6/u /7/u
+/8/u /9/u /10/u /11/u /12/u /13/u /14/u /15/u, f 54;
+#X obj 346 229 cyclone/prepend set;
+#X obj 536 206 cyclone/prepend set;
+#X text 291 8 Retrieve analog value each 60ms, f 15;
+#X text 436 2 get digital pins 1 to 3 status, f 11;
+#X text 741 25 get Teensy 3 Touch each 60ms;
+#N canvas 0 94 450 300 fillArray 0;
+#X obj 60 223 send AnalogArray;
+#X obj 60 142 mrpeach/routeOSC /1 /2 /3 /4 /5 /6 /7 /8 /9 /10 /11 /12
+/13 /14 /15 /16, f 54;
+#X obj 60 194 cyclone/funnel 16;
+#X obj 60 120 inlet;
+#X connect 1 0 2 0;
+#X connect 1 1 2 1;
+#X connect 1 2 2 2;
+#X connect 1 3 2 3;
+#X connect 1 4 2 4;
+#X connect 1 5 2 5;
+#X connect 1 6 2 6;
+#X connect 1 7 2 7;
+#X connect 1 8 2 8;
+#X connect 1 9 2 9;
+#X connect 1 10 2 10;
+#X connect 1 11 2 11;
+#X connect 1 12 2 12;
+#X connect 1 13 2 13;
+#X connect 1 14 2 14;
+#X connect 1 15 2 15;
+#X connect 2 0 0 0;
+#X connect 3 0 1 0;
+#X restore 348 423 pd fillArray;
+#X msg 536 226;
+#X msg 346 252;
+#X text 211 279 Digital pins state;
+#X obj 200 194 spigot;
+#X obj 234 171 tgl 15 0 empty empty empty 17 7 0 10 -262144 -1 -1 0
+1;
+#X obj 668 651 cnv 15 400 80 empty empty empty 20 12 0 14 -258113 -66577
+0;
+#X text 26 71 Oscuino Serial Adrian Freed 2013;
+#X text 762 229 - comport;
+#X text 763 213 - cyclone;
+#X obj 530 148 import mrpeach;
+#X text 763 197 - mrpeach osc slipenc and slipdec;
+#X text 650 153 This patch depends on several third party externals
+available in PD-extended (deprecated?) \, Purr \, or through deken
+plugin (Help -> Find externals):;
+#X connect 0 0 90 0;
+#X connect 1 0 90 0;
+#X connect 2 0 90 0;
+#X connect 3 0 90 0;
+#X connect 8 0 90 0;
+#X connect 10 0 84 0;
+#X connect 26 0 27 0;
+#X connect 27 0 90 0;
+#X connect 40 0 91 0;
+#X connect 40 0 106 0;
+#X connect 57 0 90 0;
+#X connect 74 0 90 0;
+#X connect 84 0 0 0;
+#X connect 85 0 86 0;
+#X connect 86 0 57 0;
+#X connect 89 0 40 1;
+#X connect 90 0 40 0;
+#X connect 91 0 92 0;
+#X connect 92 0 96 0;
+#X connect 92 1 93 0;
+#X connect 92 2 97 0;
+#X connect 92 3 94 0;
+#X connect 92 4 98 0;
+#X connect 93 0 4 0;
+#X connect 93 1 5 0;
+#X connect 93 2 6 0;
+#X connect 93 3 7 0;
+#X connect 93 4 28 0;
+#X connect 93 5 29 0;
+#X connect 93 6 30 0;
+#X connect 93 7 31 0;
+#X connect 93 8 32 0;
+#X connect 93 9 33 0;
+#X connect 93 10 34 0;
+#X connect 93 11 35 0;
+#X connect 93 12 36 0;
+#X connect 93 13 37 0;
+#X connect 93 14 38 0;
+#X connect 93 15 39 0;
+#X connect 93 16 41 0;
+#X connect 93 17 42 0;
+#X connect 93 18 43 0;
+#X connect 93 19 44 0;
+#X connect 94 0 45 0;
+#X connect 94 1 47 0;
+#X connect 94 2 49 0;
+#X connect 94 3 48 0;
+#X connect 94 4 46 0;
+#X connect 94 5 50 0;
+#X connect 94 6 51 0;
+#X connect 94 7 52 0;
+#X connect 94 8 53 0;
+#X connect 94 9 54 0;
+#X connect 94 10 56 0;
+#X connect 94 11 55 0;
+#X connect 95 0 58 0;
+#X connect 95 1 60 0;
+#X connect 95 2 62 0;
+#X connect 95 3 61 0;
+#X connect 95 4 59 0;
+#X connect 95 5 63 0;
+#X connect 95 6 64 0;
+#X connect 95 7 65 0;
+#X connect 95 8 66 0;
+#X connect 95 9 68 0;
+#X connect 95 10 70 0;
+#X connect 95 11 69 0;
+#X connect 95 12 67 0;
+#X connect 95 13 73 0;
+#X connect 95 14 72 0;
+#X connect 95 15 71 0;
+#X connect 96 0 9 0;
+#X connect 96 1 12 0;
+#X connect 96 2 14 0;
+#X connect 96 3 13 0;
+#X connect 96 4 11 0;
+#X connect 96 5 15 0;
+#X connect 96 6 16 0;
+#X connect 96 7 17 0;
+#X connect 96 8 18 0;
+#X connect 96 9 20 0;
+#X connect 96 10 22 0;
+#X connect 96 11 21 0;
+#X connect 96 12 19 0;
+#X connect 96 13 25 0;
+#X connect 96 14 24 0;
+#X connect 96 15 23 0;
+#X connect 96 16 95 0;
+#X connect 96 16 102 0;
+#X connect 97 0 104 0;
+#X connect 98 0 103 0;
+#X connect 106 0 87 0;
+#X connect 107 0 106 1;
diff --git a/lib/OSC/Applications/PD/o.io.slipserial.pd b/lib/OSC/Applications/PD/o.io.slipserial.pd
new file mode 100644
index 0000000..0d9fea0
--- /dev/null
+++ b/lib/OSC/Applications/PD/o.io.slipserial.pd
@@ -0,0 +1,22 @@
+#N canvas 618 358 756 268 10;
+#X obj 95 179 mrpeach/slipdec 65536;
+#X obj 95 47 mrpeach/slipenc 65536;
+#X obj 359 20 loadbang;
+#X obj 95 22 inlet;
+#X obj 95 206 outlet;
+#X msg 359 83 baud 115200;
+#X obj 261 46 inlet;
+#X msg 318 46 devicename /dev/tty.usbserial-A5002rKU \, pollintervall
+1;
+#X obj 95 135 comport;
+#X obj 134 157 print errors;
+#X connect 0 0 4 0;
+#X connect 1 0 8 0;
+#X connect 2 0 7 0;
+#X connect 2 0 5 0;
+#X connect 3 0 1 0;
+#X connect 5 0 8 0;
+#X connect 6 0 8 0;
+#X connect 7 0 8 0;
+#X connect 8 0 0 0;
+#X connect 8 1 9 0;
diff --git a/lib/OSC/Applications/Processing/SLIPSerialToUDP/GUI.pde b/lib/OSC/Applications/Processing/SLIPSerialToUDP/GUI.pde
new file mode 100644
index 0000000..a1ef8ac
--- /dev/null
+++ b/lib/OSC/Applications/Processing/SLIPSerialToUDP/GUI.pde
@@ -0,0 +1,148 @@
+
+ControlP5 cp5;
+
+void setupGUI() {
+ //the ControlP5 object
+ cp5 = new ControlP5(this);
+
+ //start button
+ cp5.addButton("START")
+ .setPosition(width/2 - 100, height-30)
+ .setSize(200, 20);
+
+ //stop button
+ cp5.addButton("STOP")
+ .setPosition(width/2 - 100, height-30)
+ .setSize(200, 20)
+ .hide();
+
+ //setup the baud list
+ DropdownList baudRate = cp5.addDropdownList("BaudRate")
+ .setPosition(50, 130)
+ .setSize(200, 90)
+ .setItemHeight(20)
+ .setBarHeight(20)
+ .setId(4).close();
+ ControllerStyle baudRateStyle = baudRate.getCaptionLabel().getStyle();
+ baudRate.getCaptionLabel().set("SELECT THE BAUD RATE");
+ baudRateStyle.marginTop = baudRateStyle.marginLeft = baudRateStyle.marginTop = 3;
+ //the baud options
+ for (int i=0; i serialBuffer = new ArrayList();
+
+void setupSerial() {
+ serial = new Serial(this, Serial.list()[serialListNumber], baud);
+}
+
+void stopSerial() {
+ serial.stop();
+}
+
+void serialEvent(Serial serial) {
+ //decode the message
+ while (serial.available () > 0) {
+ slipDecode(byte(serial.read()));
+ }
+}
+
+void SerialSendToUDP() {
+ byte [] buffer = new byte[serialBuffer.size()];
+ //copy the buffer over
+ for (int i = 0; i < serialBuffer.size(); i++) {
+ buffer[i] = serialBuffer.get(i);
+ }
+ //send it off
+ UDPSendBuffer(buffer);
+ //clear the buffer
+ serialBuffer.clear();
+ //light up the indicator
+ drawIncomingSerial();
+}
+
+void serialSend(byte[] data) {
+
+ //encode the message and send it
+ for (int i = 0; i < data.length; i++){
+ slipEncode(data[i]);
+ }
+ //write the eot
+ serial.write(eot);
+ println("");
+}
+
+/************************************************************************************
+ SLIP ENCODING
+ ************************************************************************************/
+
+byte eot = byte(192);
+byte slipesc = byte(219);
+byte slipescend = byte(220);
+byte slipescesc = byte(221);
+
+byte previousByte;
+
+void slipDecode(byte incoming) {
+ byte previous = previousByte;
+ previousByte = incoming;
+ //if the previous was the escape char
+ if (previous == slipesc) {
+ //if this one is the esc eot
+ if (incoming==slipescend) {
+ serialBuffer.add(eot);
+ }
+ else if (incoming==slipescesc) {
+ serialBuffer.add(slipesc);
+ }
+ }
+ else if (incoming==eot) {
+ //if it's the eot
+ //send off the packet
+ SerialSendToUDP();
+ }
+ else if (incoming != slipesc) {
+ serialBuffer.add(incoming);
+ }
+}
+
+void slipEncode(byte incoming) {
+ if(incoming == eot){
+ serial.write(slipesc);
+ serial.write(slipescend);
+ } else if(incoming==slipesc) {
+ serial.write(slipesc);
+ serial.write(slipescesc);
+ } else {
+ serial.write(incoming);
+ }
+ print((char)incoming);
+ print(" ");
+ println(incoming);
+}
diff --git a/lib/OSC/Applications/Processing/SLIPSerialToUDP/UDP.pde b/lib/OSC/Applications/Processing/SLIPSerialToUDP/UDP.pde
new file mode 100644
index 0000000..5520f34
--- /dev/null
+++ b/lib/OSC/Applications/Processing/SLIPSerialToUDP/UDP.pde
@@ -0,0 +1,27 @@
+//UDP communication
+UDP udp;
+
+int inPort = 9000;
+int outPort = 9001;
+String ipAddress = "127.0.0.1";
+
+void setupUDP() {
+ udp = new UDP( this, inPort );
+ //udp.log( true ); // <-- printout the connection activity
+ udp.listen( true );
+}
+
+void stopUDP() {
+ udp.close();
+}
+
+void UDPSendBuffer(byte[] data) {
+ udp.send( data, ipAddress, outPort );
+}
+
+//called when UDP receives some data
+void receive( byte[] data) {
+ drawIncomingUDP();
+ //send it over to serial
+ serialSend(data);
+}
diff --git a/lib/OSC/Applications/Processing/SLIPSerialToUDPp3 b/lib/OSC/Applications/Processing/SLIPSerialToUDPp3
new file mode 100644
index 0000000..e5c3ad6
--- /dev/null
+++ b/lib/OSC/Applications/Processing/SLIPSerialToUDPp3
@@ -0,0 +1,375 @@
+import processing.serial.*;
+//download at http://ubaa.net/shared/processing/udp/
+import hypermedia.net.*;
+//download at www.sojamo.de/libraries/controlp5
+import controlP5.*;
+
+/************************************************************************************
+ GUI
+ ************************************************************************************/
+
+ControlP5 cp5;
+
+DropdownList serialddl;
+DropdownList baudddl;
+Textlabel arduinoLabel;
+Textlabel UDPLabel;
+Textlabel incomingPacket;
+Button startButton;
+Button stopButton;
+Textfield ipAddressField;
+Textfield incomingPortField;
+Textfield outgoingPortField;
+
+void setupGUI() {
+ //the ControlP5 object
+ cp5 = new ControlP5(this);
+
+ //start button
+ startButton = cp5.addButton("START")
+ .setPosition(200, 200)
+ .setSize(200, 19)
+ ;
+
+ //stop button
+ stopButton = cp5.addButton("STOP")
+ .setPosition(200, 200)
+ .setSize(200, 19)
+ ;
+ stopButton.hide();
+
+ //Serial Port selector
+ serialddl = cp5.addDropdownList("SerialPort")
+ .setPosition(50, 100)
+ .setSize(200, 200)
+ ;
+ serialddl.setItemHeight(20);
+ serialddl.setBarHeight(15);
+ serialddl.setCaptionLabel("SELECT ARDUINO SERIAL PORT");
+ //serialddl.captionLabel().style().marginTop = 3;
+ //serialddl.captionLabel().style().marginLeft = 3;
+ //serialddl.valueLabel().style().marginTop = 3;
+ //set the serial options
+ String SerialList[] = Serial.list();
+ for (int i=0;i serialBuffer = new ArrayList();
+
+void setupSerial() {
+ serial = new Serial(this, Serial.list()[serialListNumber], baud);
+}
+
+void stopSerial() {
+ serial.stop();
+}
+
+void serialEvent(Serial serial) {
+ //decode the message
+ //println (serial.read());
+ while (serial.available () > 0) {
+ slipDecode(byte(serial.read()));
+ }
+}
+
+void SerialSendToUDP() {
+ byte [] buffer = new byte[serialBuffer.size()];
+ //copy the buffer over
+ for (int i = 0; i < serialBuffer.size(); i++) {
+ buffer[i] = serialBuffer.get(i);
+ }
+ //send it off
+ UDPSendBuffer(buffer);
+ //clear the buffer
+ serialBuffer.clear();
+ //light up the indicator
+ drawIncomingSerial();
+}
+
+void serialSend(byte[] data) {
+ //encode the message and send it
+ for (int i = 0; i < data.length; i++){
+ slipEncode(data[i]);
+ }
+ //write the eot
+ serial.write(eot);
+}
+
+/************************************************************************************
+ SLIP ENCODING
+ ************************************************************************************/
+
+byte eot = byte(192);
+byte slipesc = byte(219);
+byte slipescend = byte(220);
+byte slipescesc = byte(221);
+
+byte previousByte;
+
+void slipDecode(byte incoming) {
+ byte previous = previousByte;
+ previousByte = incoming;
+ //if the previous was the escape char
+ if (previous == slipesc) {
+ //if this one is the esc eot
+ if (incoming==slipescend) {
+ serialBuffer.add(eot);
+ }
+ else if (incoming==slipescesc) {
+ serialBuffer.add(slipesc);
+ }
+ }
+ else if (incoming==eot) {
+ //if it's the eot
+ //send off the packet
+ SerialSendToUDP();
+ }
+ else {
+ serialBuffer.add(incoming);
+ }
+}
+
+void slipEncode(byte incoming) {
+ if(incoming == eot){
+ serial.write(slipesc);
+ serial.write(slipescend);
+ } else if(incoming==slipesc) {
+ serial.write(slipesc);
+ serial.write(slipescesc);
+ } else {
+ serial.write(incoming);
+ }
+}
+
+
+/************************************************************************************
+ UDP
+ ************************************************************************************/
+
+//UDP communication
+UDP udp;
+
+int inPort = 9000;
+int outPort = 10001;
+String ipAddress = "192.168.0.12";
+
+void setupUDP() {
+ udp = new UDP( this, inPort );
+ udp.log( true ); // <-- printout the connection activity
+ udp.listen( true );
+}
+
+void stopUDP() {
+ udp.close();
+}
+
+void UDPSendBuffer(byte[] data) {
+ udp.send( data, ipAddress, outPort );
+}
+
+//called when UDP receives some data
+void receive( byte[] data) {
+ drawIncomingUDP();
+ //send it over to serial
+ serialSend(data);
+}
+
+/************************************************************************************
+ SETUP/DRAW
+ ************************************************************************************/
+
+void setup() {
+ // configure the screen size and frame rate
+ size(550, 250, P3D);
+ frameRate(30);
+ setupGUI();
+}
+
+void draw() {
+ background(128);
+ if (applicationRunning) {
+ drawIncomingPackets();
+ }
+}
+
+
+/************************************************************************************
+ VISUALIZING INCOMING PACKETS
+ ************************************************************************************/
+
+int lastSerialPacket = 0;
+int lastUDPPacket = 0;
+
+void drawIncomingPackets() {
+ //the serial packet
+ fill(0);
+ rect(75, 50, 100, 100);
+ //the udp packet
+ rect(325, 50, 100, 100);
+ int now = millis();
+ int lightDuration = 75;
+ if (now - lastSerialPacket < lightDuration) {
+ fill(255);
+ rect(85, 60, 80, 80);
+ }
+ if (now - lastUDPPacket < lightDuration) {
+ fill(255);
+ rect(335, 60, 80, 80);
+ }
+}
+
+void drawIncomingSerial() {
+ lastSerialPacket = millis();
+}
+
+void drawIncomingUDP() {
+ lastUDPPacket = millis();
+}
diff --git a/lib/OSC/Applications/Processing/UDPReceiveBundle/UDPReceiveBundle.pde b/lib/OSC/Applications/Processing/UDPReceiveBundle/UDPReceiveBundle.pde
new file mode 100644
index 0000000..466ddbf
--- /dev/null
+++ b/lib/OSC/Applications/Processing/UDPReceiveBundle/UDPReceiveBundle.pde
@@ -0,0 +1,74 @@
+/*
+Receives and visualizes OSCBundles sent over UDP
+
+Use with /examples/UDPSendBundle
+
+or with /examples/SerialSendBundle in conjunction
+with /Applications/Processing/SLIPSerialToUDP
+*/
+
+import oscP5.*;
+import netP5.*;
+
+OscP5 oscP5;
+
+void setup() {
+ size(600,300);
+ frameRate(30);
+ //set this to the receiving port
+ oscP5 = new OscP5(this,9001);
+}
+
+
+void draw() {
+ background(0);
+ //draw the analog values
+ float analog0Height = map(analogValue0, 0, 1024, 0, 200);
+ float analog1Height = map(analogValue1, 0, 1024, 0, 200);
+ fill(255);
+ rect(50, 250, 50, -analog0Height);
+ rect(150, 250, 50, -analog1Height);
+ //and the labels
+ textSize(12);
+ text("/analog/0", 50, 270);
+ text("/analog/1", 150, 270);
+ //and the digital pin label
+ text("/digital/5", 250, 270);
+ textSize(25);
+ text(digitalValue5, 250, 250);
+ //now do the mouse part
+ //add the label
+ textSize(12);
+ text("/mouse/step", 350, 270);
+ //make a box where it should go
+ noFill();
+ stroke(255);
+ rect(350, 50, 200, 200);
+ //and a square where the mouse is
+ fill(255);
+ float mouseXPos = map(mouseStepX, 0, 1024, 350, 530);
+ float mouseYPos = map(mouseStepY, 0, 1024, 50, 230);
+ rect(mouseXPos, mouseYPos, 20, 20);
+}
+
+int analogValue0 = 50;
+int analogValue1 = 50;
+String digitalValue5 = "LOW";
+
+int mouseStepX = 0;
+int mouseStepY = 0;
+
+// incoming osc message are forwarded to the oscEvent method.
+void oscEvent(OscMessage theOscMessage) {
+ //println(theOscMessage.addrPattern());
+ if (theOscMessage.addrPattern().equals("/analog/0")){
+ analogValue0 = theOscMessage.get(0).intValue();
+ } else if(theOscMessage.addrPattern().equals("/analog/1")){
+ analogValue1 = theOscMessage.get(0).intValue();
+ } else if(theOscMessage.addrPattern().equals("/digital/5")){
+ digitalValue5 = theOscMessage.get(0).stringValue();
+ } else if(theOscMessage.addrPattern().equals("/mouse/step")){
+ mouseStepX = theOscMessage.get(0).intValue();
+ mouseStepY = theOscMessage.get(1).intValue();
+ }
+}
diff --git a/lib/OSC/Applications/Processing/UDPReceiveMessage/UDPReceiveMessage.pde b/lib/OSC/Applications/Processing/UDPReceiveMessage/UDPReceiveMessage.pde
new file mode 100644
index 0000000..9856bcd
--- /dev/null
+++ b/lib/OSC/Applications/Processing/UDPReceiveMessage/UDPReceiveMessage.pde
@@ -0,0 +1,42 @@
+/*
+Receives and visualizes OSCBundles sent over UDP
+
+Use with /examples/UDPSendMessage
+
+or with /examples/SerialSendMessage in conjunction
+with /Applications/Processing/SLIPSerialToUDP
+*/
+
+import oscP5.*;
+import netP5.*;
+
+OscP5 oscP5;
+
+void setup() {
+ size(150,300);
+ frameRate(30);
+ //set this to the receiving port
+ oscP5 = new OscP5(this,9001);
+}
+
+
+void draw() {
+ background(0);
+ //draw the analog values
+ float analog0Height = map(analogValue0, 0, 1024, 0, 200);
+ fill(255);
+ rect(50, 250, 50, -analog0Height);
+ //and the labels
+ textSize(12);
+ text("/analog/0", 50, 270);
+}
+
+int analogValue0 = 50;
+
+// incoming osc message are forwarded to the oscEvent method.
+void oscEvent(OscMessage theOscMessage) {
+ //println(theOscMessage.addrPattern());
+ if (theOscMessage.addrPattern().equals("/analog/0")){
+ analogValue0 = theOscMessage.get(0).intValue();
+ }
+}
diff --git a/lib/OSC/Applications/Processing/serialSend/code/javaosc.jar b/lib/OSC/Applications/Processing/serialSend/code/javaosc.jar
new file mode 100755
index 0000000..8a683ef
Binary files /dev/null and b/lib/OSC/Applications/Processing/serialSend/code/javaosc.jar differ
diff --git a/lib/OSC/Applications/Processing/serialSend/serialSend.pde b/lib/OSC/Applications/Processing/serialSend/serialSend.pde
new file mode 100644
index 0000000..79d25ae
--- /dev/null
+++ b/lib/OSC/Applications/Processing/serialSend/serialSend.pde
@@ -0,0 +1,50 @@
+import oscP5.*;
+import netP5.*;
+
+OscP5 oscP5;
+NetAddress arduinoAddress;
+//the number of analog pins on this controller
+int analogPins = 16;
+//an array of all of the pin values
+int[] pinVals = new int[analogPins];
+
+void setup() {
+ frameRate(60);
+ size(320, 100);
+ background(0);
+ //initialize the listening port
+ oscP5 = new OscP5(this, 9999);
+ //the outgoing communication to the arduino
+ arduinoAddress = new NetAddress("128,32.122.252", 8888);
+}
+
+
+void draw() {
+ //clear the previous bars
+ fill(0);
+ rect(0, 0, width, height);
+ //draw each of the bars showing the pin value
+ for (int i = 0; i < analogPins; i++) {
+ int value = pinVals[i];
+ int barWidth = width/analogPins;
+ float barHeight = (value/1024.)*height;
+ //draws the new bar in white
+ fill(255);
+ rect(barWidth*i, height - barHeight, barWidth, barHeight);
+ }
+}
+
+// incoming osc message are forwarded to the oscEvent method.
+void oscEvent(OscMessage msg) {
+ String address = msg.addrPattern();
+ if (address.startsWith("/analog/")) {
+ //then it's an analog reading
+ //split the address
+ String[] splitAddr = address.split("/");
+ //the third element should be the number
+ int pinNum = Integer.parseInt(splitAddr[2]);
+ int val = msg.get(0).intValue();
+ pinVals[pinNum] = val;
+ }
+}
+
diff --git a/lib/OSC/Applications/Processing/serialSend/sketch.properties b/lib/OSC/Applications/Processing/serialSend/sketch.properties
new file mode 100644
index 0000000..2e0e580
--- /dev/null
+++ b/lib/OSC/Applications/Processing/serialSend/sketch.properties
@@ -0,0 +1 @@
+mode=Android
diff --git a/lib/OSC/LICENSE b/lib/OSC/LICENSE
new file mode 100644
index 0000000..ba4ea6f
--- /dev/null
+++ b/lib/OSC/LICENSE
@@ -0,0 +1,20 @@
+Written by Yotam Mann and Adrian Freed, The Center for New Music and Audio Technologies,
+University of California, Berkeley. Copyright (c) 2013, The Regents of
+the University of California (Regents).
+
+Permission to use, copy, modify, distribute, and distribute modified versions
+of this software and its documentation without fee and without a signed
+licensing agreement, is hereby granted, provided that the above copyright
+notice, this paragraph and the following two paragraphs appear in all copies,
+modifications, and distributions.
+
+IN NO EVENT SHALL REGENTS BE LIABLE TO ANY PARTY FOR DIRECT, INDIRECT,
+SPECIAL, INCIDENTAL, OR CONSEQUENTIAL DAMAGES, INCLUDING LOST PROFITS, ARISING
+OUT OF THE USE OF THIS SOFTWARE AND ITS DOCUMENTATION, EVEN IF REGENTS HAS
+BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+
+REGENTS SPECIFICALLY DISCLAIMS ANY WARRANTIES, INCLUDING, BUT NOT LIMITED TO,
+THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
+PURPOSE. THE SOFTWARE AND ACCOMPANYING DOCUMENTATION, IF ANY, PROVIDED
+HEREUNDER IS PROVIDED "AS IS". REGENTS HAS NO OBLIGATION TO PROVIDE
+MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
diff --git a/lib/OSC/OSCBoards.cpp b/lib/OSC/OSCBoards.cpp
new file mode 100644
index 0000000..984751c
--- /dev/null
+++ b/lib/OSC/OSCBoards.cpp
@@ -0,0 +1,191 @@
+/*
+ Written by Adrian Freed, The Center for New Music and Audio Technologies,
+ University of California, Berkeley. Copyright (c) 2013, The Regents of
+ the University of California (Regents).
+
+ Permission to use, copy, modify, distribute, and distribute modified versions
+ of this software and its documentation without fee and without a signed
+ licensing agreement, is hereby granted, provided that the above copyright
+ notice, this paragraph and the following two paragraphs appear in all copies,
+ modifications, and distributions.
+
+ IN NO EVENT SHALL REGENTS BE LIABLE TO ANY PARTY FOR DIRECT, INDIRECT,
+ SPECIAL, INCIDENTAL, OR CONSEQUENTIAL DAMAGES, INCLUDING LOST PROFITS, ARISING
+ OUT OF THE USE OF THIS SOFTWARE AND ITS DOCUMENTATION, EVEN IF REGENTS HAS
+ BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+
+ REGENTS SPECIFICALLY DISCLAIMS ANY WARRANTIES, INCLUDING, BUT NOT LIMITED TO,
+ THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
+ PURPOSE. THE SOFTWARE AND ACCOMPANYING DOCUMENTATION, IF ANY, PROVIDED
+ HEREUNDER IS PROVIDED "AS IS". REGENTS HAS NO OBLIGATION TO PROVIDE
+ MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
+
+ For bug reports and feature requests please email me at yotam@cnmat.berkeley.edu
+ */
+
+
+#include
+#include "OSCBoards.h"
+
+#ifndef analogInputToDigitalPin
+int analogInputToDigitalPin(int i)
+{
+ switch(i)
+ {
+#ifdef A0
+ case 0: return A0;
+#endif
+#ifdef A1
+ case 1: return A1;
+#endif
+#ifdef A2
+ case 2: return A2;
+#endif
+#ifdef A3
+ case 3: return A3;
+#endif
+#ifdef A4
+ case 4: return A4;
+#endif
+#ifdef A5
+ case 5: return A5;
+#endif
+#ifdef A6
+ case 6: return A6;
+#endif
+#ifdef A7
+ case 7: return A7;
+#endif
+#ifdef A8
+ case 8: return A8;
+#endif
+#ifdef A9
+ case 9: return A9;
+#endif
+#ifdef A10
+ case 10: return A10;
+#endif
+#ifdef A11
+ case 11: return A11;
+#endif
+#ifdef A12
+ case 12: return A12;
+#endif
+#ifdef A13
+ case 13: return A13;
+#endif
+#ifdef A14
+ case 14: return A14;
+#endif
+#ifdef A15
+ case 15: return A15;
+#endif
+#ifdef A16
+ case 16: return A16;
+#endif
+ }
+ return -1;
+}
+#endif
+
+
+#ifdef BOARD_HAS_DIE_POWER_SUPPLY_MEASUREMENT
+#if defined(__MK20DX128__) || defined(__MK20DX256__) || defined(__MKL26Z64__) || defined(__MK64FX512V__) || defined(__MK66FX1M0__)
+float getSupplyVoltage()
+{
+ analogReference(DEFAULT);
+ analogReadResolution(12);
+ analogReadAveraging(32);
+ PMC_REGSC |= PMC_REGSC_BGBE; // 39=bandgap ref (PMC_REGSC |= PMC_REGSC_BGBE);
+ delay(1);
+
+#if defined(__MKL26Z64__)
+ // Teensy 3 LC
+ int val = analogRead(39);
+ return val>0? (1.0f*4095/val):0.0f;
+#elif defined(__MK64FX512V__) || defined(__MK66FX1M0__)
+ int val = analogRead(71);
+ return val>0? (1.195f*4095/val):0.0f;
+#else
+ int val = analogRead(39);
+ return val>0? (1.195f*4095/val):0.0f;
+#endif
+}
+
+#else
+// power supply measurement on some Arduinos
+float getSupplyVoltage(){
+ // powersupply
+ int result;
+ // Read 1.1V reference against AVcc
+#if defined(__AVR_ATmega32U4__) || defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
+ ADMUX = _BV(REFS0) | _BV(MUX4) | _BV(MUX3) | _BV(MUX2) | _BV(MUX1);
+#elif defined (__AVR_ATtiny24__) || defined(__AVR_ATtiny44__) || defined(__AVR_ATtiny84__)
+ ADMUX = _BV(MUX5) | _BV(MUX0);
+#elif defined (__AVR_ATtiny25__) || defined(__AVR_ATtiny45__) || defined(__AVR_ATtiny85__)
+ ADMUX = _BV(MUX3) | _BV(MUX2);
+#elif defined(__AVR_AT90USB646__) || defined(__AVR_AT90USB1286__) || defined(__AVR_ATmega1280__)
+ ADMUX = 0x40| _BV(MUX4) | _BV(MUX3) | _BV(MUX2) | _BV(MUX1) ;
+ ADCSRB = 0;
+#else
+ ADMUX = _BV(REFS0) | _BV(MUX3) | _BV(MUX2) | _BV(MUX1);
+#endif
+ delayMicroseconds(300); // wait for Vref to settle
+ ADCSRA |= _BV(ADSC); // Convert
+ while (bit_is_set(ADCSRA,ADSC));
+ result = ADCL;
+ result |= ADCH<<8;
+
+ float supplyvoltage = 1.1264f *1023 / result;
+ return supplyvoltage;
+}
+#endif
+
+#endif
+
+#ifdef BOARD_HAS_DIE_TEMPERATURE_SENSOR
+
+#if defined(__MK20DX128__) || defined(__MK20DX256__)|| defined(__MKL26Z64__) || defined(__MK66FX1M0__) || defined(__MK64FX512V__)
+float getTemperature()
+{
+#if defined(__MK64FX512V__) || defined(__MK66FX1M0__)
+ const int temppin = 70 ;
+#else
+ const int temppin = 38;
+#endif
+ // untested on all teensy 3.x
+ analogReference(INTERNAL);
+ analogReadResolution(12);
+ analogReadAveraging(32);
+ delay(2);
+
+ float val = 25.0 + 0.17083 * (2454.19 - analogRead(temppin));
+
+ analogReference(DEFAULT);
+
+ return val;
+}
+#else
+// temperature
+float getTemperature(){
+ int result;
+
+#if defined(__AVR_ATmega32U4__)
+ ADMUX = _BV(REFS1) | _BV(REFS0) | _BV(MUX2) | _BV(MUX1) | _BV(MUX0);
+ ADCSRB = _BV(MUX5);
+#else
+ ADMUX = _BV(REFS1) | _BV(REFS0) | _BV(MUX3);
+#endif
+ delayMicroseconds(200); // wait for Vref to settle
+ ADCSRA |= _BV(ADSC); // Convert
+ while (bit_is_set(ADCSRA,ADSC));
+ result = ADCL;
+ result |= ADCH<<8;
+
+ analogReference(DEFAULT);
+
+ return result/1023.0f;
+}
+#endif
+
+#endif
diff --git a/lib/OSC/OSCBoards.h b/lib/OSC/OSCBoards.h
new file mode 100644
index 0000000..29a31f7
--- /dev/null
+++ b/lib/OSC/OSCBoards.h
@@ -0,0 +1,56 @@
+//
+// OSCBoards.h
+//
+//
+// Created by AdrianFreed on 5/26/13.
+//
+//
+
+#ifndef _OSCBoards_h
+#define _OSCBoards_h
+
+
+#if defined(__MK20DX128__) || defined(__MK20DX256__) || defined(__MKL26Z64__) || defined(__MK66FX1M0__)
+// Teensy 3.0 3.1 3.1LC 3.2 3.6
+#define BOARD_HAS_CAPACITANCE_SENSING
+#endif
+
+#if defined(__AVR_ATmega32U4__) || defined(__MKL26Z64__) || defined(__MK20DX128__)|| defined(__MK20DX256__) || defined(__MK66FX1M0__) || defined(__AVR_ATmega328_) || defined(__AVR_ATmega128__)
+
+#define BOARD_HAS_DIE_TEMPERATURE_SENSOR
+#endif
+
+#if defined(__AVR_ATmega32U4__) || defined(__MK20DX128__) || defined(__MK20DX256__) || defined(__MK66FX1M0__) || defined(__MK66FX1M0__) || defined(__MKL26Z64__) || defined(__AVR_ATmega32U4__) || defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) || defined (__AVR_ATtiny24__) || defined(__AVR_ATtiny44__) || defined(__AVR_ATtiny84__) || defined (__AVR_ATtiny25__) || defined(__AVR_ATtiny45__) || defined(__AVR_ATtiny85__) || defined(__AVR_AT90USB646__) || defined(__AVR_AT90USB1286__) || defined(__AVR_ATmega1280__) || defined(__AVR_ATmega328_) || defined(__AVR_ATmega128__)
+
+
+#define BOARD_HAS_DIE_POWER_SUPPLY_MEASUREMENT
+#endif
+
+
+#if defined(__AVR_ATmega32U4__) || defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) || defined (__AVR_ATtiny24__) || defined(__AVR_ATtiny44__) || defined(__AVR_ATtiny84__) || defined (__AVR_ATtiny25__) || defined(__AVR_ATtiny45__) || defined(__AVR_ATtiny85__) || defined(__AVR_AT90USB646__) || defined(__AVR_AT90USB1286__) || defined(__AVR_ATmega1280__) || defined(__AVR_ATmega328_) || defined(__AVR_ATmega128__)
+#define BOARD_HAS_ANALOG_PULLUP
+#endif
+
+// missing specs for PIC32
+
+#if (defined(__PIC32MX__) || defined(__PIC32MZ__))
+#define NUM_ANALOG_INPUTS NUM_ANALOG_PINS
+#define NUM_DIGITAL_INPUTS NUM_DIGITAL_PINS
+#define LED_BUILTIN PIN_LED1
+
+#endif
+
+
+#ifndef analogInputToDigitalPin
+int analogInputToDigitalPin(int i);
+#endif
+
+#ifdef BOARD_HAS_DIE_TEMPERATURE_SENSOR
+float getTemperature();
+#endif
+
+#ifdef BOARD_HAS_DIE_POWER_SUPPLY_MEASUREMENT
+float getSupplyVoltage();
+#endif
+
+#endif
diff --git a/lib/OSC/OSCBundle.cpp b/lib/OSC/OSCBundle.cpp
new file mode 100644
index 0000000..3957c11
--- /dev/null
+++ b/lib/OSC/OSCBundle.cpp
@@ -0,0 +1,357 @@
+/*
+ Written by Yotam Mann, The Center for New Music and Audio Technologies,
+ University of California, Berkeley. Copyright (c) 2012, The Regents of
+ the University of California (Regents).
+
+ Permission to use, copy, modify, distribute, and distribute modified versions
+ of this software and its documentation without fee and without a signed
+ licensing agreement, is hereby granted, provided that the above copyright
+ notice, this paragraph and the following two paragraphs appear in all copies,
+ modifications, and distributions.
+
+ IN NO EVENT SHALL REGENTS BE LIABLE TO ANY PARTY FOR DIRECT, INDIRECT,
+ SPECIAL, INCIDENTAL, OR CONSEQUENTIAL DAMAGES, INCLUDING LOST PROFITS, ARISING
+ OUT OF THE USE OF THIS SOFTWARE AND ITS DOCUMENTATION, EVEN IF REGENTS HAS
+ BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+
+ REGENTS SPECIFICALLY DISCLAIMS ANY WARRANTIES, INCLUDING, BUT NOT LIMITED TO,
+ THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
+ PURPOSE. THE SOFTWARE AND ACCOMPANYING DOCUMENTATION, IF ANY, PROVIDED
+ HEREUNDER IS PROVIDED "AS IS". REGENTS HAS NO OBLIGATION TO PROVIDE
+ MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
+
+ For bug reports and feature requests please email me at yotam@cnmat.berkeley.edu
+ */
+
+#include "OSCBundle.h"
+#include
+
+ /*=============================================================================
+ CONSTRUCTORS / DESTRUCTOR
+=============================================================================*/
+
+OSCBundle::OSCBundle(osctime_t _timetag){
+ setTimetag(_timetag);
+ numMessages = 0;
+ error = OSC_OK;
+ messages = NULL;
+ incomingBuffer = NULL;
+ incomingBufferSize = 0;
+ decodeState = STANDBY;
+}
+
+OSCBundle::~OSCBundle(){
+ for (int i = 0; i < numMessages; i++){
+ OSCMessage * msg = getOSCMessage(i);
+ delete msg;
+ }
+ free(messages);
+ free(incomingBuffer);
+}
+
+//clears all of the OSCMessages inside
+OSCBundle& OSCBundle::empty(){
+ error = OSC_OK;
+ for (int i = 0; i < numMessages; i++){
+ OSCMessage * msg = getOSCMessage(i);
+ delete msg;
+ }
+ free(messages);
+ messages = NULL;
+ clearIncomingBuffer();
+ numMessages = 0;
+ return *this;
+}
+
+/*=============================================================================
+ SETTERS
+ =============================================================================*/
+
+OSCMessage & OSCBundle::add(const char * _address){
+ OSCMessage * msg = new OSCMessage(_address);
+ if (!msg->hasError()){
+ //realloc the array to fit the message
+ OSCMessage ** messageMem = (OSCMessage **) realloc(messages, sizeof(OSCMessage *) * (numMessages + 1));
+ if (messageMem != NULL){
+ messages = messageMem;
+ messages[numMessages] = msg;
+ numMessages++;
+ } else {
+ error = ALLOCFAILED;
+ }
+ }
+ return *msg;
+}
+
+OSCMessage & OSCBundle::add(){
+ OSCMessage * msg = new OSCMessage();
+ //realloc the array to fit the message
+ OSCMessage ** messageMem = (OSCMessage **) realloc(messages, sizeof(OSCMessage *) * (numMessages + 1));
+ if (messageMem != NULL){
+ messages = messageMem;
+ messages[numMessages] = msg;
+ numMessages++;
+ } else {
+ error = ALLOCFAILED;
+ }
+ return *msg;
+}
+
+OSCMessage & OSCBundle::add(OSCMessage & _msg){
+ OSCMessage * msg = new OSCMessage(&_msg);
+ if (!msg->hasError()){
+ //realloc the array to fit the message
+ OSCMessage ** messageMem = (OSCMessage **) realloc(messages, sizeof(OSCMessage *) * (numMessages + 1));
+ if (messageMem != NULL){
+ messages = messageMem;
+ messages[numMessages] = msg;
+ numMessages++;
+ } else {
+ error = ALLOCFAILED;
+ }
+ }
+ return *msg;
+}
+
+/*=============================================================================
+ GETTERS
+ =============================================================================*/
+
+//returns the first fullMatch.
+OSCMessage * OSCBundle::getOSCMessage( char * addr){
+ for (int i = 0; i < numMessages; i++){
+ OSCMessage * msg = getOSCMessage(i);
+ if (msg->fullMatch(addr)){
+ return msg;
+ }
+ }
+ return NULL;
+}
+
+//the position is the same as the order they were declared in
+OSCMessage * OSCBundle::getOSCMessage(int pos){
+ if (pos < numMessages){
+ return messages[pos];
+ }
+ return NULL;
+}
+
+/*=============================================================================
+ PATTERN MATCHING
+ =============================================================================*/
+
+
+bool OSCBundle::dispatch(const char * pattern, void (*callback)(OSCMessage&), int initial_offset){
+ bool called = false;
+ for (int i = 0; i < numMessages; i++){
+ OSCMessage msg = getOSCMessage(i);
+ called = msg.dispatch(pattern, callback, initial_offset) || called ;
+ }
+ return called;
+}
+
+
+bool OSCBundle::route(const char * pattern, void (*callback)(OSCMessage&, int), int initial_offset){
+ bool called = false;
+ for (int i = 0; i < numMessages; i++){
+ OSCMessage msg = getOSCMessage(i);
+ called = msg.route(pattern, callback, initial_offset) || called;
+ }
+ return called;
+}
+
+/*=============================================================================
+ SIZE
+ =============================================================================*/
+
+
+int OSCBundle::size(){
+ return numMessages;
+}
+
+/*=============================================================================
+ ERROR HANDLING
+ =============================================================================*/
+
+bool OSCBundle::hasError(){
+ bool retError = error != OSC_OK;
+ //test each of the data
+ for (int i = 0; i < numMessages; i++){
+ OSCMessage * msg = getOSCMessage(i);
+ retError |= msg->hasError();
+ }
+ return retError;
+}
+
+OSCErrorCode OSCBundle::getError(){
+ return error;
+}
+
+
+/*=============================================================================
+ SENDING
+ =============================================================================*/
+
+OSCBundle& OSCBundle::send(Print &p){
+ //don't send a bundle with errors
+ if (hasError()){
+ return *this;
+ }
+ //write the bundle header
+ static uint8_t header[] = {'#', 'b', 'u', 'n', 'd', 'l', 'e', 0};
+ p.write(header, 8);
+ //write the timetag
+{
+ osctime_t time = timetag;
+ uint32_t d = BigEndian(time.seconds);
+ uint8_t * ptr = (uint8_t *) &d;
+ p.write(ptr, 4);
+ d = BigEndian(time.fractionofseconds);
+ ptr = (uint8_t *) &d;
+ p.write(ptr, 4);
+}
+
+ //send the messages
+ for (int i = 0; i < numMessages; i++){
+ OSCMessage * msg = getOSCMessage(i);
+ int msgSize = msg->bytes();
+ //turn the message size into a pointer
+ uint32_t s32 = BigEndian((uint32_t) msgSize);
+ uint8_t * sptr = (uint8_t *) &s32;
+ //write the message size
+ p.write(sptr, 4);
+ msg->send(p);
+ }
+ return *this;
+}
+
+/*=============================================================================
+ FILLING
+ =============================================================================*/
+
+OSCBundle& OSCBundle::fill(uint8_t incomingByte){
+ decode(incomingByte);
+ return *this;
+}
+
+OSCBundle& OSCBundle::fill(const uint8_t * incomingBytes, int length){
+ while (length--){
+ decode(*incomingBytes++);
+ }
+ return *this;
+}
+
+/*=============================================================================
+ DECODING
+ =============================================================================*/
+
+void OSCBundle::decodeTimetag(){
+ //parse the incoming buffer as a uint64
+ setTimetag(incomingBuffer);
+ //make sure the endianness is right
+ //xxx time tag timetag = BigEndian(timetag);
+ decodeState = MESSAGE_SIZE;
+ clearIncomingBuffer();
+}
+
+void OSCBundle::decodeHeader(){
+ const char * header = "#bundle";
+ if (strcmp(header, (char *) incomingBuffer)!=0){
+ //otherwise go back to the top and wait for a new bundle header
+ decodeState = STANDBY;
+ error = INVALID_OSC;
+ } else {
+ decodeState = TIMETAG;
+ }
+ clearIncomingBuffer();
+}
+
+void OSCBundle::decodeMessage(uint8_t incomingByte){
+ //get the current message
+ if (numMessages > 0){
+ OSCMessage * lastMessage = messages[numMessages - 1];
+ //put the bytes in there
+ lastMessage->fill(incomingByte);
+ //if it's all done
+ if (incomingBufferSize == incomingMessageSize){
+ //move onto the next message
+ decodeState = MESSAGE_SIZE;
+ clearIncomingBuffer();
+ } else if (incomingBufferSize > incomingMessageSize){
+ error = INVALID_OSC;
+ }
+ }
+}
+
+//does not validate the incoming OSC for correctness
+void OSCBundle::decode(uint8_t incomingByte){
+ addToIncomingBuffer(incomingByte);
+ switch (decodeState){
+ case STANDBY:
+ if (incomingByte == '#'){
+ decodeState = HEADER;
+ } else if (incomingByte == '/'){
+ add();//add a simple message to the bundle
+ decodeMessage(incomingByte);
+ decodeState = MESSAGE;
+ }
+ break;
+ case HEADER:
+ if (incomingBufferSize == 8){
+ decodeHeader();
+ decodeState = TIMETAG;
+ }
+ break;
+ case TIMETAG:
+ if (incomingBufferSize == 8){
+ decodeTimetag();
+ decodeState = MESSAGE_SIZE;
+ }
+ break;
+ case MESSAGE_SIZE:
+ if (incomingBufferSize == 4){
+ //make sure the message size is valid
+ int32_t msgSize;
+ memcpy(&msgSize, incomingBuffer, 4);
+ msgSize = BigEndian(msgSize);
+ if (msgSize % 4 != 0 || msgSize == 0){
+ error = INVALID_OSC;
+ } else {
+ //add a message to the buffer
+ decodeState = MESSAGE;
+ incomingMessageSize = msgSize;
+ clearIncomingBuffer();
+ //add a new empty message
+ add();
+ }
+ }
+ break;
+ case MESSAGE:
+ decodeMessage(incomingByte);
+ break;
+ }
+}
+
+
+/*=============================================================================
+ INCOMING BUFFER MANAGEMENT
+ =============================================================================*/
+
+void OSCBundle::addToIncomingBuffer(uint8_t incomingByte){
+ //realloc some space for the new byte and stick it on the end
+ incomingBuffer = (uint8_t *) realloc ( incomingBuffer, incomingBufferSize + 1);
+ if (incomingBuffer != NULL){
+ incomingBuffer[incomingBufferSize++] = incomingByte;
+ } else {
+ error = ALLOCFAILED;
+ }
+}
+
+void OSCBundle::clearIncomingBuffer(){
+ incomingBufferSize = 0;
+ free(incomingBuffer);
+ incomingBuffer = NULL;
+}
+
+
+
diff --git a/lib/OSC/OSCBundle.h b/lib/OSC/OSCBundle.h
new file mode 100644
index 0000000..4285749
--- /dev/null
+++ b/lib/OSC/OSCBundle.h
@@ -0,0 +1,175 @@
+/*
+ Written by Yotam Mann, The Center for New Music and Audio Technologies,
+ University of California, Berkeley. Copyright (c) 2012, 2013, The Regents of
+ the University of California (Regents).
+
+ Permission to use, copy, modify, distribute, and distribute modified versions
+ of this software and its documentation without fee and without a signed
+ licensing agreement, is hereby granted, provided that the above copyright
+ notice, this paragraph and the following two paragraphs appear in all copies,
+ modifications, and distributions.
+
+ IN NO EVENT SHALL REGENTS BE LIABLE TO ANY PARTY FOR DIRECT, INDIRECT,
+ SPECIAL, INCIDENTAL, OR CONSEQUENTIAL DAMAGES, INCLUDING LOST PROFITS, ARISING
+ OUT OF THE USE OF THIS SOFTWARE AND ITS DOCUMENTATION, EVEN IF REGENTS HAS
+ BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+
+ REGENTS SPECIFICALLY DISCLAIMS ANY WARRANTIES, INCLUDING, BUT NOT LIMITED TO,
+ THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
+ PURPOSE. THE SOFTWARE AND ACCOMPANYING DOCUMENTATION, IF ANY, PROVIDED
+ HEREUNDER IS PROVIDED "AS IS". REGENTS HAS NO OBLIGATION TO PROVIDE
+ MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
+
+
+ */
+
+#ifndef OSCBUNDLE_h
+#define OSCBUNDLE_h
+
+#include "OSCMessage.h"
+
+extern osctime_t zerotime;
+class OSCBundle
+{
+
+private:
+
+/*=============================================================================
+ PRIVATE VARIABLES
+=============================================================================*/
+
+ //the array of messages contained in the bundle
+ OSCMessage ** messages;
+
+ //the number of messages in the array
+ int numMessages;
+
+ osctime_t timetag;
+
+ //error codes
+ OSCErrorCode error;
+
+/*=============================================================================
+ DECODING INCOMING BYTES
+ =============================================================================*/
+
+ //the decoding states for incoming bytes
+ enum DecodeState {
+ STANDBY,
+ HEADER,
+ TIMETAG,
+ MESSAGE_SIZE,
+ MESSAGE,
+ } decodeState;
+
+ //stores incoming bytes until they can be decoded
+ uint8_t * incomingBuffer;
+ int incomingBufferSize;
+
+ //the size of the incoming message
+ int incomingMessageSize;
+
+ //adds a byte to the buffer
+ void addToIncomingBuffer(uint8_t);
+ //clears the incoming buffer
+ void clearIncomingBuffer();
+
+ //decoding functions
+ void decode(uint8_t);
+ void decodeTimetag();
+ void decodeHeader();
+ void decodeMessage(uint8_t);
+
+ //just a placeholder while filling
+ OSCMessage & add();
+
+
+public:
+
+/*=============================================================================
+ CONSTRUCTORS / DESTRUCTOR
+=============================================================================*/
+
+ //default timetag of
+ OSCBundle(osctime_t = zerotime);
+
+ //DESTRUCTOR
+ ~OSCBundle();
+
+ //clears all of the OSCMessages inside
+ OSCBundle& empty();
+
+/*=============================================================================
+ SETTERS
+=============================================================================*/
+
+ //start a new OSC Message in the bundle
+ OSCMessage & add(const char * address);
+ //add with nothing in it produces an invalid osc message
+ //copies an existing message into the bundle
+ OSCMessage & add(OSCMessage & msg);
+
+ template
+ OSCBundle& setTimetag(T t){
+ timetag = (osctime_t) t;
+ return *this;
+ }
+ //sets the timetag from a buffer
+ OSCBundle& setTimetag(uint8_t * buff){
+ memcpy(&timetag, buff, 8);
+ return *this;
+ }
+
+/*=============================================================================
+ GETTERS
+ =============================================================================*/
+
+ //gets the message the matches the address string
+ //will do regex matching
+ OSCMessage * getOSCMessage(char * addr);
+
+ //get message by position
+ OSCMessage * getOSCMessage(int position);
+
+/*=============================================================================
+ MATCHING
+=============================================================================*/
+
+ //if the bundle contains a message that matches the pattern,
+ //call the function callback on that message
+ bool dispatch(const char * pattern, void (*callback)(OSCMessage&), int = 0);
+
+ //like dispatch, but allows for partial matches
+ //the address match offset is sent as an argument to the callback
+ bool route(const char * pattern, void (*callback)(OSCMessage&, int), int = 0);
+
+/*=============================================================================
+ SIZE
+=============================================================================*/
+ //returns the number of messages in the bundle;
+ int size();
+
+/*=============================================================================
+ ERROR
+ =============================================================================*/
+
+ bool hasError();
+
+ OSCErrorCode getError();
+
+/*=============================================================================
+ SENDING
+ =============================================================================*/
+
+ OSCBundle& send(Print &p);
+
+/*=============================================================================
+ FILLING
+ =============================================================================*/
+
+ OSCBundle& fill(uint8_t incomingByte);
+
+ OSCBundle& fill(const uint8_t * incomingBytes, int length);
+};
+
+#endif
diff --git a/lib/OSC/OSCData.cpp b/lib/OSC/OSCData.cpp
new file mode 100644
index 0000000..f72cb9a
--- /dev/null
+++ b/lib/OSC/OSCData.cpp
@@ -0,0 +1,335 @@
+
+#include "OSCData.h"
+
+
+osctime_t zerotime = {0,0};
+/*=============================================================================
+ CONSTRUCTORS
+
+ overloaded methods for each of the types which will
+ set the type flag, the size (in bytes), and the data
+=============================================================================*/
+
+
+OSCData::OSCData(const char * s){
+ error = OSC_OK;
+ type = 's';
+ bytes = (strlen(s) + 1);
+ //own the data
+ char * mem = (char *) malloc(bytes);
+ if (mem == NULL){
+ error = ALLOCFAILED;
+ } else {
+ strcpy(mem, s);
+ data.s = mem;
+ }
+}
+
+
+
+
+OSCData::OSCData(int32_t i){
+ error = OSC_OK;
+ type = 'i';
+ bytes = 4;
+ data.i = i;
+}
+#ifndef ESPxx
+OSCData::OSCData(int i){
+ error = OSC_OK;
+ type = 'i';
+ bytes = 4;
+ data.i = i;
+}
+#endif
+OSCData::OSCData(unsigned int i){
+ error = OSC_OK;
+ type = 'i';
+ bytes = 4;
+ data.i = i;
+}
+#if defined(__SAM3X8E__)
+OSCData::OSCData(int16_t i){
+ error = OSC_OK;
+ type = 'i';
+ bytes = 4;
+ data.i = i;
+}
+#endif
+
+OSCData::OSCData(float f){
+ error = OSC_OK;
+ type = 'f';
+ bytes = 4;
+ data.f = f;
+}
+
+OSCData::OSCData(osctime_t t){
+ error = OSC_OK;
+ type = 't';
+ bytes = 8;
+ data.time = t;
+}
+OSCData::OSCData(boolean b){
+ error = OSC_OK;
+ type = b?'T':'F';
+ bytes = 0;
+}
+
+
+OSCData::OSCData(double d){
+ error = OSC_OK;
+ bytes = sizeof(double);
+ //if it's not 8 bytes it's not a true double
+ if (bytes == 8){
+ type = 'd';
+ data.d = d;
+ } else {
+ type = 'f';
+ data.f = d;
+ }
+}
+
+OSCData::OSCData(uint8_t * b, int len){
+ error = OSC_OK;
+ type = 'b';
+ bytes = len + 4;
+ //add the size to the front of the blob
+ uint32_t len32 = (uint32_t) len;
+ //make sure the length is endian-safe
+ len32 = BigEndian(len32);
+ uint8_t * lenPtr = (uint8_t *) (& len32);
+ //own the data
+ if(bytes>0)
+ {
+
+ uint8_t * mem = (uint8_t * ) malloc(bytes);
+ if (mem == NULL){
+ error = ALLOCFAILED;
+ } else {
+ //copy over the blob length
+ memcpy(mem, lenPtr, 4);
+ //copy over the blob data
+ memcpy(mem + 4, b, len);
+ data.b = mem;
+ }
+ }
+ else
+ data.b = 0;
+}
+
+OSCData::OSCData (OSCData * datum){
+ error = OSC_OK;
+ type = datum->type;
+ bytes = datum->bytes;
+ if ( (type == 'i') || (type == 'f') || (type == 'd') || (type == 't')
+ || (type == 'h') || (type == 'c') || (type == 'r') || (type == 'm')
+ )
+ {
+ data = datum->data;
+ } else if ((type == 's') || (type == 'b')){
+ //allocate a new piece of memory
+ uint8_t * mem = (uint8_t * ) malloc(bytes);
+ if (mem == NULL){
+ error = ALLOCFAILED;
+ } else {
+ //copy over the blob length
+ memcpy(mem, datum->data.b, bytes);
+ data.b = mem;
+ }
+ }
+}
+
+//DESTRUCTOR
+OSCData::~OSCData(){
+ //if there are no bytes, there is nothing to free
+ if (bytes>0){
+ //if the data is of type 's' or 'b', need to free that memory
+ if (type == 's'){
+ free(data.s);
+ }else if( type == 'b'){
+ free(data.b);
+ }
+ }
+}
+
+//sets just the type as a message placeholder
+//no data
+OSCData::OSCData(char t){
+ error = (t == 'T' || t == 'F') ? OSC_OK : INVALID_OSC;
+ type = t;
+ bytes = 0;
+}
+
+/*=============================================================================
+ GETTERS
+
+ perform a safety check to make sure the data type matches the request
+ otherwise returns NULL
+=============================================================================*/
+
+int32_t OSCData::getInt(){
+ if (type == 'i'){
+ return data.i;
+ } else {
+ #ifndef ESPxx
+ return (int32_t)NULL;
+ #else
+ return -1;
+ #endif
+ }
+}
+osctime_t OSCData::getTime(){
+ if (type == 't'){
+ return data.time;
+ } else {
+
+ return zerotime;
+ }
+}
+float OSCData::getFloat(){
+ if (type == 'f'){
+ return data.f;
+ } else {
+ #ifndef ESPxx
+ return (float)NULL;
+ #else
+ return -1;
+ #endif
+ }
+}
+
+double OSCData::getDouble(){
+ if (type == 'd'){
+ return data.d;
+ } else {
+ #ifndef ESPxx
+ return (double)NULL;
+ #else
+ return -1;
+ #endif
+ }
+}
+bool OSCData::getBoolean(){
+ if (type == 'T'){
+ return true;
+ } else if (type=='F'){
+ return false;
+ }
+ else
+ #ifndef ESPxx
+ return NULL;
+ #else
+ return -1;
+ #endif
+}
+
+
+// no-safety-check straightforward way to fill the passed buffer
+// with the received string
+int OSCData::getString(char * strBuffer){
+ if (type == 's'){
+ strncpy(strBuffer, data.s, bytes);
+ return bytes;
+ } else {
+ #ifndef ESPxx
+ return (int)NULL;
+ #else
+ return -1;
+ #endif
+ }
+}
+
+// it's possible to pass strBuffer's size as argument (length)
+// in order to check that it won't be overflown
+int OSCData::getString(char * strBuffer, int length){
+ if (type == 's' && bytes <= length){
+ strncpy(strBuffer, data.s, bytes);
+ return bytes;
+ } else {
+ #ifndef ESPxx
+ return (int)NULL;
+ #else
+ return -1;
+ #endif
+ }
+}
+
+// Here we can get only a part of the string
+int OSCData::getString(char * strBuffer, int length, int offset, int size)
+{
+ int maxLen = bytes - offset;
+ if (type == 's' && maxLen >= 0 && size <= maxLen && size <= length){
+ strncpy(strBuffer, data.s + offset, size);
+ return size;
+ } else {
+ #ifndef ESPxx
+ return (int)NULL;
+ #else
+ return -1;
+ #endif
+ }
+}
+
+// no-safety-check straightforward way to fill the passed buffer
+// with the contents of the received blob
+int OSCData::getBlob(uint8_t * blobBuffer){
+ // read the blob length
+ int blobLength = getBlobLength();
+
+ if (type == 'b'){
+ memcpy(blobBuffer, data.b + 4, blobLength);
+ return blobLength;
+ } else {
+ #ifndef ESPxx
+ return (int)NULL;
+ #else
+ return -1;
+ #endif
+ }
+}
+
+// it's possible to pass blobBuffer's size as argument (length)
+// in order to check that it won't be overflown
+int OSCData::getBlob(uint8_t * blobBuffer, int length){
+ //jump over the first 4 bytes which encode the length
+ int blobLength = bytes-4;
+ if (type == 'b' && blobLength <= length){
+ memcpy(blobBuffer, data.b + 4, blobLength);
+ return blobLength;
+ } else {
+ #ifndef ESPxx
+ return (int)NULL;
+ #else
+ return -1;
+ #endif
+ }
+}
+
+// Here we can get only a part of the blob
+int OSCData::getBlob(uint8_t * blobBuffer, int length, int offset, int size){
+ //jump over the first 4 bytes which encode the length
+ int blobLength = bytes-4-offset;
+ if (type == 'b' && blobLength >= 0 && size <= blobLength && size <= length){
+ memcpy(blobBuffer, data.b + 4 + offset, size);
+ return size;
+ } else {
+ #ifndef ESPxx
+ return (int)NULL;
+ #else
+ return -1;
+ #endif
+ }
+}
+
+const uint8_t* OSCData::getBlob() {
+ return type == 'b' ? data.b + 4 : NULL;
+}
+
+int OSCData::getBlobLength(){
+ if (type == 'b'){
+ //jump over the first 4 bytes which encode the length
+ return bytes-4;
+ }
+ return -1;
+}
diff --git a/lib/OSC/OSCData.h b/lib/OSC/OSCData.h
new file mode 100644
index 0000000..e3f16b0
--- /dev/null
+++ b/lib/OSC/OSCData.h
@@ -0,0 +1,156 @@
+/*
+ Written by Yotam Mann, The Center for New Music and Audio Technologies,
+ University of California, Berkeley. Copyright (c) 2013, The Regents of
+ the University of California (Regents).
+
+ Permission to use, copy, modify, distribute, and distribute modified versions
+ of this software and its documentation without fee and without a signed
+ licensing agreement, is hereby granted, provided that the above copyright
+ notice, this paragraph and the following two paragraphs appear in all copies,
+ modifications, and distributions.
+
+ IN NO EVENT SHALL REGENTS BE LIABLE TO ANY PARTY FOR DIRECT, INDIRECT,
+ SPECIAL, INCIDENTAL, OR CONSEQUENTIAL DAMAGES, INCLUDING LOST PROFITS, ARISING
+ OUT OF THE USE OF THIS SOFTWARE AND ITS DOCUMENTATION, EVEN IF REGENTS HAS
+ BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+
+ REGENTS SPECIFICALLY DISCLAIMS ANY WARRANTIES, INCLUDING, BUT NOT LIMITED TO,
+ THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
+ PURPOSE. THE SOFTWARE AND ACCOMPANYING DOCUMENTATION, IF ANY, PROVIDED
+ HEREUNDER IS PROVIDED "AS IS". REGENTS HAS NO OBLIGATION TO PROVIDE
+ MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
+
+ For bug reports and feature requests please email me at yotam@cnmat.berkeley.edu
+ */
+
+#ifndef OSCDATA_h
+#define OSCDATA_h
+
+#include "Arduino.h"
+
+#include
+#include
+#include
+#include
+
+#include "OSCTiming.h"
+
+#if (defined(TEENSYDUINO) && defined(USB_SERIAL)) || (!defined(TEENSYDUINO) && defined(__AVR_ATmega32U4__)) || defined(__SAM3X8E__) || (defined(_USB) && defined(_USE_USB_FOR_SERIAL_)) || defined(BOARD_maple_mini)
+
+#define BOARD_HAS_USB_SERIAL
+#if defined(__SAM3X8E__)
+#define thisBoardsSerialUSB SerialUSB
+#else
+#define thisBoardsSerialUSB Serial
+#endif
+#endif
+
+#if defined(ESP8266) || defined(ESP32)
+#define ESPxx
+#endif
+
+//ERRORS/////////////////////////////////////////////////
+typedef enum { OSC_OK = 0,
+ BUFFER_FULL, INVALID_OSC, ALLOCFAILED, INDEX_OUT_OF_BOUNDS
+} OSCErrorCode;
+
+class OSCData
+{
+
+private:
+
+ //friends
+ friend class OSCMessage;
+
+ //should only be used while decoding
+ //leaves an invalid OSCMessage with a type, but no data
+ OSCData(char t);
+
+public:
+
+ //an error flag
+ OSCErrorCode error;
+
+ //the size (in bytes) of the data
+ int bytes;
+
+ //the type of the data
+ int type;
+
+ //the data
+ union {
+ char * s; //string
+ int32_t i; //int
+ float f; //float
+ double d; //double
+ uint64_t l; //long
+ uint8_t * b; //blob
+ osctime_t time;
+ } data;
+
+ //overload the constructor to account for all the types and sizes
+ OSCData(const char * s);
+#if defined(__SAM3X8E__)
+ OSCData (int16_t);
+#endif
+ OSCData (int32_t);
+#ifndef ESPxx
+ OSCData (int);
+#endif
+ OSCData (unsigned int);
+ OSCData (float);
+ OSCData (double);
+ OSCData (uint8_t *, int);
+ //accepts another OSCData objects and clones it
+ OSCData (OSCData *);
+ OSCData (boolean);
+ OSCData (osctime_t);
+
+ //destructor
+ ~OSCData();
+
+ //GETTERS
+ int32_t getInt();
+ float getFloat();
+ double getDouble();
+ int getString(char *);
+ int getString(char *, int);
+ int getString(char *, int, int, int);
+ int getBlob(uint8_t *);
+ int getBlob(uint8_t *, int);
+ int getBlob(uint8_t *, int, int, int);
+ const uint8_t* getBlob();
+ int getBlobLength();
+ bool getBoolean();
+ osctime_t getTime();
+
+ //constructor from byte array with type and length
+ OSCData(char, uint8_t *, int);
+ //fill the passed in buffer with the data
+ //uint8_t * asByteArray();
+
+};
+
+/*
+ based on http://stackoverflow.com/questions/809902/64-bit-ntohl-in-c
+
+ if the system is little endian, it will flip the bits
+ if the system is big endian, it'll do nothing
+ */
+template
+static inline T BigEndian(const T& x)
+{
+ const int one = 1;
+ const char sig = *(char*)&one;
+ if (sig == 0) return x; // for big endian machine just return the input
+ T ret;
+ int size = sizeof(T);
+ char* src = (char*)&x + sizeof(T) - 1;
+ char* dst = (char*)&ret;
+ while (size-- > 0){
+ *dst++ = *src--;
+ }
+ return ret;
+}
+
+#endif
diff --git a/lib/OSC/OSCMatch.c b/lib/OSC/OSCMatch.c
new file mode 100644
index 0000000..ce4c727
--- /dev/null
+++ b/lib/OSC/OSCMatch.c
@@ -0,0 +1,307 @@
+#define OSC_MATCH_ENABLE_2STARS 1
+#define OSC_MATCH_ENABLE_NSTARS 1
+/*
+ Written by John MacCallum, The Center for New Music and Audio Technologies,
+ University of California, Berkeley. Copyright (c) 2009, The Regents of
+ the University of California (Regents).
+ Permission to use, copy, modify, distribute, and distribute modified versions
+ of this software and its documentation without fee and without a signed
+ licensing agreement, is hereby granted, provided that the above copyright
+ notice, this paragraph and the following two paragraphs appear in all copies,
+ modifications, and distributions.
+
+ IN NO EVENT SHALL REGENTS BE LIABLE TO ANY PARTY FOR DIRECT, INDIRECT,
+ SPECIAL, INCIDENTAL, OR CONSEQUENTIAL DAMAGES, INCLUDING LOST PROFITS, ARISING
+ OUT OF THE USE OF THIS SOFTWARE AND ITS DOCUMENTATION, EVEN IF REGENTS HAS
+ BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+
+ REGENTS SPECIFICALLY DISCLAIMS ANY WARRANTIES, INCLUDING, BUT NOT LIMITED TO,
+ THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
+ PURPOSE. THE SOFTWARE AND ACCOMPANYING DOCUMENTATION, IF ANY, PROVIDED
+ HEREUNDER IS PROVIDED "AS IS". REGENTS HAS NO OBLIGATION TO PROVIDE
+ MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
+ */
+#include
+#include "OSCMatch.h"
+
+static int osc_match_star(const char *pattern, const char *address);
+static int osc_match_star_r(const char *pattern, const char *address);
+static int osc_match_single_char(const char *pattern, const char *address);
+static int osc_match_bracket(const char *pattern, const char *address);
+static int osc_match_curly_brace(const char *pattern, const char *address);
+
+int osc_match(const char *pattern, const char *address, int *pattern_offset, int *address_offset)
+{
+ if(!strcmp(pattern, address)){
+ *pattern_offset = strlen(pattern);
+ *address_offset = strlen(address);
+ return OSC_MATCH_ADDRESS_COMPLETE | OSC_MATCH_PATTERN_COMPLETE;
+ }
+
+ const char *pattern_start;
+ const char *address_start;
+
+ pattern_start = pattern;
+ address_start = address;
+
+ *pattern_offset = 0;
+ *address_offset = 0;
+
+ while(*address != '\0' && *pattern != '\0'){
+ if(*pattern == '*'){
+ if(!osc_match_star(pattern, address)){
+ return 0;
+ }
+ while(*pattern != '/' && *pattern != '\0'){
+ pattern++;
+ }
+ while(*address != '/' && *address != '\0'){
+ address++;
+ }
+ }else if(*address == '*'){
+ while(*pattern != '/' && *pattern != '\0'){
+ pattern++;
+ }
+ while(*address != '/' && *address != '\0'){
+ address++;
+ }
+ }else{
+ int n = 0;
+ if(!(n = osc_match_single_char(pattern, address))){
+ return 0;
+ }
+ if(*pattern == '['){
+ while(*pattern != ']'){
+ pattern++;
+ }
+ pattern++;
+ address++;
+ }else if(*pattern == '{'){
+ while(*pattern != '}'){
+ pattern++;
+ }
+ pattern++;
+ address += n;
+ }else{
+ pattern++;
+ address++;
+ }
+ }
+ }
+
+ *pattern_offset = pattern - pattern_start;
+ *address_offset = address - address_start;
+
+ int r = 0;
+
+ if(*address == '\0') {
+ r |= OSC_MATCH_ADDRESS_COMPLETE;
+ }
+
+ if(*pattern == '\0') {
+ r |= OSC_MATCH_PATTERN_COMPLETE;
+ }
+
+ return r;
+}
+
+static int osc_match_star(const char *pattern, const char *address)
+{
+ const char *address_start = address;
+ const char *pattern_start = pattern;
+ int num_stars = 0;
+ if(*address == '\0') { return 0; }
+ while(*address != '/' && *address != '\0'){
+ address++;
+ }
+ while(*pattern != '/' && *pattern != '\0'){
+ if(*pattern == '*'){
+ num_stars++;
+ }
+ pattern++;
+ }
+ pattern--;
+ address--;
+ switch(num_stars){
+ case 1:
+ {
+ const char *pp = pattern, *aa = address;
+ while(*pp != '*'){
+ if(!(osc_match_single_char(pp, aa))){
+ return 0;
+ }
+ if(*pp == ']' || *pp == '}'){
+ while(*pp != '[' && *pp != '{'){
+ pp--;
+ }
+ }
+ pp--;
+ aa--;
+ }
+ }
+ break;
+ case 2:
+#if (OSC_MATCH_ENABLE_2STARS == 1)
+ {
+ const char *pp = pattern, *aa = address;
+ while(*pp != '*'){
+ if(!(osc_match_single_char(pp, aa))){
+ return 0;
+ }
+ if(*pp == ']' || *pp == '}'){
+ while(*pp != '[' && *pp != '{'){
+ pp--;
+ }
+ }
+ pp--;
+ aa--;
+ }
+ aa++; // we want to start one character forward to allow the star to match nothing
+ const char *star2 = pp;
+ const char *test = aa;
+ int i = 0;
+ while(test > address_start){
+ pp = star2 - 1;
+ aa = test - 1;
+ i++;
+ while(*pp != '*'){
+ if(!osc_match_single_char(pp, aa)){
+ break;
+ }
+ if(*pp == ']' || *pp == '}'){
+ while(*pp != '[' && *pp != '{'){
+ pp--;
+ }
+ }
+ pp--;
+ aa--;
+ }
+ if(pp == pattern_start){
+ return 1;
+ }
+ test--;
+ }
+ return 0;
+ }
+ break;
+#else
+ return 0;
+#endif
+ default:
+#if (OSC_MATCH_ENABLE_NSTARS == 1)
+ return osc_match_star_r(pattern_start, address_start);
+ break;
+#else
+ return 0;
+#endif
+ }
+ return 1;
+}
+
+#if (OSC_MATCH_ENABLE_NSTARS == 1)
+static int osc_match_star_r(const char *pattern, const char *address)
+{
+ if(*address == '/' || *address == '\0'){
+ if(*pattern == '/' || *pattern == '\0' || (*pattern == '*' && ((*(pattern + 1) == '/') || *(pattern + 1) == '\0'))){
+ return 1;
+ }else{
+ return 0;
+ }
+ }
+ if(*pattern == '*'){
+ if(osc_match_star_r(pattern + 1, address)){
+ return 1;
+ }else{
+ return osc_match_star_r(pattern, address + 1);
+ }
+ }else{
+ if(!osc_match_single_char(pattern, address)){
+ return 0;
+ }
+ if(*pattern == '[' || *pattern == '{'){
+ while(*pattern != ']' && *pattern != '}'){
+ pattern++;
+ }
+ }
+ return osc_match_star_r(pattern + 1, address + 1);
+ }
+}
+#endif
+
+static int osc_match_single_char(const char *pattern, const char *address)
+{
+ switch(*pattern){
+ case '[':
+ return osc_match_bracket(pattern, address);
+ case ']':
+ while(*pattern != '['){
+ pattern--;
+ }
+ return osc_match_bracket(pattern, address);
+ case '{':
+ return osc_match_curly_brace(pattern, address);
+ case '}':
+ while(*pattern != '{'){
+ pattern--;
+ }
+ return osc_match_curly_brace(pattern, address);
+ case '?':
+ return 1;
+ default:
+ if(*pattern == *address){
+ return 1;
+ }else{
+ return 0;
+ }
+ }
+ return 0;
+}
+
+static int osc_match_bracket(const char *pattern, const char *address)
+{
+ pattern++;
+ int val = 1;
+ if(*pattern == '!'){
+ pattern++;
+ val = 0;
+ }
+ int matched = !val;
+ while(*pattern != ']' && *pattern != '\0'){
+ // the character we're on now is the beginning of a range
+ if(*(pattern + 1) == '-'){
+ if(*address >= *pattern && *address <= *(pattern + 2)){
+ matched = val;
+ break;
+ }else{
+ pattern += 3;
+ }
+ }else{
+ // just test the character
+ if(*pattern == *address){
+ matched = val;
+ break;
+ }
+ pattern++;
+ }
+ }
+ return matched;
+}
+
+static int osc_match_curly_brace(const char *pattern, const char *address)
+{
+ pattern++;
+ const char *ptr = pattern;
+ while(*ptr != '}' && *ptr != '\0' && *ptr != '/'){
+ while(*ptr != '}' && *ptr != '\0' && *ptr != '/' && *ptr != ','){
+ ptr++;
+ }
+ int n = ptr - pattern;
+ if(!strncmp(pattern, address, n)){
+ return n;
+ }else{
+ ptr++;
+ pattern = ptr;
+ }
+ }
+ return 0;
+}
\ No newline at end of file
diff --git a/lib/OSC/OSCMatch.h b/lib/OSC/OSCMatch.h
new file mode 100644
index 0000000..a73d26f
--- /dev/null
+++ b/lib/OSC/OSCMatch.h
@@ -0,0 +1,78 @@
+/*
+ Written by John MacCallum, The Center for New Music and Audio Technologies,
+ University of California, Berkeley. Copyright (c) 2009, The Regents of
+ the University of California (Regents).
+ Permission to use, copy, modify, distribute, and distribute modified versions
+ of this software and its documentation without fee and without a signed
+ licensing agreement, is hereby granted, provided that the above copyright
+ notice, this paragraph and the following two paragraphs appear in all copies,
+ modifications, and distributions.
+
+ IN NO EVENT SHALL REGENTS BE LIABLE TO ANY PARTY FOR DIRECT, INDIRECT,
+ SPECIAL, INCIDENTAL, OR CONSEQUENTIAL DAMAGES, INCLUDING LOST PROFITS, ARISING
+ OUT OF THE USE OF THIS SOFTWARE AND ITS DOCUMENTATION, EVEN IF REGENTS HAS
+ BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+
+ REGENTS SPECIFICALLY DISCLAIMS ANY WARRANTIES, INCLUDING, BUT NOT LIMITED TO,
+ THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
+ PURPOSE. THE SOFTWARE AND ACCOMPANYING DOCUMENTATION, IF ANY, PROVIDED
+ HEREUNDER IS PROVIDED "AS IS". REGENTS HAS NO OBLIGATION TO PROVIDE
+ MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
+ */
+
+#ifndef __OSC_MATCH_H__
+#define __OSC_MATCH_H__
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+ /**
+ * Switch this off to disable matching against a pattern with 2 stars
+ */
+ //#define OSC_MATCH_ENABLE_2STARS 1
+ /**
+ * Switch this off to disable matching against a pattern with more than 2 stars which will
+ * be done recursively.
+ */
+ //#define OSC_MATCH_ENABLE_NSTARS 1
+
+ /**
+ * Return code for osc_match() that indicates that the entire address was successfully matched
+ */
+#define OSC_MATCH_ADDRESS_COMPLETE 1
+
+ /**
+ * Return code for osc_match() that indicates that the entire pattern was successfully matched
+ */
+#define OSC_MATCH_PATTERN_COMPLETE 2
+ /*
+ typedef struct _osc_callback {
+ const char* address; // Address
+ struct _osc_callback *child; // RAM
+ struct _osc_callback *sibling; // RAM
+ struct _osc_callback *parent; // RAM
+ int callback; // ROM
+ } osc_callback;
+ */
+
+ /**
+ * Match a pattern against an address. In the case of a partial match, pattern_offset
+ * and address_offset will contain the number of bytes into their respective strings
+ * where the match failed.
+ *
+ * @param pattern The pattern to match
+ * @param address The address to match
+ * @param pattern_offset The number of bytes into the pattern that were matched successfully
+ * @param address_offset The number of bytes into the address that were matched successfully
+ * @return 0 if the match failed altogether, or an or'd combination of OSC_MATCH_ADDRESS_COMPLETE and
+ * OSC_MATCH_PATTERN_COMPLETE.
+ */
+ int osc_match(const char *pattern, const char *address, int *pattern_offset, int *address_offset);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif // __OSC_MATCH_H__
+
diff --git a/lib/OSC/OSCMessage.cpp b/lib/OSC/OSCMessage.cpp
new file mode 100644
index 0000000..9a18fe8
--- /dev/null
+++ b/lib/OSC/OSCMessage.cpp
@@ -0,0 +1,791 @@
+/*
+ Written by Yotam Mann, The Center for New Music and Audio Technologies,
+ University of California, Berkeley. Copyright (c) 2012, The Regents of
+ the University of California (Regents).
+
+ Permission to use, copy, modify, distribute, and distribute modified versions
+ of this software and its documentation without fee and without a signed
+ licensing agreement, is hereby granted, provided that the above copyright
+ notice, this paragraph and the following two paragraphs appear in all copies,
+ modifications, and distributions.
+
+ IN NO EVENT SHALL REGENTS BE LIABLE TO ANY PARTY FOR DIRECT, INDIRECT,
+ SPECIAL, INCIDENTAL, OR CONSEQUENTIAL DAMAGES, INCLUDING LOST PROFITS, ARISING
+ OUT OF THE USE OF THIS SOFTWARE AND ITS DOCUMENTATION, EVEN IF REGENTS HAS
+ BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+
+ REGENTS SPECIFICALLY DISCLAIMS ANY WARRANTIES, INCLUDING, BUT NOT LIMITED TO,
+ THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
+ PURPOSE. THE SOFTWARE AND ACCOMPANYING DOCUMENTATION, IF ANY, PROVIDED
+ HEREUNDER IS PROVIDED "AS IS". REGENTS HAS NO OBLIGATION TO PROVIDE
+ MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
+
+ For bug reports and feature requests please email me at yotam@cnmat.berkeley.edu
+ */
+
+#include "OSCMessage.h"
+#include "OSCMatch.h"
+#include "OSCTiming.h"
+
+extern osctime_t zerotime;
+/*=============================================================================
+ CONSTRUCTORS / DESTRUCTOR
+=============================================================================*/
+
+//constructor with address
+OSCMessage::OSCMessage(const char * _address){
+ setupMessage();
+ setAddress(_address);
+}
+
+//constructor with nothing
+//just a placeholder since the message is invalid
+OSCMessage::OSCMessage(){
+ setupMessage();
+ error = INVALID_OSC;
+}
+
+//variable length constructor
+//for example OSCMessage msg("/address", "isf", 1, "two", 3.0);
+/*
+OSCMessage::OSCMessage(const char * _address, char * types, ... ){
+ setupMessage(_address);
+}
+ */
+
+//sets up a new message
+void OSCMessage::setupMessage(){
+ address = NULL;
+ //setup the attributes
+ dataCount = 0;
+ error = OSC_OK;
+ //setup the space for data
+ data = NULL;
+ //setup for filling the message
+ incomingBuffer = NULL;
+ incomingBufferSize = 0;
+ incomingBufferFree = 0;
+ clearIncomingBuffer();
+ //set the decode state
+ decodeState = STANDBY;
+}
+
+//DESTRUCTOR
+OSCMessage::~OSCMessage(){
+ //free everything that needs to be freed
+ //free the address
+ free(address);
+ //free the data
+ empty();
+ //free the filling buffer
+ free(incomingBuffer);
+}
+
+OSCMessage& OSCMessage::empty(){
+ error = OSC_OK;
+ //free each of the data in the array
+ for (int i = 0; i < dataCount; i++){
+ const auto datum = getOSCData(i);
+ //explicitly destruct the data
+ //datum->~OSCData();
+ delete datum;
+ }
+ //and free the array
+ free(data);
+ data = NULL;
+ dataCount = 0;
+ decodeState = STANDBY;
+ clearIncomingBuffer();
+ return *this;
+}
+
+//COPY
+OSCMessage::OSCMessage(OSCMessage * msg){
+ //start with a message with the same address
+ setupMessage();
+ setAddress(msg->address);
+ //add each of the data to the other message
+ for (int i = 0; i < msg->dataCount; i++){
+ add(msg->data[i]);
+ }
+}
+
+/*=============================================================================
+ GETTING DATA
+=============================================================================*/
+
+OSCData * OSCMessage::getOSCData(int position){
+ if (position < dataCount){
+ const auto datum = data[position];
+ return datum;
+ } else {
+ error = INDEX_OUT_OF_BOUNDS;
+ return nullptr;
+ }
+}
+
+int32_t OSCMessage::getInt(int position){
+ const auto datum = getOSCData(position);
+ if (!hasError()){
+ return datum->getInt();
+ } else {
+ return 0;
+ }
+}
+osctime_t OSCMessage::getTime(int position){
+ const auto datum = getOSCData(position);
+ if (!hasError()){
+ return datum->getTime();
+ } else {
+ return zerotime;
+ }
+}
+float OSCMessage::getFloat(int position){
+ const auto datum = getOSCData(position);
+ if (!hasError()){
+ return datum->getFloat();
+ } else {
+ return 0.0f;
+ }
+}
+
+double OSCMessage::getDouble(int position){
+ const auto datum = getOSCData(position);
+ if (!hasError()){
+ return datum->getDouble();
+ } else {
+
+ return 0.0;
+ }
+}
+
+bool OSCMessage::getBoolean(int position){
+ const auto datum = getOSCData(position);
+ if (!hasError()){
+ return datum->getBoolean();
+ } else {
+ return false;
+ }
+}
+
+
+int OSCMessage::getString(int position, char * buffer){
+ const auto datum = getOSCData(position);
+ if (!hasError()){
+ return datum->getString(buffer, datum->bytes);
+ } else {
+ return -1;
+ }
+}
+
+int OSCMessage::getString(int position, char * buffer, int bufferSize){
+ const auto datum = getOSCData(position);
+ if (!hasError()){
+ //the number of bytes to copy is the smaller between the buffer size and the datum's byte length
+ int copyBytes = bufferSize < datum->bytes? bufferSize : datum->bytes;
+ return datum->getString(buffer, copyBytes);
+ } else {
+ return -1;
+ }
+}
+
+int OSCMessage::getString(int position, char * buffer, int bufferSize, int offset, int size){
+ const auto datum = getOSCData(position);
+ if (!hasError()){
+ //the number of bytes to copy is the smaller between the buffer size and the datum's byte length
+ int copyBytes = bufferSize < datum->bytes? bufferSize : datum->bytes;
+ return datum->getString(buffer, copyBytes, offset, size);
+ } else {
+ return -1;
+ }
+}
+
+
+int OSCMessage::getBlob(int position, uint8_t * buffer){
+ const auto datum = getOSCData(position);
+ if (!hasError()){
+ return datum->getBlob(buffer);
+ } else {
+ return -1;
+ }
+}
+
+int OSCMessage::getBlob(int position, uint8_t * buffer, int bufferSize){
+ const auto datum = getOSCData(position);
+ if (!hasError()){
+ return datum->getBlob(buffer, bufferSize);
+ } else {
+ return -1;
+ }
+}
+
+int OSCMessage::getBlob(int position, uint8_t * buffer, int bufferSize, int offset, int size){
+ const auto datum = getOSCData(position);
+ if (!hasError()){
+ return datum->getBlob(buffer, bufferSize, offset, size);
+ } else {
+ return -1;
+ }
+}
+
+const uint8_t* OSCMessage::getBlob(int position) {
+ const auto datum = getOSCData(position);
+ if(!hasError()) {
+ return datum->getBlob();
+ } else {
+ return nullptr;
+ }
+}
+
+uint32_t OSCMessage::getBlobLength(int position)
+{
+ const auto datum = getOSCData(position);
+ if (!hasError()){
+ return datum->getBlobLength();
+ } else {
+ return 0;
+ }
+
+}
+
+char OSCMessage::getType(int position){
+ const auto datum = getOSCData(position);
+ if (!hasError()){
+ return datum->type;
+ } else {
+ return '\0';
+ }
+}
+
+int OSCMessage::getDataLength(int position){
+ const auto datum = getOSCData(position);
+ if (!hasError()){
+ return datum->bytes;
+ } else {
+ return 0;
+ }
+}
+
+/*=============================================================================
+ TESTING DATA
+=============================================================================*/
+
+bool OSCMessage::testType(int position, char type){
+ const auto datum = getOSCData(position);
+ if (!hasError()){
+ return datum->type == type;
+ } else {
+ return false;
+ }
+}
+
+bool OSCMessage::isInt(int position){
+ return testType(position, 'i');
+}
+
+bool OSCMessage::isTime(int position){
+ return testType(position, 't');
+}
+
+
+bool OSCMessage::isFloat(int position){
+ return testType(position, 'f');
+}
+
+bool OSCMessage::isBlob(int position){
+ return testType(position, 'b');
+}
+
+bool OSCMessage::isChar(int position){
+ return testType(position, 'c');
+}
+
+bool OSCMessage::isString(int position){
+ return testType(position, 's');
+}
+
+bool OSCMessage::isDouble(int position){
+ return testType(position, 'd');
+}
+bool OSCMessage::isBoolean(int position){
+ return testType(position, 'T') || testType(position, 'F');
+}
+
+
+/*=============================================================================
+ PATTERN MATCHING
+=============================================================================*/
+
+int OSCMessage::match(const char * pattern, int addr_offset){
+ int pattern_offset;
+ int address_offset;
+ int ret = osc_match(address + addr_offset, pattern, &pattern_offset, &address_offset);
+ char * next = (char *) (address + addr_offset + pattern_offset);
+ if (ret==3){
+ return pattern_offset;
+ } else if (pattern_offset > 0 && *next == '/'){
+ return pattern_offset;
+ } else {
+ return 0;
+ }
+}
+
+bool OSCMessage::fullMatch( const char * pattern, int addr_offset){
+ int pattern_offset;
+ int address_offset;
+ int ret = osc_match(address + addr_offset, pattern, &pattern_offset, &address_offset );
+ return (ret==3);
+}
+
+bool OSCMessage::dispatch(const char * pattern, void (*callback)(OSCMessage &), int addr_offset){
+ if (fullMatch(pattern, addr_offset)){
+ callback(*this);
+ return true;
+ } else {
+ return false;
+ }
+}
+
+bool OSCMessage::route(const char * pattern, void (*callback)(OSCMessage &, int), int initial_offset){
+ int match_offset = match(pattern, initial_offset);
+ if (match_offset>0){
+ callback(*this, match_offset + initial_offset);
+ return true;
+ } else {
+ return false;
+ }
+}
+
+/*=============================================================================
+ ADDRESS
+ =============================================================================*/
+
+int OSCMessage::getAddress(char * buffer, int offset){
+ int result = strlen(address);
+ if (result > offset)
+ strcpy(buffer, address+offset);
+ else
+ *buffer = 0;
+ return result - offset; // could be negative!
+}
+
+int OSCMessage::getAddress(char * buffer, int offset, int len){
+ int result = strlen(address);
+
+ if (result > offset)
+ {
+ strncpy(buffer, address+offset, len); // N.B. NOT guaranteed to null-terminate! So...
+ buffer[len-1] = 0; // ...prevent strlen() blowing up
+ }
+ else
+ *buffer = 0;
+ return strlen(buffer);
+}
+
+const char* OSCMessage::getAddress(){
+ return address;
+}
+
+int OSCMessage::getAddressLength(int offset)
+{
+ int result = (int) strlen(address) - offset;
+ if (result < 0) // offset past end!
+ result = 0; // do the best we can
+ return result;
+}
+
+OSCMessage& OSCMessage::setAddress(const char * _address){
+ //free the previous address
+ free(address); // are we sure address was allocated?
+ //copy the address
+ char * addressMemory = (char *) malloc( (strlen(_address) + 1) * sizeof(char) );
+ if (addressMemory == NULL){
+ error = ALLOCFAILED;
+ address = NULL;
+ } else {
+ strcpy(addressMemory, _address);
+ address = addressMemory;
+ }
+ return *this;
+}
+
+/*=============================================================================
+ SIZE
+=============================================================================*/
+
+#ifdef SLOWpadcalculation
+int OSCMessage::padSize(int _bytes){
+ int space = (_bytes + 3) / 4;
+ space *= 4;
+ return space - _bytes;
+}
+#else
+static inline int padSize(int bytes) { return (4- (bytes&03))&3; }
+#endif
+//returns the number of OSCData in the OSCMessage
+int OSCMessage::size(){
+ return dataCount;
+}
+
+int OSCMessage::bytes(){
+ int messageSize = 0;
+ //send the address
+ int addrLen = strlen(address) + 1;
+ messageSize += addrLen;
+ //padding amount
+ int addrPad = padSize(addrLen);
+ messageSize += addrPad;
+ //add the comma separator
+ messageSize += 1;
+ //add the types
+ messageSize += dataCount;
+ //pad the types
+ int typePad = padSize(dataCount + 1); //for the comma
+ if (typePad == 0){
+ typePad = 4; // to make sure the type string is null terminated
+ }
+ messageSize+=typePad;
+ //then the data
+ for (int i = 0; i < dataCount; i++){
+ const auto datum = getOSCData(i);
+ messageSize+=datum->bytes;
+ messageSize += padSize(datum->bytes);
+ }
+ return messageSize;
+}
+
+/*=============================================================================
+ ERROR HANDLING
+=============================================================================*/
+
+bool OSCMessage::hasError(){
+ if(error != OSC_OK) return true;
+ //test each of the data
+ for (int i = 0; i < dataCount; i++){
+ if(getOSCData(i)->error) return true;
+ }
+ return false;
+}
+
+OSCErrorCode OSCMessage::getError(){
+ return error;
+}
+
+/*=============================================================================
+ SENDING
+ =============================================================================*/
+
+OSCMessage& OSCMessage::send(Print &p){
+ //don't send a message with errors
+ if (hasError()){
+ return *this;
+ }
+ uint8_t nullChar = '\0';
+ //send the address
+ int addrLen = strlen(address) + 1;
+ //padding amount
+ int addrPad = padSize(addrLen);
+ //write it to the stream
+ p.write((uint8_t *) address, addrLen);
+ //add the padding
+ while(addrPad--){
+ p.write(nullChar);
+ }
+ //add the comma separator
+ p.write((uint8_t) ',');
+ //add the types
+#ifdef PAULSSUGGESTION
+ // Paul suggested buffering on the stack
+ // to improve performance. The problem is this could exhaust the stack
+ // for long complex messages
+ {
+ uint8_t typstr[dataCount];
+
+ for (int i = 0; i < dataCount; i++){
+ typstr[i] = getType(i);
+ }
+ p.write(typstr,dataCount);
+ }
+#else
+ for (int i = 0; i < dataCount; i++){
+ p.write((uint8_t) getType(i));
+ }
+#endif
+ //pad the types
+ int typePad = padSize(dataCount + 1); // 1 is for the comma
+ if (typePad == 0){
+ typePad = 4; // This is because the type string has to be null terminated
+ }
+ while(typePad--){
+ p.write(nullChar);
+ }
+ //write the data
+ for (int i = 0; i < dataCount; i++){
+ const auto datum = getOSCData(i);
+ if ((datum->type == 's') || (datum->type == 'b')){
+ p.write(datum->data.b, datum->bytes);
+ int dataPad = padSize(datum->bytes);
+ while(dataPad--){
+ p.write(nullChar);
+ }
+ } else if (datum->type == 'd'){
+ double d = BigEndian(datum->data.d);
+ uint8_t * ptr = (uint8_t *) &d;
+ p.write(ptr, 8);
+ } else if (datum->type == 't'){
+ osctime_t time = datum->data.time;
+ uint32_t d = BigEndian(time.seconds);
+ uint8_t * ptr = (uint8_t *) &d;
+ p.write(ptr, 4);
+ d = BigEndian(time.fractionofseconds);
+ ptr = (uint8_t *) &d;
+ p.write(ptr, 4);
+
+ } else if (datum->type == 'T' || datum->type == 'F')
+ { }
+ else { // float or int
+ uint32_t i = BigEndian(datum->data.i);
+ uint8_t * ptr = (uint8_t *) &i;
+ p.write(ptr, datum->bytes);
+ }
+ }
+ return *this;
+}
+
+/*=============================================================================
+ FILLING
+ =============================================================================*/
+
+OSCMessage& OSCMessage::fill(uint8_t incomingByte){
+ decode(incomingByte);
+ return *this;
+}
+
+OSCMessage& OSCMessage::fill(uint8_t * incomingBytes, int length){
+ while (length--){
+ decode(*incomingBytes++);
+ }
+ return *this;
+}
+
+/*=============================================================================
+ DECODING
+ =============================================================================*/
+
+void OSCMessage::decodeAddress(){
+ setAddress((char *) incomingBuffer);
+ //change the error from invalid message
+ error = OSC_OK;
+ clearIncomingBuffer();
+}
+
+void OSCMessage::decodeType(uint8_t incomingByte){
+ char type = incomingByte;
+ add(type);
+}
+
+void OSCMessage::decodeData(uint8_t incomingByte){
+ //get the first OSCData to re-set
+ for (int i = 0; i < dataCount; i++){
+ const auto datum = getOSCData(i);
+ if (datum->error == INVALID_OSC){
+ //set the contents of datum with the data received
+ switch (datum->type){
+ case 'i':
+ if (incomingBufferSize == 4){
+ //parse the buffer as an int
+ union {
+ int32_t i;
+ uint8_t b[4];
+ } u;
+ memcpy(u.b, incomingBuffer, 4);
+ int32_t dataVal = BigEndian(u.i);
+ set(i, dataVal);
+ clearIncomingBuffer();
+ }
+ break;
+ case 'f':
+ if (incomingBufferSize == 4){
+ //parse the buffer as a float
+ union {
+ float f;
+ uint8_t b[4];
+ } u;
+ memcpy(u.b, incomingBuffer, 4);
+ float dataVal = BigEndian(u.f);
+ set(i, dataVal);
+ clearIncomingBuffer();
+ }
+ break;
+ case 'd':
+ if (incomingBufferSize == 8){
+ //parse the buffer as a double
+ union {
+ double d;
+ uint8_t b[8];
+ } u;
+ memcpy(u.b, incomingBuffer, 8);
+ double dataVal = BigEndian(u.d);
+ set(i, dataVal);
+ clearIncomingBuffer();
+ }
+ break;
+ case 't':
+ if (incomingBufferSize == 8){
+ //parse the buffer as a timetag
+ union {
+ osctime_t t;
+ uint8_t b[8];
+ } u;
+ memcpy(u.b, incomingBuffer, 8);
+
+ u.t.seconds = BigEndian(u.t.seconds);
+ u.t.fractionofseconds = BigEndian(u.t.fractionofseconds);
+ set(i, u.t);
+ clearIncomingBuffer();
+ }
+ break;
+
+ case 's':
+ if (incomingByte == 0){
+ char * str = (char *) incomingBuffer;
+ set(i, str);
+ clearIncomingBuffer();
+ decodeState = DATA_PADDING;
+ }
+ break;
+ case 'b':
+ if (incomingBufferSize > 4){
+ //compute the expected blob size
+ union {
+ uint32_t i;
+ uint8_t b[4];
+ } u;
+ memcpy(u.b, incomingBuffer, 4);
+ uint32_t blobLength = BigEndian(u.i);
+ if (incomingBufferSize == (int)(blobLength + 4)){
+ set(i, incomingBuffer + 4, blobLength);
+ clearIncomingBuffer();
+ decodeState = DATA_PADDING;
+ }
+
+ }
+ break;
+ }
+ //break out of the for loop once we've selected the first invalid message
+ break;
+ }
+ }
+}
+
+//does not validate the incoming OSC for correctness
+void OSCMessage::decode(uint8_t incomingByte){
+ addToIncomingBuffer(incomingByte);
+ switch (decodeState){
+ case STANDBY:
+ if (incomingByte == '/'){
+ decodeState = ADDRESS;
+ }
+ break;
+ case ADDRESS:
+ if (incomingByte == 0){
+ //end of the address
+ //decode the address
+ decodeAddress();
+ //next state
+ decodeState = ADDRESS_PADDING;
+ }
+ break;
+ case ADDRESS_PADDING:
+ //it does not count the padding
+ if (incomingByte==','){
+ //next state
+ decodeState = TYPES;
+ clearIncomingBuffer();
+ }
+ break;
+ case TYPES:
+ if (incomingByte != 0){
+ //next state
+ decodeType(incomingByte);
+ } else {
+ decodeState = TYPES_PADDING;
+ }
+ //FALL THROUGH to test if it should go to the data state
+ case TYPES_PADDING: {
+ //compute the padding size for the types
+ //to determine the start of the data section
+ int typePad = padSize(dataCount + 1); // 1 is the comma
+ if (typePad == 0){
+ typePad = 4; // to make sure it will be null terminated
+ }
+ if (incomingBufferSize == (typePad + dataCount)){
+ clearIncomingBuffer();
+ decodeState = DATA;
+ }
+ }
+ break;
+ case DATA:
+ decodeData(incomingByte);
+ break;
+ case DATA_PADDING:{
+ //get the last valid data
+ for (int i = dataCount - 1; i >= 0; i--){
+ const auto datum = getOSCData(i);
+ if (datum->error == OSC_OK){
+ //compute the padding size for the data
+ int dataPad = padSize(datum->bytes);
+ // if there is no padding required, switch back to DATA, and don't clear the incomingBuffer because it holds next data
+ if (dataPad == 0){
+ decodeState = DATA;
+ }
+ else if (incomingBufferSize == dataPad){
+ clearIncomingBuffer();
+ decodeState = DATA;
+ }
+ break;
+ }
+ }
+ }
+ break;
+ case DONE:
+ break; // TODO: is this correct? - was missing from original code, it did this by default
+ }
+}
+
+
+/*=============================================================================
+ INCOMING BUFFER MANAGEMENT
+ =============================================================================*/
+#define OSCPREALLOCATEIZE 16
+void OSCMessage::addToIncomingBuffer(uint8_t incomingByte){
+ //realloc some space for the new byte and stick it on the end
+ if(incomingBufferFree>0)
+ {
+ incomingBuffer[incomingBufferSize++] = incomingByte;
+ incomingBufferFree--;
+ }
+ else
+ {
+
+ incomingBuffer = (uint8_t *) realloc ( incomingBuffer, incomingBufferSize + 1 + OSCPREALLOCATEIZE);
+ if (incomingBuffer != NULL){
+ incomingBuffer[incomingBufferSize++] = incomingByte;
+ incomingBufferFree = OSCPREALLOCATEIZE;
+ } else {
+ error = ALLOCFAILED;
+ }
+ }
+}
+
+void OSCMessage::clearIncomingBuffer(){
+ incomingBuffer = (uint8_t *) realloc ( incomingBuffer, OSCPREALLOCATEIZE);
+ if (incomingBuffer != NULL){
+ incomingBufferFree = OSCPREALLOCATEIZE;
+ } else {
+ error = ALLOCFAILED;
+ incomingBuffer = NULL;
+
+ }
+ incomingBufferSize = 0;
+}
diff --git a/lib/OSC/OSCMessage.h b/lib/OSC/OSCMessage.h
new file mode 100644
index 0000000..3d9d448
--- /dev/null
+++ b/lib/OSC/OSCMessage.h
@@ -0,0 +1,350 @@
+/*
+ Written by Yotam Mann, The Center for New Music and Audio Technologies,
+ University of California, Berkeley. Copyright (c) 2012, The Regents of
+ the University of California (Regents).
+
+ Permission to use, copy, modify, distribute, and distribute modified versions
+ of this software and its documentation without fee and without a signed
+ licensing agreement, is hereby granted, provided that the above copyright
+ notice, this paragraph and the following two paragraphs appear in all copies,
+ modifications, and distributions.
+
+ IN NO EVENT SHALL REGENTS BE LIABLE TO ANY PARTY FOR DIRECT, INDIRECT,
+ SPECIAL, INCIDENTAL, OR CONSEQUENTIAL DAMAGES, INCLUDING LOST PROFITS, ARISING
+ OUT OF THE USE OF THIS SOFTWARE AND ITS DOCUMENTATION, EVEN IF REGENTS HAS
+ BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+
+ REGENTS SPECIFICALLY DISCLAIMS ANY WARRANTIES, INCLUDING, BUT NOT LIMITED TO,
+ THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
+ PURPOSE. THE SOFTWARE AND ACCOMPANYING DOCUMENTATION, IF ANY, PROVIDED
+ HEREUNDER IS PROVIDED "AS IS". REGENTS HAS NO OBLIGATION TO PROVIDE
+ MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
+
+ For bug reports and feature requests please email me at yotam@cnmat.berkeley.edu
+ */
+
+#ifndef OSCMESSAGE_h
+#define OSCMESSAGE_h
+
+#include "OSCData.h"
+#include
+
+
+class OSCMessage
+{
+
+private:
+
+ //friends
+ friend class OSCBundle;
+
+
+/*=============================================================================
+ PRIVATE VARIABLES
+=============================================================================*/
+
+ //the address
+ char * address;
+
+ //the data
+ OSCData ** data;
+
+ //the number of OSCData in the data array
+ int dataCount;
+
+ //error codes for potential runtime problems
+ OSCErrorCode error;
+
+/*=============================================================================
+ DECODING INCOMING BYTES
+ =============================================================================*/
+
+ //the decoding states for incoming bytes
+ enum DecodeState {
+ STANDBY,
+ ADDRESS,
+ ADDRESS_PADDING,
+ TYPES,
+ TYPES_PADDING,
+ DATA,
+ DATA_PADDING,
+ DONE,
+ } decodeState;
+
+ //stores incoming bytes until they can be decoded
+ uint8_t * incomingBuffer;
+ int incomingBufferSize; // how many bytes are stored
+ int incomingBufferFree; // how many bytes are allocated but unused
+
+ //adds a byte to the buffer
+ void addToIncomingBuffer(uint8_t);
+ //clears the incoming buffer
+ void clearIncomingBuffer();
+
+ //decoding function
+ void decode(uint8_t);
+ void decodeAddress();
+ void decodeType(uint8_t);
+ void decodeData(uint8_t);
+
+/*=============================================================================
+ HELPER FUNCTIONS
+=============================================================================*/
+
+ void setupMessage();
+
+ //compares the OSCData's type char to a test char
+ bool testType(int position, char type);
+
+ //returns the number of bytes to pad to make it 4-bit aligned
+ // int padSize(int bytes);
+
+public:
+
+ //returns the OSCData at that position
+ OSCData * getOSCData(int);
+
+/*=============================================================================
+ CONSTRUCTORS / DESTRUCTOR
+=============================================================================*/
+
+ //new constructor needs an address
+ OSCMessage (const char * _address);
+ //no address
+ //placeholder since it's invalid OSC
+ OSCMessage();
+
+ //can optionally accept all of the data after the address
+ //OSCMessage(const char * _address, char * types, ... );
+ //created from another OSCMessage
+ OSCMessage (OSCMessage *);
+
+ //DESTRUCTOR
+ ~OSCMessage();
+
+ //empties all of the data
+ OSCMessage& empty();
+
+/*=============================================================================
+ SETTING DATA
+=============================================================================*/
+
+ //returns the OSCMessage so that multiple 'add's can be strung together
+ template
+ OSCMessage& add(T datum){
+ //make a piece of data
+ OSCData * d = new OSCData(datum);
+ //check if it has any errors
+ if (d->error == ALLOCFAILED){
+ error = ALLOCFAILED;
+ } else {
+ //resize the data array
+ OSCData ** dataMem = (OSCData **) realloc(data, sizeof(OSCData *) * (dataCount + 1));
+ if (dataMem == NULL){
+ error = ALLOCFAILED;
+ } else {
+ data = dataMem;
+ //add data to the end of the array
+ data[dataCount] = d;
+ //increment the data size
+ dataCount++;
+ }
+ }
+ return *this;
+ }
+
+ //blob specific add
+ OSCMessage& add(uint8_t * blob, int length){
+ //make a piece of data
+ OSCData * d = new OSCData(blob, length);
+ //check if it has any errors
+ if (d->error == ALLOCFAILED){
+ error = ALLOCFAILED;
+ } else {
+ //resize the data array
+ OSCData ** dataMem = (OSCData **) realloc(data, sizeof(OSCData *) * (dataCount + 1));
+ if (dataMem == NULL){
+ error = ALLOCFAILED;
+ } else {
+ data = dataMem;
+ //add data to the end of the array
+ data[dataCount] = d;
+ //increment the data size
+ dataCount++;
+ }
+ }
+ return *this;
+ }
+
+ //sets the data at a position
+ template
+ OSCMessage& set(int position, T datum){
+ if (position < dataCount){
+ //replace the OSCData with a new one
+ OSCData * oldDatum = getOSCData(position);
+ //destroy the old one
+ delete oldDatum;
+ //make a new one
+ OSCData * newDatum = new OSCData(datum);
+ //test if there was an error
+ if (newDatum->error == ALLOCFAILED){
+ error = ALLOCFAILED;
+ } else {
+ //otherwise, put it in the data array
+ data[position] = newDatum;
+ }
+ } else if (position == (dataCount)){
+ //add the data to the end
+ add(datum);
+ } else {
+ //else out of bounds error
+ error = INDEX_OUT_OF_BOUNDS;
+ }
+ return *this;
+ }
+
+ //blob specific setter
+ OSCMessage& set(int position, uint8_t * blob, int length){
+ if (position < dataCount){
+ //replace the OSCData with a new one
+ OSCData * oldDatum = getOSCData(position);
+ //destroy the old one
+ delete oldDatum;
+ //make a new one
+ OSCData * newDatum = new OSCData(blob, length);
+ //test if there was an error
+ if (newDatum->error == ALLOCFAILED){
+ error = ALLOCFAILED;
+ } else {
+ //otherwise, put it in the data array
+ data[position] = newDatum;
+ }
+ } else if (position == (dataCount)){
+ //add the data to the end
+ add(blob, length);
+ } else {
+ //else out of bounds error
+ error = INDEX_OUT_OF_BOUNDS;
+ }
+ return *this;
+ }
+
+ OSCMessage& setAddress(const char *);
+
+/*=============================================================================
+ GETTING DATA
+
+ getters take a position as an argument
+=============================================================================*/
+
+ int32_t getInt(int);
+ osctime_t getTime(int);
+
+ float getFloat(int);
+ double getDouble(int);
+ bool getBoolean(int);
+
+ //return the copied string's length
+ int getString(int, char *);
+ //check that it won't overflow the passed buffer's size with a third argument
+ int getString(int, char *, int);
+ //offset and size can be defined in order to only query a part of the string
+ int getString(int, char *, int, int, int);
+
+ //returns the number of unsigned int8's copied into the buffer
+ int getBlob(int, uint8_t *);
+ //check that it won't overflow the passed buffer's size with a third argument
+ int getBlob(int, uint8_t *, int);
+ //offset and size can be defined in order to only query a part of the blob's content
+ int getBlob(int, uint8_t *, int, int, int);
+ //get pointer to blob
+ const uint8_t* getBlob(int);
+
+
+ // returns the length of blob
+ uint32_t getBlobLength(int position);
+
+ //returns the number of bytes of the data at that position
+ int getDataLength(int);
+
+ //returns the type at the position
+ char getType(int);
+
+ //put the address in the buffer
+ int getAddress(char * buffer, int offset = 0);
+ int getAddress(char * buffer, int offset, int len);
+
+ const char* getAddress();
+
+ // Find out address length so we can create a buffer
+ int getAddressLength(int offset = 0);
+
+
+/*=============================================================================
+ TESTING DATA
+
+ testers take a position as an argument
+=============================================================================*/
+
+ bool isInt(int);
+ bool isFloat(int);
+ bool isBlob(int);
+ bool isChar(int);
+ bool isString(int);
+ bool isDouble(int);
+ bool isBoolean(int);
+ bool isTime(int);
+
+/*=============================================================================
+ PATTERN MATCHING
+=============================================================================*/
+
+ //match the pattern against the address
+ //returns true only for a complete match
+ bool fullMatch( const char * pattern, int = 0);
+
+ //returns the number of characters matched in the address
+ int match( const char * pattern, int = 0);
+
+ //calls the function with the message as the arg if it was a full match
+ bool dispatch(const char * pattern, void (*callback)(OSCMessage &), int = 0);
+
+ //like dispatch, but allows for partial matches
+ //the address match offset is sent as an argument to the callback
+ //also room for an option address offset to allow for multiple nested routes
+ bool route(const char * pattern, void (*callback)(OSCMessage &, int), int = 0);
+
+
+
+/*=============================================================================
+ SIZE
+=============================================================================*/
+
+ //the number of data that the message contains
+ int size();
+
+ //computes the number of bytes the OSCMessage occupies if everything is 32-bit aligned
+ int bytes();
+
+/*=============================================================================
+ TRANSMISSION
+ =============================================================================*/
+
+ //send the message
+ OSCMessage& send(Print &p);
+
+ //fill the message from a byte stream
+ OSCMessage& fill(uint8_t);
+ OSCMessage& fill(uint8_t *, int);
+
+/*=============================================================================
+ ERROR
+=============================================================================*/
+
+ bool hasError();
+
+ OSCErrorCode getError();
+
+};
+
+#endif
diff --git a/lib/OSC/OSCTiming.cpp b/lib/OSC/OSCTiming.cpp
new file mode 100644
index 0000000..1f85073
--- /dev/null
+++ b/lib/OSC/OSCTiming.cpp
@@ -0,0 +1,178 @@
+/*
+ Written by Adrian Freed, The Center for New Music and Audio Technologies,
+ University of California, Berkeley. Copyright (c) 2013, The Regents of
+ the University of California (Regents).
+
+ Permission to use, copy, modify, distribute, and distribute modified versions
+ of this software and its documentation without fee and without a signed
+ licensing agreement, is hereby granted, provided that the above copyright
+ notice, this paragraph and the following two paragraphs appear in all copies,
+ modifications, and distributions.
+
+ IN NO EVENT SHALL REGENTS BE LIABLE TO ANY PARTY FOR DIRECT, INDIRECT,
+ SPECIAL, INCIDENTAL, OR CONSEQUENTIAL DAMAGES, INCLUDING LOST PROFITS, ARISING
+ OUT OF THE USE OF THIS SOFTWARE AND ITS DOCUMENTATION, EVEN IF REGENTS HAS
+ BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+
+ REGENTS SPECIFICALLY DISCLAIMS ANY WARRANTIES, INCLUDING, BUT NOT LIMITED TO,
+ THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
+ PURPOSE. THE SOFTWARE AND ACCOMPANYING DOCUMENTATION, IF ANY, PROVIDED
+ HEREUNDER IS PROVIDED "AS IS". REGENTS HAS NO OBLIGATION TO PROVIDE
+ MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
+
+ For bug reports and feature requests please email me at yotam@cnmat.berkeley.edu
+ */
+
+
+#include "OSCTiming.h"
+
+#if defined(TEENSYDUINO) && defined(__arm__)
+extern volatile uint32_t systick_millis_count;
+static uint32_t savedcount, savedcurrent;
+
+static void latchOscTime()
+{
+
+ uint32_t istatus;
+ uint32_t count, current;
+
+ __disable_irq();
+ current = SYST_CVR;
+ count = systick_millis_count;
+ istatus = SCB_ICSR; // bit 26 indicates if systick exception pending
+ __enable_irq();
+ //systick_current = current;
+ //systick_count = count;
+ //systick_istatus = istatus & SCB_ICSR_PENDSTSET ? 1 : 0;
+ if ((istatus & SCB_ICSR_PENDSTSET) && current > 50) count++;
+ current = ((F_CPU / 1000) - 1) - current;
+ savedcount=count; savedcurrent=current;
+}
+static osctime_t computeOscTime()
+{ //4,294,967,296
+
+
+ osctime_t t;
+
+
+ t.seconds = (( uint64_t)(savedcount/1000)) ;
+
+
+ t.fractionofseconds = ( (uint64_t)(4294967295) * ( (savedcount * 1000 + (uint64_t)savedcurrent / (F_CPU / 1000000UL)) % 1000000) ) /1000000;
+ return t;
+}
+
+osctime_t oscTime()
+{
+ latchOscTime();
+ return computeOscTime();
+}
+
+#elif defined(CORE_TEENSY)
+extern volatile uint32_t timer0_millis_count;
+static uint32_t savedcount, savedmicros;
+
+static void latchOscTime()
+{
+ noInterrupts();
+ savedcount = timer0_millis_count;
+ savedmicros = micros();
+ interrupts();
+}
+
+static osctime_t computeOscTime()
+{ //4,294,967,296
+ osctime_t t;
+ savedmicros %= 1000000;
+ t.fractionofseconds= (67108864ULL * savedmicros) / 15625 ; // 2^32/1000000
+ t.seconds = savedcount/1000;
+ return t;
+#ifdef ddfgsdfgsdfgsdfg
+ return ((savedcount/1000)<<32) + ( (4294967295ULL) * ( (savedcount * 1000ULL + savedmicros) % 1000000ULL) ) /1000000ULL
+
+ ;
+#endif
+
+
+}
+osctime_t oscTime()
+{
+ latchOscTime();
+ return computeOscTime();
+
+}
+#elif defined(AVR) || defined(__AVR_ATmega32U4__) || defined(__SAM3X8E__) || defined(_SAMD21_) || defined(__ARM__)
+static uint32_t savedcount, savedmicros;
+
+
+static void latchOscTime()
+{
+ noInterrupts();
+ //cli();
+ savedcount = millis();
+ savedmicros = micros();
+ interrupts();
+ //sei();
+}
+
+osctime_t computeOscTime()
+{ //4,294,967,296
+ osctime_t t;
+ savedmicros %= 1000000UL;
+ // t.fractionofseconds = (67108864ULL * (uint64_t)savedmicros) / 15625ULL ; // 2^32/1000000
+ t.fractionofseconds= (67108864UL * savedmicros)/ 15625ULL ; // 2^32/1000000
+ t.seconds = savedcount/1000;
+ return t;
+
+
+
+}
+osctime_t oscTime()
+{
+ latchOscTime();
+ return computeOscTime();
+}
+
+#else
+
+
+
+static void latchOscTime()
+{
+}
+
+osctime_t oscTime()
+{
+ osctime_t t;
+ t.fractionofseconds = 1;
+ return t;
+
+}
+#endif
+
+int adcRead(int pin, osctime_t *t)
+{
+ latchOscTime();
+
+ int v =analogRead(pin);
+ *t = oscTime();
+ return v;
+}
+#if defined(__MK20DX128__) || defined(__MK20DX256__) || defined(__MKL26Z64__) || defined(__MK66FX1M0__)
+int capacitanceRead(int pin, osctime_t *t)
+{
+ latchOscTime();
+ int v = touchRead(pin);
+
+ *t = oscTime();
+ return v;
+}
+#endif
+int inputRead(int pin, osctime_t *t)
+{
+
+ int v =digitalRead(pin);
+ *t = oscTime();
+
+ return v;
+}
diff --git a/lib/OSC/OSCTiming.h b/lib/OSC/OSCTiming.h
new file mode 100644
index 0000000..4fc9f32
--- /dev/null
+++ b/lib/OSC/OSCTiming.h
@@ -0,0 +1,30 @@
+//
+// OSCTiming.h
+//
+//
+// Created by AdrianFreed on 11/10/13.
+//
+//
+
+#ifndef ____OSCTiming__
+#define ____OSCTiming__
+
+
+#include "Arduino.h"
+#include
+#include
+#include
+typedef struct
+{
+ uint32_t seconds;
+ uint32_t fractionofseconds;
+} osctime_t;
+
+osctime_t oscTime();
+int adcRead(int pin, osctime_t *t);
+int capacitanceRead(int pin, osctime_t *t);
+
+int inputRead(int pin, uint64_t *t);
+
+
+#endif /* defined(____OSCTiming__) */
diff --git a/lib/OSC/README.md b/lib/OSC/README.md
new file mode 100644
index 0000000..bd035f0
--- /dev/null
+++ b/lib/OSC/README.md
@@ -0,0 +1,235 @@
+# OSC for Arduino
+
+This is an Arduino and Teensy library implementation of the [OSC](http://opensoundcontrol.org) (Open Sound Control) encoding.It was developed primarily by Yotam Mann and Adrian Freed at CNMAT where OSC was invented. It benefits from contributions from John MacCallum, Matt Wright, Jeff Lubow and Andy Schmeder and many beta testers.
+
+Features:
+
+* Supports the four basic OSC data types (32-bit integers, 32-bit floats, strings, and blobs - arbitrary length byte sequences)
+* Supports the optional 64-bit timetag data type and Booleans
+* Address pattern matching
+* Dynamic memory allocation
+* Sends and receives OSC packets over transport layers that implements the Arduino Stream Class such as Serial and Ethernet UDP
+
+# Installation
+
+We recommend Arduino 1.8.5 and a compatible Teensyduino overlay if you use the Teensy. Install using the library manager.
+
+Additional information about installing libraries on [Arduino's website](https://www.arduino.cc/en/Guide/Libraries).
+
+# Examples
+
+The `Applications` folder contains examples for Max/MSP and PD and Processing that work with the example sketches. This will be expanded to include other applications like TouchOSC and Processing. For the Max/MSP examples you will need to download the CNMAT max externals package that includes the "o." objects available [here](http://cnmat.berkeley.edu/downloads).
+
+# API
+
+OSC for Arduino supports creating, sending and receiving OSCMessages individually and wrapped into OSCBundles.
+
+The full API is available [here](./API.md).
+
+### Sending Data
+
+Create a new `OSCMessage` with an address in the constructor:
+
+```C++
+OSCMessage msg("/address");
+```
+
+add some data to it:
+
+```C++
+msg.add(1);
+msg.add(2.0);
+msg.add("three");
+```
+
+`add` will infer the type of the data and encode it correctly. The API also supports chaining, so multiple calls to `add` can be strung together:
+
+```C++
+msg.add(1).add(2.0f).add("three");
+```
+
+Then send it over any transport layer that extends Arduino's [Print class](http://playground.arduino.cc/Code/Printclass) like the `Serial` out.
+
+```C++
+msg.send(Serial);
+```
+
+### Receiving Data
+
+In a typical Serial stream, there is no way to know where one message ends and another begins. That's why we recommend using `SLIPSerial` (which also comes in the OSC for Arduino Package). Read more about the lightweight [SLIP encoding](https://en.wikipedia.org/wiki/Serial_Line_Internet_Protocol).
+
+To receive an OSCMessage, wait for the end of SLIP Stream, and fill an empty OSCMessage with the available bytes:
+
+```C++
+//make an empty message to fill with the incoming data
+OSCMessage msg;
+//wait for the end of the packet to be received
+while(!SLIPSerial.endofPacket()){
+ int size = SLIPSerial.available();
+ if (size > 0){
+ //fill the msg with all of the available bytes
+ while(size--){
+ msg.fill(SLIPSerial.read());
+ }
+ }
+}
+```
+
+Now you can query and use the data you received:
+
+```C++
+//returns true if the data in the first position is an integer
+if (msg.isInt(0)){
+ //get that integer
+ int data = msg.getInt(0);
+}
+```
+
+### Routing / Dispatching
+
+OSCMessages can be routed to a specific function by matching their address exactly or with an OSC pattern.
+
+`dispatch` will do a full match on the OSCMessage's address or patterned address.
+
+```C++
+OSCMessage msg("/a/1");
+msg.dispatch("/a/1", dispatchAddress);
+```
+
+And the function definition of `dispatchAddress` could be as follows:
+
+```C++
+//called whenever an OSCMessage's address matches "/a/1"
+void dispatchAddress(OSCMessage &msg){
+ //do something with the OSCMessage...
+ if (msg.isFloat(0)){
+ float val = msg.getFloat(0);
+ }
+}
+```
+
+`route` does the same thing as `dispatch` but allows for partial address matching as long as they are aligned to a `/` character.
+
+```C++
+OSCMessage msg("/b/2");
+msg.route("/b", routeAddress);
+```
+
+```C++
+//called whenever an OSCMessage's address matches "/b"
+void routeAddress(OSCMessage &msg, int addressOffset){
+ //do something with the OSCMessage...
+ if (msg.isBoolean(0)){
+ bool val = msg.getBoolean(0);
+ }
+}
+```
+
+### OSCBundles
+
+An OSCBundle is a group of OSCMessage that can be sent and received together.
+
+```C++
+OSCBundle bundle;
+//add a new OSCMessage to the bundle with the address "/a"
+OSCMessage msgA = bundle.add("/a");
+//add some data to that message
+msgA.add("some data");
+//append another OSCMessage, this time chaining 'add' calls
+bundle.add("/b").add("some more data").add("even more data");
+```
+
+Now send the OSCBundle over SLIPSerial
+
+```C++
+//start a new SLIP Packet
+SLIPSerial.beginPacket();
+//send the data
+bundle.send(SLIPSerial);
+//end the packet
+SLIPSerial.endPacket();
+```
+
+### SLIP Serial
+
+The OSC for Arduino library includes extensions of the USB serial and Hardware serial functions of the Arduino core that sends and receives data using the SLIP encoding. This makes Max/MSP and PD integration very simple using CNMAT's o.io.slipserial. The SLIPSerial library implements the same methods as the Serial object with additional `beginPacket` and `endPacket` methods to mark the boundaries of each packet in a serial stream.
+
+When sending data, begin each packet with `SLIPSerial.beginPacket()`, then write any data to the SLIPSerial and signify the end of the packet using `SLIPSerial.endPacket()`.
+
+On the receiving side, in addition to the normal `read` and `available` methods of the Serial object, SLIPSerial includes `SLIPSerial.endofPacket()` which returns true when the EOT (End Of Transmission) character is received, marking the end of the data packet.
+
+# Oscuino
+
+As well as many small examples illustrating the API, there is a larger application called "oscuino" that illustrates how to use OSC to simplify situations Firmata and Maxuino are typically used in.
+
+# Support
+
+### IDEs
+
+Arduino 1.8.5
+
+Best Supported Board:
+ARM boards such M0, Zero, Teensy 3.0 and 3.1 and LC have the performance and memory that afford rich OSC implementations.
+Our primary test platform for new development is the Teensy 3.x series which currently offers the best performance
+of any of the Arduinos and variants. We greatly appreciate Paul Stoffregen's ongoing work
+with "best practice" engineering of high performance micro-controllers.
+
+### Unsupported boards
+
+Arduino Yun and related openwrt/arduino hybrids (e.g. Draguino):
+
+Marco Brianza is exploring these interesting approaches to running this OSC library on the Atmel 32u4 in the Yun:
+ https://github.com/cylinderlight/udp2serial
+ https://github.com/cylinderlight/udp2serialSPI
+
+The Yun still lacks the Linux-side support to reliably move data between the 32u4 and the router's cpu. We recommend that you add a Teensy to the USB port of an OpenWrt router to get good performance and reliability with our library.
+
+# Testing
+
+OSC for Arduino comes with a small suite of tests to validate its functionality and test compatibility when new platforms come out. The tests are broken into a number of individual `.ino` files located in the `test` folder.
+
+The tests require [ArduinoUnit](https://github.com/mmurdoch/arduinounit) to be installed in the `libraries` folder. The results of the test are printed to the Serial console.
+
+Tested on:
+
+* Esplora
+* Leonardo
+* Teensy 3.x
+* Mega 2560
+
+# Performance
+
+Currently best performance is achieved with Arduinos with built-in USB Serial, i.e. Teensy 3.0, Teensy 2.0 and 2.0++ and Leanardo variants (12Mbps max).
+
+This is because the Wiznet 5100 used in the Ethernet Arduino and shields uses really slow SPI (0.3Mbps). This will change as people retool to use the much faster Wiznet 5200 which has been measured with the Due at 6Mbps.
+
+References:
+* http://forum.pjrc.com/threads/17951-WIZ820io-Ethernet-and-2nd-power-supply-with-teensy-3-0
+* http://arduino.cc/forum/index.php?topic=139147.0
+
+The serial examples use a 9600 baud rate which is reliable on most of the FTDI based Arduinos. The slow rate is required for Arduino's without clock chips such as the TinyLili. Once you have established that things work at 9600 baud you will find it very beneficial to increase the rate. e.g. `Serial.begin(345600); // !! 115200, 230400, 345600, 460800 X`
+
+# Future development ideas
+
+* WIFI examples
+* STM32 support
+* Intel Galileo support
+* HiFive Support
+* Photon Support
+* support for special OSC types in CNMAT's "o." especially subbundles
+* examples for recent OSC support in node.js and Node Red
+* nested bundles
+* performance tuning
+* Photon spark core examples
+* Better Time Tags that avoid the overflow limitation of Arduino timer code
+* Time Tag synchronization
+* Bluetooth LE
+* TCP/IP Examples
+* examples for more applications (i.e. TouchOSC, Processing with SLIP)
+* deadline scheduling of OSC 64-bit timetags
+* ADK support
+
+We welcome and appreciate your contributions and feedback.
+
+# New in this release
+ESPxx, M0, PIC32
\ No newline at end of file
diff --git a/lib/OSC/SLIPEncodedSerial.h b/lib/OSC/SLIPEncodedSerial.h
new file mode 100644
index 0000000..a75c549
--- /dev/null
+++ b/lib/OSC/SLIPEncodedSerial.h
@@ -0,0 +1,292 @@
+/*
+Extends the Serial class to encode SLIP over serial
+*/
+#include "Arduino.h"
+
+#ifndef SLIPEncodedSerial_h
+#define SLIPEncodedSerial_h
+
+#include
+#ifdef ARDUINO_API_VERSION
+#include
+#else
+#include
+#endif
+
+
+
+#if (defined(TEENSYDUINO) && (defined(USB_SERIAL) || defined(USB_DUAL_SERIAL) || defined(USB_TRIPLE_SERIAL) || defined(USB_SERIAL_HID) || defined(USB_MIDI_SERIAL) || defined(USB_MIDI_AUDIO_DUAL_SERIAL) || defined(USB_MIDI4_SERIAL) || defined(USB_MIDI16_SERIAL) || defined(USB_MIDI_AUDIO_SERIAL) || defined(USB_MIDI16_AUDIO_SERIAL))) || (!defined(TEENSYDUINO) && defined(__AVR_ATmega32U4__)) || defined(__SAM3X8E__) || (defined(_USB) && defined(_USE_USB_FOR_SERIAL_)) || defined(_SAMD21_) || defined(__PIC32MX__) || defined(__PIC32MZ__) || defined(ARDUINO_USB_CDC_ON_BOOT) || defined(ARDUINO_ARCH_RP2040)
+#define BOARD_HAS_USB_SERIAL
+
+
+//import the serial USB object
+#if defined(TEENSYDUINO) && defined (__arm__)
+#if !defined(USB_HOST_TEENSY36_)
+#include
+#endif
+#elif defined(TEENSYDUINO) && defined (__AVR__)
+#include
+#elif defined(__SAM3X8E__) || defined(_SAMD21_)
+#include
+#elif (defined(__PIC32MX__) || defined(__PIC32MZ__) || defined(ARDUINO_USB_CDC_ON_BOOT))
+#include
+#elif defined(__AVR_ATmega32U4__)
+#include "USBAPI.h"
+#include
+#elif defined(ARDUINO_ARCH_RP2040)
+#include
+#else
+#error Unknown USB port
+#endif
+
+#endif
+
+template
+class _SLIPSerial: public Stream{
+
+private:
+ // state machine for SLIP escape characters
+ enum erstate {CHAR, FIRSTEOT, SECONDEOT, SLIPESC } rstate;
+
+ //the serial port used
+ T * serial;
+
+public:
+ _SLIPSerial(T &s)
+ {
+ serial = &s;
+ rstate = CHAR;
+ }
+
+ static const uint8_t eot = 0300;
+ static const uint8_t slipesc = 0333;
+ static const uint8_t slipescend = 0334;
+ static const uint8_t slipescesc = 0335;
+ /*
+ SERIAL METHODS
+ */
+ bool endofPacket()
+ {
+ if(rstate == SECONDEOT)
+ {
+ rstate = CHAR;
+ return true;
+ }
+ if (rstate==FIRSTEOT)
+ {
+ if(serial->available())
+ {
+ uint8_t c =serial->peek();
+ if(c==eot)
+ {
+ serial->read(); // throw it on the floor
+ }
+ }
+ rstate = CHAR;
+ return true;
+ }
+ return false;
+ }
+ int available(){
+ back:
+ uint8_t cnt = serial->available();
+
+ if(cnt==0)
+ return 0;
+ if(rstate==CHAR)
+ {
+ uint8_t c =serial->peek();
+ if(c==slipesc)
+ {
+ rstate = SLIPESC;
+ serial->read(); // throw it on the floor
+ goto back;
+ }
+ else if( c==eot)
+ {
+ rstate = FIRSTEOT;
+ serial->read(); // throw it on the floor
+ goto back;
+ }
+ return 1; // we may have more but this is the only sure bet
+ }
+ else if(rstate==SLIPESC)
+ return 1;
+ else if(rstate==FIRSTEOT)
+ {
+ if(serial->peek()==eot)
+ {
+ rstate = SECONDEOT;
+ serial->read(); // throw it on the floor
+ return 0;
+ }
+ rstate = CHAR;
+ }else if (rstate==SECONDEOT) {
+ rstate = CHAR;
+ }
+
+ return 0;
+
+ }
+
+ //reads a byte from the buffer
+ int read(){
+ back:
+ uint8_t c = serial->read();
+ if(rstate==CHAR)
+ {
+ if(c==slipesc)
+ {
+ rstate=SLIPESC;
+ goto back;
+ }
+ else if(c==eot){
+
+ return -1; // xxx this is an error
+ }
+ return c;
+ }
+ else
+ if(rstate==SLIPESC)
+ {
+ rstate=CHAR;
+ if(c==slipescend)
+ return eot;
+ else if(c==slipescesc)
+ return slipesc;
+ else {
+ // insert some error code here
+ return -1;
+ }
+
+ }
+ else
+ return -1;
+ }
+ size_t readBytes( uint8_t *buffer, size_t size)
+ {
+ size_t count = 0;
+ while(!endofPacket() && available() && (size>0))
+ {
+ int c = read();
+ if(c>=0)
+ {
+ *buffer++ = c;
+ ++count;
+ --size;
+
+ }
+ else
+ break;
+ }
+ return count;
+ }
+ // as close as we can get to correct behavior
+ int peek(){
+ uint8_t c = serial->peek();
+ if(rstate==SLIPESC)
+ {
+ if(c==slipescend)
+ return eot;
+ else if(c==slipescesc)
+ return slipesc;
+ }
+ return c;
+ }
+
+ //encode SLIP
+ size_t write(uint8_t b){
+ if(b == eot){
+ serial->write(slipesc);
+ return serial->write(slipescend);
+ } else if(b==slipesc) {
+ serial->write(slipesc);
+ return serial->write(slipescesc);
+ } else {
+ return serial->write(b);
+ }
+ }
+ size_t write(const uint8_t *buffer, size_t size)
+ {
+ size_t result=0;
+ while(size--)
+ {
+ result = write(*buffer++);
+ }
+ return result;
+ }
+
+
+ void begin(unsigned long baudrate){
+ serial->begin(baudrate);
+ }
+ // for bluetooth
+ void begin(char *name){
+ serial->begin(name);
+ }
+ //SLIP specific method which begins a transmitted packet
+ void beginPacket() { serial->write(eot); }
+
+ //signify the end of the packet with an EOT
+ void endPacket(){
+ serial->write(eot);
+ }
+
+ void flush(){
+ serial->flush();
+ }
+
+};
+
+using SLIPEncodedSerial = _SLIPSerial ;
+// template <> void _SLIPSerial::endPacket(){
+// serial->write(eot);
+
+// }
+
+#ifdef BOARD_HAS_USB_SERIAL
+
+#if defined(_SAMD21_)
+// Required for Serial on Zero based boards
+#if defined(ARDUINO_SAMD_ZERO)
+// Adafruit breaks with tradition here
+#define thisBoardsSerialUSB Serial
+typedef decltype(Serial) actualUSBtype;
+#else
+#define thisBoardsSerialUSB SerialUSB
+typedef decltype(SerialUSB) actualUSBtype;
+#endif
+#elif defined(__SAM3X8E__)
+// Required for Serial on Zero based boards
+#define thisBoardsSerialUSB SerialUSB
+typedef decltype(SerialUSB) actualUSBtype;
+
+// defined(__SAM3X8E__)
+#elif defined(ARDUINO_ARCH_RP2040) || defined(ARDUINO_USB_CDC_ON_BOOT) || defined(CORE_TEENSY) || defined(__AVR_ATmega32U4__) || (defined(__PIC32MX__) || defined(__PIC32MZ__))
+#define thisBoardsSerialUSB Serial
+typedef decltype(Serial) actualUSBtype;
+#endif
+using SLIPEncodedUSBSerial = _SLIPSerial;
+#if defined(CORE_TEENSY)
+template <> void _SLIPSerial::endPacket(){
+ serial->write(eot);
+ serial->send_now();
+}
+#endif
+
+#endif
+
+// Bluetooth Example
+
+// #if BOARD_HAS_BLUETOOTH_SERIAL
+// #include "BluetoothSerial.h"
+// BluetoothSerial bluetoothserialinstance;
+// SLIPEncodedBluetoothSerial SLIPSerial(bluetoothserialinstance);
+
+#if defined(CONFIG_BT_ENABLED) && defined(CONFIG_BLUEDROID_ENABLED) && !defined(CONFIG_IDF_TARGET_ESP32C3) && !defined(CONFIG_IDF_TARGET_ESP32C3) && !defined(CONFIG_IDF_TARGET_ESP32S3) && !defined(CONFIG_IDF_TARGET_ESP32S2)
+#include "BluetoothSerial.h"
+using SLIPEncodedBluetoothSerial = _SLIPSerial;
+#define BOARD_HAS_BLUETOOTH_SERIAL
+
+#endif
+#endif
\ No newline at end of file
diff --git a/lib/OSC/examples/ESP8266ReceiveBundle/ESP8266ReceiveBundle.ino b/lib/OSC/examples/ESP8266ReceiveBundle/ESP8266ReceiveBundle.ino
new file mode 100644
index 0000000..7558258
--- /dev/null
+++ b/lib/OSC/examples/ESP8266ReceiveBundle/ESP8266ReceiveBundle.ino
@@ -0,0 +1,103 @@
+/*---------------------------------------------------------------------------------------------
+
+ Open Sound Control (OSC) library for the ESP8266/ESP32
+
+ Example for receiving open sound control (OSC) bundles on the ESP8266/ESP32
+ Send integers '0' or '1' to the address "/led" to turn on/off the built-in LED of the esp8266.
+
+ This example code is in the public domain.
+
+--------------------------------------------------------------------------------------------- */
+#ifdef ESP8266
+#include
+#else
+#include
+#endif
+#include
+#include
+#include
+#include
+
+char ssid[] = "*****************"; // your network SSID (name)
+char pass[] = "*******"; // your network password
+
+// A UDP instance to let us send and receive packets over UDP
+WiFiUDP Udp;
+const IPAddress outIp(10,40,10,105); // remote IP (not needed for receive)
+const unsigned int outPort = 9999; // remote port (not needed for receive)
+const unsigned int localPort = 8888; // local port to listen for UDP packets (here's where we send the packets)
+
+
+OSCErrorCode error;
+unsigned int ledState = LOW; // LOW means led is *on*
+
+#ifndef BUILTIN_LED
+#ifdef LED_BUILTIN
+#define BUILTIN_LED LED_BUILTIN
+#else
+#define BUILTIN_LED 13
+#endif
+#endif
+
+void setup() {
+ pinMode(BUILTIN_LED, OUTPUT);
+ digitalWrite(BUILTIN_LED, ledState); // turn *on* led
+
+ Serial.begin(115200);
+
+ // Connect to WiFi network
+ Serial.println();
+ Serial.println();
+ Serial.print("Connecting to ");
+ Serial.println(ssid);
+ WiFi.begin(ssid, pass);
+
+ while (WiFi.status() != WL_CONNECTED) {
+ delay(500);
+ Serial.print(".");
+ }
+ Serial.println("");
+
+ Serial.println("WiFi connected");
+ Serial.println("IP address: ");
+ Serial.println(WiFi.localIP());
+
+ Serial.println("Starting UDP");
+ Udp.begin(localPort);
+ Serial.print("Local port: ");
+#ifdef ESP32
+ Serial.println(localPort);
+#else
+ Serial.println(Udp.localPort());
+#endif
+
+}
+
+
+void led(OSCMessage &msg) {
+ ledState = msg.getInt(0);
+ digitalWrite(BUILTIN_LED, ledState);
+ Serial.print("/led: ");
+ Serial.println(ledState);
+}
+
+void loop() {
+ OSCBundle bundle;
+ int size = Udp.parsePacket();
+
+ if (size > 0) {
+ while (size--) {
+ bundle.fill(Udp.read());
+ }
+ if (!bundle.hasError()) {
+ bundle.dispatch("/led", led);
+ } else {
+ error = bundle.getError();
+ Serial.print("error: ");
+ Serial.println(error);
+ }
+ }
+}
+
+
+
diff --git a/lib/OSC/examples/ESP8266ReceiveMessage/ESP8266ReceiveMessage.ino b/lib/OSC/examples/ESP8266ReceiveMessage/ESP8266ReceiveMessage.ino
new file mode 100644
index 0000000..69faa10
--- /dev/null
+++ b/lib/OSC/examples/ESP8266ReceiveMessage/ESP8266ReceiveMessage.ino
@@ -0,0 +1,100 @@
+/*---------------------------------------------------------------------------------------------
+
+ Open Sound Control (OSC) library for the ESP8266/ESP32
+
+ Example for receiving open sound control (OSC) messages on the ESP8266/ESP32
+ Send integers '0' or '1' to the address "/led" to turn on/off the built-in LED of the esp8266.
+
+ This example code is in the public domain.
+
+--------------------------------------------------------------------------------------------- */
+#ifdef ESP8266
+#include
+#else
+#include
+#endif
+#include
+#include
+#include
+#include
+
+char ssid[] = "*****************"; // your network SSID (name)
+char pass[] = "*******"; // your network password
+
+// A UDP instance to let us send and receive packets over UDP
+WiFiUDP Udp;
+const IPAddress outIp(10,40,10,105); // remote IP (not needed for receive)
+const unsigned int outPort = 9999; // remote port (not needed for receive)
+const unsigned int localPort = 8888; // local port to listen for UDP packets (here's where we send the packets)
+
+
+OSCErrorCode error;
+unsigned int ledState = LOW; // LOW means led is *on*
+
+#ifndef BUILTIN_LED
+#ifdef LED_BUILTIN
+#define BUILTIN_LED LED_BUILTIN
+#else
+#define BUILTIN_LED 13
+#endif
+#endif
+
+void setup() {
+ pinMode(BUILTIN_LED, OUTPUT);
+ digitalWrite(BUILTIN_LED, ledState); // turn *on* led
+
+ Serial.begin(115200);
+
+ // Connect to WiFi network
+ Serial.println();
+ Serial.println();
+ Serial.print("Connecting to ");
+ Serial.println(ssid);
+ WiFi.begin(ssid, pass);
+
+ while (WiFi.status() != WL_CONNECTED) {
+ delay(500);
+ Serial.print(".");
+ }
+ Serial.println("");
+
+ Serial.println("WiFi connected");
+ Serial.println("IP address: ");
+ Serial.println(WiFi.localIP());
+
+ Serial.println("Starting UDP");
+ Udp.begin(localPort);
+ Serial.print("Local port: ");
+#ifdef ESP32
+ Serial.println(localPort);
+#else
+ Serial.println(Udp.localPort());
+#endif
+
+}
+
+
+void led(OSCMessage &msg) {
+ ledState = msg.getInt(0);
+ digitalWrite(BUILTIN_LED, ledState);
+ Serial.print("/led: ");
+ Serial.println(ledState);
+}
+
+void loop() {
+ OSCMessage msg;
+ int size = Udp.parsePacket();
+
+ if (size > 0) {
+ while (size--) {
+ msg.fill(Udp.read());
+ }
+ if (!msg.hasError()) {
+ msg.dispatch("/led", led);
+ } else {
+ error = msg.getError();
+ Serial.print("error: ");
+ Serial.println(error);
+ }
+ }
+}
diff --git a/lib/OSC/examples/ESP8266sendMessage/ESP8266sendMessage.ino b/lib/OSC/examples/ESP8266sendMessage/ESP8266sendMessage.ino
new file mode 100644
index 0000000..3aa61ff
--- /dev/null
+++ b/lib/OSC/examples/ESP8266sendMessage/ESP8266sendMessage.ino
@@ -0,0 +1,66 @@
+/*---------------------------------------------------------------------------------------------
+
+ Open Sound Control (OSC) library for the ESP8266/ESP32
+
+ Example for sending messages from the ESP8266/ESP32 to a remote computer
+ The example is sending "hello, osc." to the address "/test".
+
+ This example code is in the public domain.
+
+--------------------------------------------------------------------------------------------- */
+#if defined(ESP8266)
+#include
+#else
+#include
+#endif
+#include
+#include
+
+char ssid[] = "*****************"; // your network SSID (name)
+char pass[] = "*******"; // your network password
+
+WiFiUDP Udp; // A UDP instance to let us send and receive packets over UDP
+const IPAddress outIp(10,40,10,105); // remote IP of your computer
+const unsigned int outPort = 9999; // remote port to receive OSC
+const unsigned int localPort = 8888; // local port to listen for OSC packets (actually not used for sending)
+
+void setup() {
+ Serial.begin(115200);
+
+ // Connect to WiFi network
+ Serial.println();
+ Serial.println();
+ Serial.print("Connecting to ");
+ Serial.println(ssid);
+ WiFi.begin(ssid, pass);
+
+ while (WiFi.status() != WL_CONNECTED) {
+ delay(500);
+ Serial.print(".");
+ }
+ Serial.println("");
+
+ Serial.println("WiFi connected");
+ Serial.println("IP address: ");
+ Serial.println(WiFi.localIP());
+
+ Serial.println("Starting UDP");
+ Udp.begin(localPort);
+ Serial.print("Local port: ");
+#ifdef ESP32
+ Serial.println(localPort);
+#else
+ Serial.println(Udp.localPort());
+#endif
+
+}
+
+void loop() {
+ OSCMessage msg("/test");
+ msg.add("hello, osc.");
+ Udp.beginPacket(outIp, outPort);
+ msg.send(Udp);
+ Udp.endPacket();
+ msg.empty();
+ delay(500);
+}
diff --git a/lib/OSC/examples/OSCEsplora/OSCEsplora.ino b/lib/OSC/examples/OSCEsplora/OSCEsplora.ino
new file mode 100644
index 0000000..3325d97
--- /dev/null
+++ b/lib/OSC/examples/OSCEsplora/OSCEsplora.ino
@@ -0,0 +1,287 @@
+
+/*
+ Bidirectional Esplora OSC communications using SLIP
+
+ Adrian Freed, Jeff Lubow 2013
+
+ Includes some examples of common "best practices" for OSC name space and parameter
+ mapping design.
+
+
+*/
+
+#include
+#include
+//Teensy and Leonardo variants have special USB serial
+#include
+
+#if !defined(__AVR_ATmega32U4__)
+#error select Arduino Esplora in board menu
+#endif
+
+// temperature
+float getTemperature(){
+ int result;
+
+ ADMUX = _BV(REFS1) | _BV(REFS0) | _BV(MUX2) | _BV(MUX1) | _BV(MUX0);
+ ADCSRB = _BV(MUX5);
+ delayMicroseconds(200); // wait for Vref to settle
+ ADCSRA |= _BV(ADSC); // Convert
+ while (bit_is_set(ADCSRA,ADSC));
+ result = ADCL;
+ result |= ADCH<<8;
+
+ analogReference(DEFAULT);
+ return result/1023.0f;
+}
+
+float getSupplyVoltage(){
+ // powersupply
+ int result;
+ // Read 1.1V reference against AVcc
+ ADMUX = _BV(REFS0) | _BV(MUX4) | _BV(MUX3) | _BV(MUX2) | _BV(MUX1);
+ delayMicroseconds(300); // wait for Vref to settle
+ ADCSRA |= _BV(ADSC); // Convert
+ while (bit_is_set(ADCSRA,ADSC));
+ result = ADCL;
+ result |= ADCH<<8;
+
+ float supplyvoltage = 1.1264f *1023 / result;
+ return supplyvoltage;
+}
+
+// Esplora has a dinky green led at the top left and a big RGB led at the bottom right
+void routeLed(OSCMessage &msg, int addrOffset ){
+ if(msg.match("/red", addrOffset)) {
+ if (msg.isInt(0)) Esplora.writeRed( (byte)msg.getInt(0));
+ }
+ else
+ if(msg.match("/green", addrOffset)) {
+ if (msg.isInt(0)) Esplora.writeGreen( (byte)msg.getInt(0));
+ }
+ else
+ if(msg.match("/blue", addrOffset)) {
+ if (msg.isInt(0)) Esplora.writeBlue( (byte)msg.getInt(0));
+ }
+ else
+ if(msg.match("/rgb", addrOffset)) {
+
+ if (msg.isInt(0)&&msg.isInt(1)&&msg.isInt(2))
+ {
+ Esplora.writeRGB((byte)msg.getInt(0),(byte)msg.getInt(1),(byte)msg.getInt(2));
+ }
+ }
+ else
+ {
+ if (msg.isInt(0))
+ {
+ digitalWrite(13, msg.getInt(0)>0?HIGH:LOW);
+ }
+ }
+}
+
+// Esplora has a dinky green led at the top left and a big RGB led at the bottom right
+void routeOut(OSCMessage &msg, int addrOffset ){
+ if(msg.match("/B", addrOffset) || msg.match("/b", addrOffset)) {
+ if (msg.isInt(0)) {
+ pinMode(11,OUTPUT);
+ digitalWrite(11, msg.getInt(0)>0?HIGH:LOW);
+ }
+ else
+ pinMode(11,INPUT); // add pull up logic some day
+ }
+ else
+ if(msg.match("/A", addrOffset) ||msg.match("/a", addrOffset)) {
+ if (msg.isInt(0)) {
+ pinMode(3,OUTPUT);
+ digitalWrite(3, msg.getInt(0)>0?HIGH:LOW);
+ }
+ else
+ pinMode(3,INPUT); // add pull up logic some day
+ }
+}
+
+/**
+ * TONE
+ *
+ * square wave output "/tone"
+ *
+ * format:
+ * /tone
+ * (no value) = notome
+ * float or int = frequency
+ * optional length of time as an integer in milliseconds afterwards
+ *
+ **/
+
+void routeTone(OSCMessage &msg, int addrOffset ){
+
+ unsigned int frequency = 0;
+ if (msg.isInt(0)){
+ frequency = msg.getInt(0);
+ }
+ else if(msg.isFloat(0)){
+ frequency = msg.getFloat(0); // this doesn't work due to problems with double to float conversion?
+ }
+ else
+ Esplora.noTone();
+ if(frequency>0)
+ {
+ if(msg.isInt(1))
+ Esplora.tone(frequency, msg.getInt(1));
+ else
+ Esplora.tone( frequency);
+ }
+}
+const char *released = "released";
+const char *pressed = "pressed";
+
+const byte MUX_ADDR_PINS[] = {
+ A0, A1, A2, A3 };
+const byte MUX_COM_PIN = A4;
+
+unsigned int myReadChannel(byte channel) {
+ digitalWrite(MUX_ADDR_PINS[0], (channel & 1) ? HIGH : LOW);
+ digitalWrite(MUX_ADDR_PINS[1], (channel & 2) ? HIGH : LOW);
+ digitalWrite(MUX_ADDR_PINS[2], (channel & 4) ? HIGH : LOW);
+ digitalWrite(MUX_ADDR_PINS[3], (channel & 8) ? HIGH : LOW);
+
+ return analogRead(MUX_COM_PIN);
+}
+
+
+SLIPEncodedUSBSerial SLIPSerial(Serial);
+void setup() {
+ SLIPSerial.begin(115200); // set this as high as you can reliably run on your platform
+}
+
+int32_t counter = 0;
+int32_t serialnumber = 2; //hard coded; beware
+int32_t num_components = 3; //currently break the bundle up into 3 components
+
+void loop(){
+ OSCBundle bndl;
+ int32_t manifest_count = 1;
+
+ if(!SLIPSerial.available())
+ {
+
+ // The RAW OSC address space and parameter mappngs try to capture
+ // the data at lowest level without calibration or scaling
+ // The names are chosen to match what is on the silkscreen of the board where it is found
+ #define RAW
+ #ifdef RAW
+ SLIPSerial.beginPacket();
+ bndl.add("/mic").add((int32_t)Esplora.readMicrophone());
+ bndl.add("/temp/sensor/celsius").add((int32_t)Esplora.readTemperature(DEGREES_C));
+ bndl.add("/temp/sensor/fahrenheit").add((int32_t)Esplora.readTemperature(DEGREES_F));
+ bndl.add("/linear/potentiometer").add((int32_t)Esplora.readSlider());
+ bndl.add("/light/sensor").add((int32_t)Esplora.readLightSensor());
+ bndl.add("/switch/1").add((int32_t)Esplora.readButton(SWITCH_1));
+ bndl.add("/switch/2").add((int32_t)Esplora.readButton(SWITCH_2));
+ bndl.add("/switch/3").add((int32_t)Esplora.readButton(SWITCH_3));
+ bndl.add("/switch/4").add((int32_t)Esplora.readButton(SWITCH_4));
+ bndl.add("/joystick/X").add((int32_t)Esplora.readJoystickX());
+ bndl.add("/joystick/Y").add((int32_t)Esplora.readJoystickY());
+ bndl.add("/joystick/switch").add((int32_t)Esplora.readJoystickSwitch());
+ bndl.add("/joystick/switch/1").add((int32_t)Esplora.readButton(JOYSTICK_DOWN));
+ bndl.add("/joystick/switch/2").add((int32_t)Esplora.readButton(JOYSTICK_LEFT));
+ bndl.add("/joystick/switch/3").add((int32_t)Esplora.readButton(JOYSTICK_UP));
+ bndl.add("/joystick/switch/4").add((int32_t)Esplora.readButton(JOYSTICK_RIGHT));
+ bndl.add("/accelerometer/x").add(Esplora.readAccelerometer(X_AXIS));
+ bndl.add("/accelerometer/y").add(Esplora.readAccelerometer(Y_AXIS));
+ bndl.add("/accelerometer/z").add(Esplora.readAccelerometer(Z_AXIS));
+ bndl.send(SLIPSerial); // send the bytes to the SLIP stream
+ SLIPSerial.endPacket(); // mark the end of the OSC Packet
+ bndl.empty();
+ #endif //RAW
+
+
+ // The COOKED OSC address space and parameter mappings
+ // encode data for ease of use and legibility at the host. Unit intervals replace integers
+ // The names are chosen to clarify usage rather than adherence to the silkscreen
+ // also values are acquired as close together as reasonably possible to increase
+ // their usability in sensor fusion contexts, i.e. in this case with the accelerometer
+
+
+ SLIPSerial.beginPacket(); // mark the beginning of the OSC Packet
+
+ //bundle 1
+ bndl.add("/acceleration/x").add(Esplora.readAccelerometer(X_AXIS)/512.0f);
+ bndl.add("/acceleration/y").add(Esplora.readAccelerometer(Y_AXIS)/512.0f);
+ bndl.add("/acceleration/z").add(Esplora.readAccelerometer(Z_AXIS)/512.0f);
+ bndl.add("/photoresistor").add(Esplora.readLightSensor()/1023.0f);
+ bndl.add("/joystick/horizontal").add(-1.0 * (int32_t)Esplora.readJoystickX()/512.0f);
+ bndl.add("/joystick/vertical").add(-1.0 * (int32_t)Esplora.readJoystickY()/512.0f);
+ bndl.add("/joystick/button").add(Esplora.readJoystickSwitch()>0? released:pressed);
+ bndl.add("/joystick/backward").add((int32_t)Esplora.readButton(JOYSTICK_DOWN)?released:pressed);
+ bndl.add("/joystick/left").add((int32_t)Esplora.readButton(JOYSTICK_LEFT)?released:pressed);
+ bndl.add("/joystick/forward").add((int32_t)Esplora.readButton(JOYSTICK_UP)?released:pressed);
+ bndl.add("/joystick/right").add((int32_t)Esplora.readButton(JOYSTICK_RIGHT)?released:pressed);
+ bndl.add("/serialnumber").add(serialnumber);
+ //bndl.add("/manifest").add(manifest_count++).add(num_components).add(counter);
+ bndl.send(SLIPSerial); // send the bytes to the SLIP stream
+ SLIPSerial.endPacket(); // mark the end of the OSC Packet
+ bndl.empty(); //bundle ending early due to current memory limitations
+
+ //bundle 2
+ bndl.add("/diamond/backward").add((int32_t)Esplora.readButton(SWITCH_1)?released:pressed);
+ bndl.add("/diamond/left").add((int32_t)Esplora.readButton(SWITCH_2)?released:pressed);
+ bndl.add("/diamond/forward").add((int32_t)Esplora.readButton(SWITCH_3)?released:pressed);
+ bndl.add("/diamond/right").add((int32_t)Esplora.readButton(SWITCH_4)?released:pressed);
+ bndl.add("/microphone/loudness").add(Esplora.readMicrophone()/1023.0f);
+ bndl.add("/temperature/fahrenheit").add((float)Esplora.readTemperature(DEGREES_F));
+ bndl.add("/temperature/celsius").add((float)Esplora.readTemperature(DEGREES_C));
+ bndl.add("/slider/horizontal").add(1.0f - ((float)Esplora.readSlider()/1023.0f));
+ bndl.add("/serialnumber").add(serialnumber);
+ //bndl.add("/manifest").add(manifest_count++).add(num_components).add(counter);
+ bndl.send(SLIPSerial); // send the bytes to the SLIP stream
+ SLIPSerial.endPacket(); // mark the end of the OSC Packet
+ bndl.empty(); //bundle ending early due to current memory limitations
+
+ //bundle 3
+ bndl.add("/connector/white/left").add(myReadChannel(CH_MIC +1)/1023.0);
+ bndl.add("/connector/white/right").add(myReadChannel(CH_MIC +2)/1023.0);
+ bndl.add("/led/red").add((int32_t)Esplora.readRed());
+ bndl.add("/led/green").add((int32_t)Esplora.readGreen());
+ bndl.add("/led/blue").add((int32_t)Esplora.readBlue());
+ bndl.add("/led/rgb").add((int32_t)Esplora.readRed()).add((int32_t)Esplora.readGreen()).add((int32_t)Esplora.readBlue());
+ bndl.add("/connector/orange/right").add((digitalRead(3)==HIGH)?1:0);
+ bndl.add("/connector/orange/left").add((digitalRead(11)==HIGH)?1:0);
+ bndl.add("/vendor").add("Arduino");
+ bndl.add("/productname").add("Esplora");
+ bndl.add("/serialnumber").add(serialnumber);
+ //bndl.add("/manifest").add(manifest_count++).add(num_components).add(counter);
+ bndl.send(SLIPSerial); // send the bytes to the SLIP stream
+ SLIPSerial.endPacket(); // mark the end of the OSC Packet
+ bndl.empty();
+
+ counter += 1;
+ // bndl.add("/32u4/supplyVoltage").add(getSupplyVoltage());
+ // bndl.add("/32u4/temperature").add(getTemperature());
+
+ }
+ else
+ {
+ OSCBundle bundleIN;
+ int size;
+
+ while(!SLIPSerial.endofPacket())
+ if ((size =SLIPSerial.available()) > 0)
+ {
+ while(size--)
+ bundleIN.fill(SLIPSerial.read());
+ }
+ {
+ if(!bundleIN.hasError())
+ {
+ bundleIN.route("/led", routeLed);
+ bundleIN.route("/L", routeLed); // this is how it is marked on the silkscreen
+ bundleIN.route("/out", routeOut); // for the TinkerIt output connectors
+ bundleIN.route("/tone", routeTone);
+ bundleIN.route("/squarewave", routeTone);
+ bundleIN.route("/notone", routeTone);
+ }
+ }
+ }
+}
diff --git a/lib/OSC/examples/PatternMatching/PatternMatching.ino b/lib/OSC/examples/PatternMatching/PatternMatching.ino
new file mode 100644
index 0000000..e68ec8c
--- /dev/null
+++ b/lib/OSC/examples/PatternMatching/PatternMatching.ino
@@ -0,0 +1,91 @@
+/*
+ The library has four methods for doing pattern matching on address.
+ 'match' and 'fullMatch' are specific to OSCMessages while route and dispatch work on both messages and bundles.
+
+ OSCMessage:
+ match - matches the message's address pattern against an address. returns the number of characters matched from the address passed in.
+ fullMatch - returns true if the pattern was a complete match against the address
+
+ OSCMessage && OSCBundle:
+ route - calls a function with the matched OSCMessage(s) and the number of matched characters in the address as the parameters
+ dispatch - calls a function with each OSCMessage which was fully matched by the pattern
+
+///////////////////////////////////////////////////////////////////////////////////////////////////
+OSC Regular expression pattern matching rules from http://opensoundcontrol.org/spec-1_0
+
+ 1. '?' in the OSC Address Pattern matches any single character
+ 2. '*' in the OSC Address Pattern matches any sequence of zero or more characters
+ 3. A string of characters in square brackets (e.g., "[string]") in the OSC Address Pattern matches any character in the string.
+ Inside square brackets, the minus sign (-) and exclamation point (!) have special meanings:
+ two characters separated by a minus sign indicates the range of characters between the given two in ASCII collating sequence.
+ An exclamation point at the beginning of a bracketed string negates the sense of the list, meaning that the list matches any character not in the list.
+ 4. A comma-separated list of strings enclosed in curly braces (e.g., "{foo,bar}") in the OSC Address Pattern matches any of the strings in the list.
+ 5. Any other character in an OSC Address Pattern can match only the same character.
+ ///////////////////////////////////////////////////////////////////////////////////////////////////
+ */
+
+#include
+
+void setup() {
+ Serial.begin(38400);
+}
+
+void loop(){
+ //a heavily patterned message address
+ OSCMessage msg0("/{input,output}/[0-2]/[!ab]/*");
+ //match will traverse as far as it can in the pattern
+ //it returns the number of characters matched from the pattern
+ int patternOffset = msg0.match("/input/1");
+ if (patternOffset>0){
+ //string multiple 'match' methods together using the pattern offset parameter to continue matching where it left off
+ //use 'fullMatch' to test if the entire pattern was matched.
+ if(msg0.fullMatch("/c/anything", patternOffset)){
+ Serial.println("Match: '/input/1/c/anything' against the pattern '/{input,output}/[0-2]/[abc]/*'");
+ }
+ }
+ //write over the other message address
+ OSCMessage msg1("/partialMatch");
+ //match will return 0 if it did not reach the end or a '/'
+ if(!msg1.match("/partial")){
+ Serial.println("No Match: '/partial' against the pattern '/partialMatch'");
+ }
+ OSCMessage msg2("/output/[0-2]");
+ //'route' is uses 'match' to allow for partial matches
+ //it invokes the callback with the matched message and the pattern offset as parameters to the callback
+ msg2.route("/output", routeOutput);
+ //'dispatch' uses 'fullMatch' so it does not allow for partial matches
+ //invokes the callback with only one argument which is the matched message
+ msg2.dispatch("/output/1", routeOutputOne);
+ delay(1000);
+}
+
+//called after matching '/output'
+//the matched message and the number of matched characters as the parameters
+void routeOutput(OSCMessage &msg, int patternOffset){
+ Serial.println("Match: '/output'");
+ //string multiple 'route' methods together using the pattern offset parameter.
+ msg.route("/0", routeZero, patternOffset);
+}
+
+//called after matching '/0'
+void routeZero(OSCMessage &msg, int addressOffset){
+ Serial.println("Match: '/output/0'");
+}
+
+//called after matching '/output/1'
+void routeOutputOne(OSCMessage &msg){
+ Serial.println("Match: '/output/1'");
+}
+
+
+//
+// TROUBLESHOOTING:
+// Because of a bug in the Arduino IDE, it sometimes thinks that the '*' in combination with '/' is the opening or closing of a multiline comment
+// This can be fixed by escaping the '/' with '\' or using the octal value of '*' which is '\052'
+// for example:
+// "/*" == "/\052" == "\/*"
+//
+
+
+
+
diff --git a/lib/OSC/examples/SerialCallResponse/SerialCallResponse.ino b/lib/OSC/examples/SerialCallResponse/SerialCallResponse.ino
new file mode 100644
index 0000000..2569835
--- /dev/null
+++ b/lib/OSC/examples/SerialCallResponse/SerialCallResponse.ino
@@ -0,0 +1,108 @@
+/*
+ Serial Call Response
+ Send responses to calls for information from a remote host
+*/
+
+#include
+#include
+
+#include
+
+#ifdef BOARD_HAS_USB_SERIAL
+SLIPEncodedUSBSerial SLIPSerial( thisBoardsSerialUSB );
+#else
+ SLIPEncodedSerial SLIPSerial(Serial); // Change to Serial1 or Serial2 etc. for boards with multiple serial ports that don’t have Serial
+#endif
+
+OSCBundle bundleOUT;
+
+/**
+ * ANALOG
+ *
+ * called when the address matches "/a"
+ *
+ * format:
+ * /analog/(pin)
+ * /u = analogRead with pullup
+ *
+ **/
+
+void routeAnalog(OSCMessage &msg, int addrOffset ){
+ int pinMatched;
+ pinMatched = msg.match("/0", addrOffset);
+ if(pinMatched){
+ if (msg.fullMatch("/u", pinMatched+addrOffset)) pinMode(analogInputToDigitalPin(0), INPUT_PULLUP); //set the pullup
+ //do the analog read and send the results
+ bundleOUT.add("/analog/0").add((int32_t)analogRead(0));
+ }
+ pinMatched = msg.match("/1", addrOffset);
+ if(pinMatched){
+ if (msg.fullMatch("/u", pinMatched+addrOffset)) pinMode(analogInputToDigitalPin(1), INPUT_PULLUP); //set the pullup
+ //do the analog read and send the results
+ bundleOUT.add("/analog/1").add((int32_t)analogRead(1));
+ }
+ pinMatched = msg.match("/2", addrOffset);
+ if(pinMatched){
+ if (msg.fullMatch("/u", pinMatched+addrOffset)) pinMode(analogInputToDigitalPin(2), INPUT_PULLUP); //set the pullup
+ //do the analog read and send the results
+ bundleOUT.add("/analog/2").add((int32_t)analogRead(2));
+ }
+ pinMatched = msg.match("/3", addrOffset);
+ if(pinMatched){
+ if (msg.fullMatch("/u", pinMatched+addrOffset)) pinMode(analogInputToDigitalPin(3), INPUT_PULLUP); //set the pullup
+ //do the analog read and send the results
+ bundleOUT.add("/analog/3").add((int32_t)analogRead(3));
+ }
+ pinMatched = msg.match("/4", addrOffset);
+ if(pinMatched){
+ if (msg.fullMatch("/u", pinMatched+addrOffset)) pinMode(analogInputToDigitalPin(4), INPUT_PULLUP); //set the pullup
+ //do the analog read and send the results
+ bundleOUT.add("/analog/4").add((int32_t)analogRead(4));
+ }
+ pinMatched = msg.match("/5", addrOffset);
+ if(pinMatched){
+ if (msg.fullMatch("/u", pinMatched+addrOffset)) pinMode(analogInputToDigitalPin(5), INPUT_PULLUP); //set the pullup
+ //do the analog read and send the results
+ bundleOUT.add("/analog/5").add((int32_t)analogRead(5));
+ }
+}
+
+/**
+ * MAIN METHODS
+ *
+ * setup and loop, bundle receiving/sending, initial routing
+ */
+void setup() {
+ SLIPSerial.begin(9600); // set this as high as you can reliably run on your platform
+}
+
+//reads and routes the incoming messages
+void loop(){
+ OSCBundle bundleIN;
+
+ int size;
+
+ while(!SLIPSerial.endofPacket())
+ if ((size =SLIPSerial.available()) > 0)
+ {
+ while(size--)
+ bundleIN.fill(SLIPSerial.read());
+ }
+ if(!bundleIN.hasError())
+ {
+ bundleIN.route("/analog", routeAnalog);
+ //send the outgoing response message
+ SLIPSerial.beginPacket();
+ bundleOUT.send(SLIPSerial);
+ SLIPSerial.endPacket();
+ bundleOUT.empty(); // empty the bundle ready to use for new messages
+ }
+}
+
+
+
+
+
+
+
+
diff --git a/lib/OSC/examples/SerialEcho/SerialEcho.ino b/lib/OSC/examples/SerialEcho/SerialEcho.ino
new file mode 100644
index 0000000..079a28a
--- /dev/null
+++ b/lib/OSC/examples/SerialEcho/SerialEcho.ino
@@ -0,0 +1,48 @@
+/*
+
+Serial USB ports are bidirectional.
+
+This example can be extended to build routers and forwarders of OSC packets
+*/
+
+#include
+
+#include
+
+#ifdef BOARD_HAS_USB_SERIAL
+SLIPEncodedUSBSerial SLIPSerial( thisBoardsSerialUSB );
+#else
+ SLIPEncodedSerial SLIPSerial(Serial); // Change to Serial1 or Serial2 etc. for boards with multiple serial ports that don’t have Serial
+#endif
+
+void setup() {
+ //begin SLIPSerial just like Serial
+ SLIPSerial.begin(9600); // set this as high as you can reliably run on your platform
+}
+
+void loop(){
+ OSCBundle bndl;
+ int size;
+ //receive a bundle
+
+ while(!SLIPSerial.endofPacket())
+ if( (size =SLIPSerial.available()) > 0)
+ {
+ while(size--)
+ bndl.fill(SLIPSerial.read());
+ }
+
+ if(!bndl.hasError())
+ {
+ static int32_t sequencenumber=0;
+ // we can sneak an addition onto the end of the bundle
+ bndl.add("/micros").add((int32_t)micros()); // (int32_t) is the type of OSC Integers
+ bndl.add("/sequencenumber").add(sequencenumber++);
+ bndl.add("/digital/5").add(digitalRead(5)==HIGH);
+ bndl.add("/lsb").add((sequencenumber &1)==1);
+ SLIPSerial.beginPacket(); // mark the beginning of the OSC Packet
+ bndl.send(SLIPSerial);
+ SLIPSerial.endPacket();
+ }
+}
+
diff --git a/lib/OSC/examples/SerialOscuinoAdaFruitPlayGroundExpresswithBundles/SerialOscuinoAdaFruitPlayGroundExpresswithBundles.ino b/lib/OSC/examples/SerialOscuinoAdaFruitPlayGroundExpresswithBundles/SerialOscuinoAdaFruitPlayGroundExpresswithBundles.ino
new file mode 100644
index 0000000..2b1a8af
--- /dev/null
+++ b/lib/OSC/examples/SerialOscuinoAdaFruitPlayGroundExpresswithBundles/SerialOscuinoAdaFruitPlayGroundExpresswithBundles.ino
@@ -0,0 +1,332 @@
+
+#include
+#include
+
+#include
+
+#ifdef BOARD_HAS_USB_SERIAL
+SLIPEncodedUSBSerial SLIPSerial( thisBoardsSerialUSB );
+#else
+ SLIPEncodedSerial SLIPSerial(Serial); // Change to Serial1 or Serial2 etc. for boards with multiple serial ports that don’t have Serial
+#endif
+
+//outgoing messages
+
+OSCBundle bundleOUT;
+
+//converts the pin to an osc address
+char * numToOSCAddress( int pin){
+ static char s[10];
+ int i = 9;
+
+ s[i--]= '\0';
+ do
+ {
+ s[i] = "0123456789"[pin % 10];
+ --i;
+ pin /= 10;
+ }
+ while(pin && i);
+ s[i] = '/';
+ return &s[i];
+}
+
+/**
+ * ROUTES
+ *
+ * these are where the routing functions go
+ *
+ */
+
+/**
+ * DIGITAL
+ *
+ * called when address matched "/d"
+ * expected format:
+ * /d/(pin)
+ * /u = digitalRead with pullup
+ * (no value) = digitalRead without pullup
+ * (value) = digital write on that pin
+ *
+ */
+
+void routeDigital(OSCMessage &msg, int addrOffset ){
+ //match input or output
+ for(byte pin = 0; pin < NUM_DIGITAL_PINS; pin++){
+ //match against the pin number strings
+ int pinMatched = msg.match(numToOSCAddress(pin), addrOffset);
+ if(pinMatched){
+ //if it has an int, then it's a digital write
+ if (msg.isInt(0)){
+ pinMode(pin, OUTPUT);
+ digitalWrite(pin, (msg.getInt(0)>0) ? HIGH:LOW);
+ }
+ else if(msg.isFloat(0)){
+ analogWrite(pin, (int)(msg.getFloat(0)*255.0f));
+ }
+
+ //otherwise it's an digital read
+ //with a pullup?
+ else if (msg.fullMatch("/u", pinMatched+addrOffset)){
+ //set the pullup
+ pinMode(pin, INPUT_PULLUP);
+ //setup the output address which should be /d/(pin)/u
+ char outputAddress[9];
+ strcpy(outputAddress, "/d");
+ strcat(outputAddress, numToOSCAddress(pin));
+ strcat(outputAddress,"/u");
+ //do the digital read and send the results
+ bundleOUT.add(outputAddress).add(digitalRead(pin));
+ } //else without a pullup
+ else {
+ //set the pinmode
+ pinMode(pin, INPUT);
+ //setup the output address which should be /d/(pin)
+ char outputAddress[6];
+ strcpy(outputAddress, "/d");
+ strcat(outputAddress, numToOSCAddress(pin));
+ //do the digital read and send the results
+ bundleOUT.add(outputAddress).add(digitalRead(pin));
+ }
+ }
+ }
+}
+
+/**
+ * ANALOG
+ *
+ * called when the address matches "/a"
+ *
+ * format:
+ * /a/(pin)
+ * /u = analogRead with pullup
+ * (no value) = analogRead without pullup
+ * (digital value) = digital write on that pin
+ * (float value) = analogWrite on that pin
+ *
+ **/
+
+void routeAnalog(OSCMessage &msg, int addrOffset ){
+ //iterate through all the analog pins
+ for(byte pin = 0; pin < NUM_ANALOG_INPUTS; pin++){
+ //match against the pin number strings
+ int pinMatched = msg.match(numToOSCAddress(pin), addrOffset);
+ if(pinMatched){
+ //if it has an int, then it's a digital write
+ if (msg.isInt(0)){
+ pinMode(analogInputToDigitalPin(pin), OUTPUT);
+ digitalWrite(analogInputToDigitalPin(pin), (msg.getInt(0) > 0)? HIGH: LOW);
+ }
+ else if(msg.isFloat(0)){
+ analogWrite(pin, (int)(msg.getFloat(0)*255.0f));
+ }
+#ifdef BOARD_HAS_ANALOG_PULLUP
+ //with a pullup?
+ else if (msg.fullMatch("/u", pinMatched+addrOffset)){
+ //set the pullup
+
+ pinMode(analogInputToDigitalPin(pin), INPUT_PULLUP);
+
+ //setup the output address which should be /a/(pin)/u
+ char outputAddress[9];
+ strcpy(outputAddress, "/a");
+ strcat(outputAddress, numToOSCAddress(pin));
+ strcat(outputAddress,"/u");
+ //do the analog read and send the results
+ bundleOUT.add(outputAddress).add((int32_t)analogRead(pin));
+ } //else without a pullup
+#endif
+
+ else {
+ //otherwise it's an analog read
+ //set the pinmode
+
+ pinMode(analogInputToDigitalPin(pin), INPUT);
+ //setup the output address which should be /a/(pin)
+ char outputAddress[6];
+ strcpy(outputAddress, "/a");
+ strcat(outputAddress, numToOSCAddress(pin));
+ //do the analog read and send the results
+ bundleOUT.add(outputAddress).add((int32_t)analogRead(pin));
+ }
+ }
+ }
+}
+
+#ifdef BOARD_HAS_TONE
+/**
+ * TONE
+ *
+ * square wave output "/tone"
+ *
+ * format:
+ * /tone/pin
+ *
+ * (digital value) (float value) = frequency in Hz
+ * (no value) disable tone
+ *
+ **/
+
+void routeTone(OSCMessage &msg, int addrOffset ){
+ //iterate through all the analog pins
+ for(byte pin = 0; pin < NUM_DIGITAL_PINS; pin++){
+ //match against the pin number strings
+ int pinMatched = msg.match(numToOSCAddress(pin), addrOffset);
+ if(pinMatched){
+ unsigned int frequency = 0;
+ //if it has an int, then it's an integers frequency in Hz
+ if (msg.isInt(0)){
+ frequency = msg.getInt(0);
+ } //otherwise it's a floating point frequency in Hz
+ else if(msg.isFloat(0)){
+ frequency = msg.getFloat(0);
+ }
+ else
+ noTone(pin);
+ if(frequency>0)
+ {
+ if(msg.isInt(1))
+ tone(pin, frequency, msg.getInt(1));
+ else
+ tone(pin, frequency);
+ }
+ }
+ }
+}
+#endif
+
+
+#ifdef BOARD_HAS_CAPACITANCE_SENSING
+#if defined(__MKL26Z64__)
+// teensy 3.0LC
+#define NTPINS 11
+const int cpins[NTPINS] = {22,23,19,18,17,16,15,0,1,3,4 };
+#elif defined(__MK66FX1M0__)
+// teensy 3.6
+#define NTPINS 12
+const int cpins[NTPINS] = {0,1,14,15,16,17,18,19,22,23,29,30 };
+#else
+//Teensy 3.1 3.2
+#define NTPINS 12
+const int cpins[NTPINS] = {22,23,19,18,17,16,15,0,1,25,32, 33 };
+#endif
+
+void routeTouch(OSCMessage &msg, int addrOffset )
+{
+ for(int i=0;i 0)? HIGH: LOW);
+ bundleOUT.add("/s/l").add(i);
+ }
+ }
+}
+
+/**
+ * MAIN METHODS
+ *
+ * setup and loop, bundle receiving/sending, initial routing
+ */
+
+
+void setup() {
+ SLIPSerial.begin(115200); // set this as high as you can reliably run on your platform
+#if ARDUINO >= 100
+ while(!Serial)
+ ; // Leonardo bug
+#endif
+
+}
+
+//reads and routes the incoming messages
+void loop(){
+ OSCBundle bundleIN;
+ int size;
+
+ while(!SLIPSerial.endofPacket())
+ if ((size =SLIPSerial.available()) > 0)
+ {
+ while(size--)
+ bundleIN.fill(SLIPSerial.read());
+ }
+
+ if(!bundleIN.hasError())
+ {
+ bundleIN.route("/s", routeSystem);
+ bundleIN.route("/a", routeAnalog);
+ bundleIN.route("/d", routeDigital);
+#ifdef BOARD_HAS_TONE
+ bundleIN.route("/tone", routeTone);
+#endif
+#ifdef BOARD_HAS_CAPACITANCE_SENSING
+ bundleIN.route("/c", routeTouch);
+#endif
+ }
+ bundleIN.empty();
+
+
+//send the outgoing message
+ SLIPSerial.beginPacket();
+ bundleOUT.send(SLIPSerial);
+ SLIPSerial.endPacket();
+ bundleOUT.empty();
+
+}
+
+
+
+
+
+
+
diff --git a/lib/OSC/examples/SerialOscuinoForFubarino/SerialOscuinoForFubarino.ino b/lib/OSC/examples/SerialOscuinoForFubarino/SerialOscuinoForFubarino.ino
new file mode 100644
index 0000000..0900c49
--- /dev/null
+++ b/lib/OSC/examples/SerialOscuinoForFubarino/SerialOscuinoForFubarino.ino
@@ -0,0 +1,292 @@
+#include
+#include
+
+// Fubarino MINI
+
+#include
+
+#ifdef BOARD_HAS_USB_SERIAL
+SLIPEncodedUSBSerial SLIPSerial( thisBoardsSerialUSB );
+#else
+ SLIPEncodedSerial SLIPSerial(Serial); // Change to Serial1 or Serial2 etc. for boards with multiple serial ports that don’t have Serial
+#endif
+OSCBundle bundleOUT;
+
+//converts the pin to an osc address
+ char * numToOSCAddress( int pin){
+ static char s[10];
+ int i = 9;
+ s[i--]= '\0';
+ do
+{
+ s[i] = "0123456789"[pin % 10];
+ --i;
+ pin /= 10;
+}
+ while(pin && i);
+s[i] = '/';
+return &s[i];
+}
+
+/**
+ * ROUTES
+ *
+ * these are where the routing functions go
+ *
+ */
+/**
+ * DIGITAL
+ *
+ * called when address matched "/d"
+ * expected format:
+ * /d/(pin)
+ * /u = digitalRead with pullup
+ * (no value) = digitalRead without pullup
+ * (value) = digital write on that pin
+ *
+ */
+
+void routeDigital(OSCMessage &msg, int addrOffset ){
+ //match input or output
+ for(byte pin = 0; pin < NUM_DIGITAL_PINS; pin++){
+ //match against the pin number strings
+ int pinMatched = msg.match(numToOSCAddress(pin), addrOffset);
+ if(pinMatched){
+ switch(pin)
+ {
+ // fubarino MINI
+ // these are used for clocks and USB and Program switch and shouldn't be written to
+ // unless you know what you are doing
+ case 3: case 14: case 15: case 23: case 16: case 31:case 32: goto out;
+ }
+ //if it has an int, then it's a digital write
+ if (msg.isInt(0)){
+ pinMode(pin, OUTPUT);
+ digitalWrite(pin, (msg.getInt(0)>0) ? HIGH:LOW);
+ } //otherwise it's an digital read
+ //with a pullup?
+ else if (msg.fullMatch("/u", pinMatched+addrOffset)){
+ //set the pullup
+ pinMode(pin, INPUT_PULLUP);
+ //setup the output address which should be /d/(pin)/u
+ char outputAddress[9];
+ strcpy(outputAddress, "/d");
+ strcat(outputAddress, numToOSCAddress(pin));
+ strcat(outputAddress,"/u");
+ //do the digital read and send the results
+ {
+ OSCMessage msgOut(outputAddress); msgOut.add(digitalRead(pin));
+ SLIPSerial.beginPacket(); msgOut.send(SLIPSerial); SLIPSerial.endPacket();
+ }
+ } //else without a pullup
+ else {
+ //set the pinmode
+ pinMode(pin, INPUT);
+ //setup the output address which should be /d/(pin)
+ char outputAddress[6];
+ strcpy(outputAddress, "/d");
+ strcat(outputAddress, numToOSCAddress(pin));
+ //do the digital read and send the results
+ {
+ OSCMessage msgOut(outputAddress); msgOut.add(digitalRead(pin));
+ SLIPSerial.beginPacket(); msgOut.send(SLIPSerial); SLIPSerial.endPacket();
+ }
+ }
+ }
+ out: ;
+ }
+}
+
+/**
+ * ANALOG
+ *
+ * called when the address matches "/a"
+ *
+ * format:
+ * /a/(pin)
+ * /u = analogRead with pullup
+ * (no value) = analogRead without pullup
+ * (digital value) = digital write on that pin
+ * (float value) = analogWrite on that pin
+ *
+ **/
+
+void routeAnalog(OSCMessage &msg, int addrOffset ){
+ //iterate through all the analog pins
+ for(byte pin = 0; pin < NUM_ANALOG_INPUTS; pin++){
+ //match against the pin number strings
+ int pinMatched = msg.match(numToOSCAddress(pin), addrOffset);
+ if(pinMatched){
+ //if it has an int, then it's a digital write
+ if (msg.isInt(0)){
+ pinMode(analogInputToDigitalPin(pin), OUTPUT);
+ digitalWrite(analogInputToDigitalPin(pin), (msg.getInt(0) > 0)? HIGH: LOW);
+ } //otherwise it's an analog read
+ else if(msg.isFloat(0)){
+ analogWrite(pin, (int)(msg.getFloat(0)*255.0f));
+ }
+#ifdef BOARD_HAS_ANALOG_PULLUP
+ //with a pullup?
+ else if (msg.fullMatch("/u", pinMatched+addrOffset)){
+ //set the pullup
+
+ pinMode(analogInputToDigitalPin(pin), INPUT_PULLUP);
+
+ //setup the output address which should be /a/(pin)/u
+ char outputAddress[9];
+ strcpy(outputAddress, "/a");
+ strcat(outputAddress, numToOSCAddress(pin));
+ strcat(outputAddress,"/u");
+ //do the analog read and send the results
+ {
+ OSCMessage msgOut(outputAddress); msgOut.add((int32_t)analogRead(pin));
+ SLIPSerial.beginPacket();msgOut.send(SLIPSerial); SLIPSerial.endPacket();
+ }
+ } //else without a pullup
+#endif
+ else {
+ //set the pinmode
+ // This fails on Arduino 1.04 on Leanardo, I added this to fix it: #define analogInputToDigitalPin(p) (p+18)
+
+ pinMode(analogInputToDigitalPin(pin), INPUT);
+ //setup the output address which should be /a/(pin)
+ char outputAddress[6];
+ strcpy(outputAddress, "/a");
+ strcat(outputAddress, numToOSCAddress(pin));
+ //do the analog read and send the results
+ {
+ OSCMessage msgOut(outputAddress); msgOut.add((int32_t)analogRead(pin));
+ SLIPSerial.beginPacket(); msgOut.send(SLIPSerial); SLIPSerial.endPacket();
+ }
+ }
+ }
+ }
+}
+
+#ifdef BOARD_HAS_TONE
+
+/**
+ * TONE
+ *
+ * square wave output "/tone"
+ *
+ * format:
+ * /tone/pin
+ *
+ * (digital value) (float value) = frequency in Hz
+ * (no value) disable tone
+ *
+ **/
+
+void routeTone(OSCMessage &msg, int addrOffset ){
+ //iterate through all the analog pins
+ for(byte pin = 0; pin < NUM_DIGITAL_PINS; pin++){
+ //match against the pin number strings
+ int pinMatched = msg.match(numToOSCAddress(pin), addrOffset);
+ if(pinMatched){
+ unsigned int frequency = 0;
+ //if it has an int, then it's an integers frequency in Hz
+ if (msg.isInt(0)){
+ frequency = msg.getInt(0);
+ } //otherwise it's a floating point frequency in Hz
+ else if(msg.isFloat(0)){
+ frequency = msg.getFloat(0);
+ }
+ else
+ noTone(pin);
+ if(frequency>0)
+ {
+ if(msg.isInt(1))
+ tone(pin, frequency, msg.getInt(1));
+ else
+ tone(pin, frequency);
+ }
+ }
+ }
+}
+#endif
+
+
+
+/**
+ * SYSTEM MESSAGES
+ *
+ * expected format:
+ * /s
+ * /m = microseconds
+ * /d = number of digital pins
+ * /a = number of analog pins
+ * /l integer = set the led
+ * /t = temperature
+ * /s = power supply voltage
+ */
+//
+void routeSystem(OSCMessage &msg, int addrOffset ){
+
+ #ifdef BOARD_HAS_DIE_TEMPERATURE_SENSOR
+ if (msg.fullMatch("/t", addrOffset)){
+ { OSCMessage msgOut("/s/t"); msgOut.add(getTemperature()); SLIPSerial.beginPacket();msgOut.send(SLIPSerial); SLIPSerial.endPacket(); }
+ }
+ #endif
+ #ifdef BOARD_HAS_DIE_POWER_SUPPLY_MEASUREMENT
+ if (msg.fullMatch("/s", addrOffset)){
+ { OSCMessage msgOut("/s/s"); msgOut.add(getSupplyVoltage()); SLIPSerial.beginPacket();msgOut.send(SLIPSerial); SLIPSerial.endPacket(); }
+ }
+ #endif
+ if (msg.fullMatch("/m", addrOffset)){
+ { OSCMessage msgOut("/s/m"); msgOut.add((int32_t)micros()); SLIPSerial.beginPacket();msgOut.send(SLIPSerial); SLIPSerial.endPacket(); }
+ }
+ if (msg.fullMatch("/d", addrOffset)){
+ { OSCMessage msgOut("/s/d"); msgOut.add(NUM_DIGITAL_PINS); SLIPSerial.beginPacket();msgOut.send(SLIPSerial); SLIPSerial.endPacket(); }
+ }
+ if (msg.fullMatch("/a", addrOffset)){
+ { OSCMessage msgOut("/s/a"); msgOut.add(NUM_ANALOG_INPUTS); SLIPSerial.beginPacket();msgOut.send(SLIPSerial); SLIPSerial.endPacket(); }
+ }
+ if (msg.fullMatch("/l", addrOffset)){
+
+ if (msg.isInt(0)){
+ pinMode(LED_BUILTIN, OUTPUT);
+ int i = msg.getInt(0);
+ pinMode(LED_BUILTIN, OUTPUT);
+ digitalWrite(LED_BUILTIN, (i > 0)? HIGH: LOW);
+ { OSCMessage msgOut("/s/l"); msgOut.add(i); SLIPSerial.beginPacket();msgOut.send(SLIPSerial); SLIPSerial.endPacket(); }
+ }
+ }
+}
+
+/**
+ * MAIN METHODS
+ *
+ * setup and loop, bundle receiving/sending, initial routing
+ */
+
+void setup() {
+ SLIPSerial.begin(9600); // set this as high as you can reliably run on your platform
+}
+
+//reads and routes the incoming messages
+void loop(){
+ OSCBundle bundleIN;
+ int size;
+ while(!SLIPSerial.endofPacket())
+ if ((size =SLIPSerial.available()) > 0)
+ {
+ while(size--)
+ bundleIN.fill(SLIPSerial.read());
+ }
+
+ if(!bundleIN.hasError())
+ {
+ bundleIN.route("/s", routeSystem);
+ bundleIN.route("/a", routeAnalog);
+ bundleIN.route("/d", routeDigital);
+#ifdef BOARD_HAS_TONE
+ bundleIN.route("/tone", routeTone);
+#endif
+#ifdef BOARD_HAS_CAPACITANCE_SENSING
+ bundleIN.route("/c", routeTouch);
+#endif
+ }
+
+}
+
diff --git a/lib/OSC/examples/SerialOscuinoGemmaM0/SerialOscuinoGemmaM0.ino b/lib/OSC/examples/SerialOscuinoGemmaM0/SerialOscuinoGemmaM0.ino
new file mode 100644
index 0000000..68d9dbe
--- /dev/null
+++ b/lib/OSC/examples/SerialOscuinoGemmaM0/SerialOscuinoGemmaM0.ino
@@ -0,0 +1,311 @@
+
+#include
+#include
+#include "Adafruit_FreeTouch.h"
+#include
+
+Adafruit_FreeTouch qt_0 = Adafruit_FreeTouch(A0, OVERSAMPLE_4, RESISTOR_50K, FREQ_MODE_NONE);
+Adafruit_FreeTouch qt_1 = Adafruit_FreeTouch(A1, OVERSAMPLE_4, RESISTOR_50K, FREQ_MODE_NONE);
+Adafruit_FreeTouch qt_2 = Adafruit_FreeTouch(A2, OVERSAMPLE_4, RESISTOR_50K, FREQ_MODE_NONE);
+ Adafruit_FreeTouch *p[3] = { &qt_0, &qt_1, &qt_2 };
+
+#undef NUM_DIGITAL_PINS
+#define NUM_DIGITAL_PINS 3
+#undef NUM_ANALOG_PINS
+#define NUM_ANALOG_PINS 3
+
+SLIPEncodedUSBSerial SLIPSerial( Serial );
+
+
+
+//outgoing messages
+
+OSCBundle bundleOUT;
+
+//converts the pin to an osc address
+char * numToOSCAddress( int pin){
+ static char s[10];
+ int i = 9;
+
+ s[i--]= '\0';
+ do
+ {
+ s[i] = "0123456789"[pin % 10];
+ --i;
+ pin /= 10;
+ }
+ while(pin && i);
+ s[i] = '/';
+ return &s[i];
+}
+
+/**
+ * ROUTES
+ *
+ * these are where the routing functions go
+ *
+ */
+
+/**
+ * DIGITAL
+ *
+ * called when address matched "/d"
+ * expected format:
+ * /d/(pin)
+ * /u = digitalRead with pullup
+ * (no value) = digitalRead without pullup
+ * (value) = digital write on that pin
+ *
+ */
+
+void routeDigital(OSCMessage &msg, int addrOffset ){
+ //match input or output
+ for(byte pin = 0; pin < NUM_DIGITAL_PINS; pin++){
+ //match against the pin number strings
+ int pinMatched = msg.match(numToOSCAddress(pin), addrOffset);
+ if(pinMatched){
+ //if it has an int, then it's a digital write
+ if (msg.isInt(0)){
+ pinMode(pin, OUTPUT);
+ digitalWrite(pin, (msg.getInt(0)>0) ? HIGH:LOW);
+ }
+ else if(msg.isFloat(0)){
+ analogWrite(pin, (int)(msg.getFloat(0)*255.0f));
+ }
+
+ //otherwise it's an digital read
+ //with a pullup?
+ else if (msg.fullMatch("/u", pinMatched+addrOffset)){
+ //set the pullup
+ pinMode(pin, INPUT_PULLUP);
+ //setup the output address which should be /d/(pin)/u
+ char outputAddress[9];
+ strcpy(outputAddress, "/d");
+ strcat(outputAddress, numToOSCAddress(pin));
+ strcat(outputAddress,"/u");
+ //do the digital read and send the results
+ bundleOUT.add(outputAddress).add(digitalRead(pin));
+ } //else without a pullup
+ else {
+ //set the pinmode
+ pinMode(pin, INPUT);
+ //setup the output address which should be /d/(pin)
+ char outputAddress[6];
+ strcpy(outputAddress, "/d");
+ strcat(outputAddress, numToOSCAddress(pin));
+ //do the digital read and send the results
+ bundleOUT.add(outputAddress).add(digitalRead(pin));
+ }
+ }
+ }
+}
+
+/**
+ * ANALOG
+ *
+ * called when the address matches "/a"
+ *
+ * format:
+ * /a/(pin)
+ * /u = analogRead with pullup
+ * (no value) = analogRead without pullup
+ * (digital value) = digital write on that pin
+ * (float value) = analogWrite on that pin
+ *
+ **/
+
+void routeAnalog(OSCMessage &msg, int addrOffset ){
+ //iterate through all the analog pins
+ for(byte pin = 0; pin < NUM_ANALOG_INPUTS; pin++){
+ //match against the pin number strings
+ int pinMatched = msg.match(numToOSCAddress(pin), addrOffset);
+ if(pinMatched){
+ //if it has an int, then it's a digital write
+ if (msg.isInt(0)){
+ pinMode(analogInputToDigitalPin(pin), OUTPUT);
+ digitalWrite(analogInputToDigitalPin(pin), (msg.getInt(0) > 0)? HIGH: LOW);
+ }
+ else if(msg.isFloat(0)){
+ analogWrite(pin, (int)(msg.getFloat(0)*255.0f));
+ }
+#ifdef BOARD_HAS_ANALOG_PULLUP
+ //with a pullup?
+ else if (msg.fullMatch("/u", pinMatched+addrOffset)){
+ //set the pullup
+
+ pinMode(analogInputToDigitalPin(pin), INPUT_PULLUP);
+
+ //setup the output address which should be /a/(pin)/u
+ char outputAddress[9];
+ strcpy(outputAddress, "/a");
+ strcat(outputAddress, numToOSCAddress(pin));
+ strcat(outputAddress,"/u");
+ //do the analog read and send the results
+ bundleOUT.add(outputAddress).add((int32_t)analogRead(pin));
+ } //else without a pullup
+#endif
+
+ else {
+ //otherwise it's an analog read
+ //set the pinmode
+
+ pinMode(analogInputToDigitalPin(pin), INPUT);
+ //setup the output address which should be /a/(pin)
+ char outputAddress[6];
+ strcpy(outputAddress, "/a");
+ strcat(outputAddress, numToOSCAddress(pin));
+ //do the analog read and send the results
+ bundleOUT.add(outputAddress).add((int32_t)analogRead(pin));
+ }
+ }
+ }
+}
+
+#if 1
+/**
+ * TONE
+ *
+ * square wave output "/tone"
+ *
+ * format:
+ * /tone/pin
+ *
+ * (digital value) (float value) = frequency in Hz
+ * (no value) disable tone
+ *
+ **/
+
+void routeTone(OSCMessage &msg, int addrOffset ){
+ //iterate through all the analog pins
+ for(byte pin = 0; pin < NUM_DIGITAL_PINS; pin++){
+ //match against the pin number strings
+ int pinMatched = msg.match(numToOSCAddress(pin), addrOffset);
+ if(pinMatched){
+ unsigned int frequency = 0;
+ //if it has an int, then it's an integers frequency in Hz
+ if (msg.isInt(0)){
+ frequency = msg.getInt(0);
+ } //otherwise it's a floating point frequency in Hz
+ else if(msg.isFloat(0)){
+ frequency = msg.getFloat(0);
+ }
+ else
+ noTone(pin);
+ if(frequency>0)
+ {
+ if(msg.isInt(1))
+ tone(pin, frequency, msg.getInt(1));
+ else
+ tone(pin, frequency);
+ }
+ }
+ }
+}
+#endif
+
+
+
+
+void routeTouch(OSCMessage &msg, int addrOffset )
+{
+ for(int i=0;i<3;++i)
+ {
+ const char *name = numToOSCAddress(i);
+ int pinMatched = msg.match(name, addrOffset);
+ if(pinMatched && p[i])
+ {
+
+ char outputAddress[9];
+ strcpy(outputAddress, "/c");
+ strcat(outputAddress, name);
+ bundleOUT.add(outputAddress).add(p[i]->measure());
+ }
+ }
+}
+
+/**
+ * SYSTEM MESSAGES
+ *
+ * expected format:
+ * /s
+ * /m = microseconds
+ * /d = number of digital pins
+ * /a = number of analog pins
+ * /l integer = set the led
+ * /t = temperature
+ * /s = power supply voltage
+ */
+//
+void routeSystem(OSCMessage &msg, int addrOffset ){
+
+ if (msg.fullMatch("/m", addrOffset)){
+ bundleOUT.add("/s/m").add((int32_t)micros());
+ }
+ if (msg.fullMatch("/d", addrOffset)){
+ bundleOUT.add("/s/d").add(NUM_DIGITAL_PINS);
+ }
+ if (msg.fullMatch("/a", addrOffset)){
+ bundleOUT.add("/s/a").add(NUM_ANALOG_INPUTS);
+ }
+ if (msg.fullMatch("/l", addrOffset)){
+ if (msg.isInt(0)){
+ pinMode(LED_BUILTIN, OUTPUT);
+ int i = msg.getInt(0);
+ pinMode(LED_BUILTIN, OUTPUT);
+ digitalWrite(LED_BUILTIN, (i > 0)? HIGH: LOW);
+ bundleOUT.add("/s/l").add(i);
+ }
+ }
+}
+
+/**
+ * MAIN METHODS
+ *
+ * setup and loop, bundle receiving/sending, initial routing
+ */
+
+
+void setup() {
+ SLIPSerial.begin(115200); // set this as high as you can reliably run on your platform
+ for(int i=0; i<3; ++i)
+ if(!p[i]->begin())
+ p[i] =0;
+}
+
+//reads and routes the incoming messages
+void loop(){
+ OSCBundle bundleIN;
+ int size;
+
+ while(!SLIPSerial.endofPacket())
+ if ((size =SLIPSerial.available()) > 0)
+ {
+ while(size--)
+ bundleIN.fill(SLIPSerial.read());
+ }
+
+ if(!bundleIN.hasError())
+ {
+ bundleIN.route("/s", routeSystem);
+ bundleIN.route("/a", routeAnalog);
+ bundleIN.route("/d", routeDigital);
+ bundleIN.route("/tone", routeTone);
+ bundleIN.route("/c", routeTouch);
+ }
+ bundleIN.empty();
+
+
+//send the outgoing message
+ SLIPSerial.beginPacket();
+ bundleOUT.send(SLIPSerial);
+ SLIPSerial.endPacket();
+ bundleOUT.empty();
+
+}
+
+
+
+
+
+
+
diff --git a/lib/OSC/examples/SerialOscuinowithBundles/SerialOscuinowithBundles.ino b/lib/OSC/examples/SerialOscuinowithBundles/SerialOscuinowithBundles.ino
new file mode 100644
index 0000000..5828ed5
--- /dev/null
+++ b/lib/OSC/examples/SerialOscuinowithBundles/SerialOscuinowithBundles.ino
@@ -0,0 +1,323 @@
+
+#include
+#include
+
+#include
+
+#ifdef BOARD_HAS_USB_SERIAL
+SLIPEncodedUSBSerial SLIPSerial( thisBoardsSerialUSB );
+#else
+ SLIPEncodedSerial SLIPSerial(Serial); // Change to Serial1 or Serial2 etc. for boards with multiple serial ports that don’t have Serial
+#endif
+
+
+//outgoing messages
+
+OSCBundle bundleOUT;
+
+//converts the pin to an osc address
+char * numToOSCAddress( int pin){
+ static char s[10];
+ int i = 9;
+
+ s[i--]= '\0';
+ do
+ {
+ s[i] = "0123456789"[pin % 10];
+ --i;
+ pin /= 10;
+ }
+ while(pin && i);
+ s[i] = '/';
+ return &s[i];
+}
+
+/**
+ * ROUTES
+ *
+ * these are where the routing functions go
+ *
+ */
+
+/**
+ * DIGITAL
+ *
+ * called when address matched "/d"
+ * expected format:
+ * /d/(pin)
+ * /u = digitalRead with pullup
+ * (no value) = digitalRead without pullup
+ * (value) = digital write on that pin
+ *
+ */
+
+void routeDigital(OSCMessage &msg, int addrOffset ){
+ //match input or output
+ for(byte pin = 0; pin < NUM_DIGITAL_PINS; pin++){
+ //match against the pin number strings
+ int pinMatched = msg.match(numToOSCAddress(pin), addrOffset);
+ if(pinMatched){
+ //if it has an int, then it's a digital write
+ if (msg.isInt(0)){
+ pinMode(pin, OUTPUT);
+ digitalWrite(pin, (msg.getInt(0)>0) ? HIGH:LOW);
+ }
+ else if(msg.isFloat(0)){
+ analogWrite(pin, (int)(msg.getFloat(0)*255.0f));
+ }
+
+ //otherwise it's an digital read
+ //with a pullup?
+ else if (msg.fullMatch("/u", pinMatched+addrOffset)){
+ //set the pullup
+ pinMode(pin, INPUT_PULLUP);
+ //setup the output address which should be /d/(pin)/u
+ char outputAddress[9];
+ strcpy(outputAddress, "/d");
+ strcat(outputAddress, numToOSCAddress(pin));
+ strcat(outputAddress,"/u");
+ //do the digital read and send the results
+ bundleOUT.add(outputAddress).add(digitalRead(pin));
+ } //else without a pullup
+ else {
+ //set the pinmode
+ pinMode(pin, INPUT);
+ //setup the output address which should be /d/(pin)
+ char outputAddress[6];
+ strcpy(outputAddress, "/d");
+ strcat(outputAddress, numToOSCAddress(pin));
+ //do the digital read and send the results
+ bundleOUT.add(outputAddress).add(digitalRead(pin));
+ }
+ }
+ }
+}
+
+/**
+ * ANALOG
+ *
+ * called when the address matches "/a"
+ *
+ * format:
+ * /a/(pin)
+ * /u = analogRead with pullup
+ * (no value) = analogRead without pullup
+ * (digital value) = digital write on that pin
+ * (float value) = analogWrite on that pin
+ *
+ **/
+
+void routeAnalog(OSCMessage &msg, int addrOffset ){
+ //iterate through all the analog pins
+ for(byte pin = 0; pin < NUM_ANALOG_INPUTS; pin++){
+ //match against the pin number strings
+ int pinMatched = msg.match(numToOSCAddress(pin), addrOffset);
+ if(pinMatched){
+ //if it has an int, then it's a digital write
+ if (msg.isInt(0)){
+ pinMode(analogInputToDigitalPin(pin), OUTPUT);
+ digitalWrite(analogInputToDigitalPin(pin), (msg.getInt(0) > 0)? HIGH: LOW);
+ }
+ else if(msg.isFloat(0)){
+ analogWrite(pin, (int)(msg.getFloat(0)*255.0f));
+ }
+#ifdef BOARD_HAS_ANALOG_PULLUP
+ //with a pullup?
+ else if (msg.fullMatch("/u", pinMatched+addrOffset)){
+ //set the pullup
+
+ pinMode(analogInputToDigitalPin(pin), INPUT_PULLUP);
+
+ //setup the output address which should be /a/(pin)/u
+ char outputAddress[9];
+ strcpy(outputAddress, "/a");
+ strcat(outputAddress, numToOSCAddress(pin));
+ strcat(outputAddress,"/u");
+ //do the analog read and send the results
+ bundleOUT.add(outputAddress).add((int32_t)analogRead(pin));
+ } //else without a pullup
+#endif
+
+ else {
+ //otherwise it's an analog read
+ //set the pinmode
+
+ pinMode(analogInputToDigitalPin(pin), INPUT);
+ //setup the output address which should be /a/(pin)
+ char outputAddress[6];
+ strcpy(outputAddress, "/a");
+ strcat(outputAddress, numToOSCAddress(pin));
+ //do the analog read and send the results
+ bundleOUT.add(outputAddress).add((int32_t)analogRead(pin));
+ }
+ }
+ }
+}
+
+#ifdef BOARD_HAS_TONE
+/**
+ * TONE
+ *
+ * square wave output "/tone"
+ *
+ * format:
+ * /tone/pin
+ *
+ * (digital value) (float value) = frequency in Hz
+ * (no value) disable tone
+ *
+ **/
+
+void routeTone(OSCMessage &msg, int addrOffset ){
+ //iterate through all the analog pins
+ for(byte pin = 0; pin < NUM_DIGITAL_PINS; pin++){
+ //match against the pin number strings
+ int pinMatched = msg.match(numToOSCAddress(pin), addrOffset);
+ if(pinMatched){
+ unsigned int frequency = 0;
+ //if it has an int, then it's an integers frequency in Hz
+ if (msg.isInt(0)){
+ frequency = msg.getInt(0);
+ } //otherwise it's a floating point frequency in Hz
+ else if(msg.isFloat(0)){
+ frequency = msg.getFloat(0);
+ }
+ else
+ noTone(pin);
+ if(frequency>0)
+ {
+ if(msg.isInt(1))
+ tone(pin, frequency, msg.getInt(1));
+ else
+ tone(pin, frequency);
+ }
+ }
+ }
+}
+#endif
+
+
+#ifdef BOARD_HAS_CAPACITANCE_SENSING
+#if defined(__MKL26Z64__)
+#define NTPINS 11
+const int cpins[NTPINS] = {22,23,19,18,17,16,15,0,1,3,4 };
+#else
+#define NTPINS 12
+const int cpins[NTPINS] = {22,23,19,18,17,16,15,0,1,25,32, 33 };
+#endif
+
+void routeTouch(OSCMessage &msg, int addrOffset )
+{
+ for(int i=0;i 0)? HIGH: LOW);
+ bundleOUT.add("/s/l").add(i);
+ }
+ }
+}
+
+/**
+ * MAIN METHODS
+ *
+ * setup and loop, bundle receiving/sending, initial routing
+ */
+
+
+void setup() {
+ SLIPSerial.begin(115200); // set this as high as you can reliably run on your platform
+}
+
+//reads and routes the incoming messages
+void loop(){
+ OSCBundle bundleIN;
+ int size;
+
+ while(!SLIPSerial.endofPacket())
+ if ((size =SLIPSerial.available()) > 0)
+ {
+ while(size--)
+ bundleIN.fill(SLIPSerial.read());
+ }
+
+ if(!bundleIN.hasError())
+ {
+ bundleIN.route("/s", routeSystem);
+ bundleIN.route("/a", routeAnalog);
+ bundleIN.route("/d", routeDigital);
+#ifdef BOARD_HAS_TONE
+ bundleIN.route("/tone", routeTone);
+#endif
+#ifdef BOARD_HAS_CAPACITANCE_SENSING
+ bundleIN.route("/c", routeTouch);
+#endif
+ }
+ bundleIN.empty();
+
+
+//send the outgoing message
+ SLIPSerial.beginPacket();
+ bundleOUT.send(SLIPSerial);
+ SLIPSerial.endPacket();
+ bundleOUT.empty();
+
+}
+
+
+
+
+
+
+
diff --git a/lib/OSC/examples/SerialOscuinowithMessages/SerialOscuinowithMessages.ino b/lib/OSC/examples/SerialOscuinowithMessages/SerialOscuinowithMessages.ino
new file mode 100644
index 0000000..894f0fb
--- /dev/null
+++ b/lib/OSC/examples/SerialOscuinowithMessages/SerialOscuinowithMessages.ino
@@ -0,0 +1,338 @@
+
+#include
+#include
+
+#include
+
+#ifdef BOARD_HAS_USB_SERIAL
+SLIPEncodedUSBSerial SLIPSerial( thisBoardsSerialUSB );
+#else
+ SLIPEncodedSerial SLIPSerial(Serial); // Change to Serial1 or Serial2 etc. for boards with multiple serial ports that don’t have Serial
+#endif
+
+
+
+//converts the pin to an osc address
+char * numToOSCAddress( int pin){
+ static char s[10];
+ int i = 9;
+
+ s[i--]= '\0';
+ do
+ {
+ s[i] = "0123456789"[pin % 10];
+ --i;
+ pin /= 10;
+ }
+ while(pin && i);
+ s[i] = '/';
+ return &s[i];
+}
+/**
+ * ROUTES
+ *
+ * these are where the routing functions go
+ *
+ */
+
+/**
+ * DIGITAL
+ *
+ * called when address matched "/d"
+ * expected format:
+ * /d/(pin)
+ * /u = digitalRead with pullup
+ * (no value) = digitalRead without pullup
+ * (value) = digital write on that pin
+ *
+ */
+
+void routeDigital(OSCMessage &msg, int addrOffset ){
+ //match input or output
+ for(byte pin = 0; pin < NUM_DIGITAL_PINS; pin++){
+ //match against the pin number strings
+ int pinMatched = msg.match(numToOSCAddress(pin), addrOffset);
+ if(pinMatched){
+ //if it has an int, then it's a digital write
+ if (msg.isInt(0)){
+ pinMode(pin, OUTPUT);
+ digitalWrite(pin, (msg.getInt(0)>0) ? HIGH:LOW);
+ } //otherwise it's an analog read
+ else if(msg.isFloat(0)){
+ analogWrite(pin, (int)(msg.getFloat(0)*255.0f));
+ }
+
+
+ //otherwise it's an digital read
+ //with a pullup?
+ else if (msg.fullMatch("/u", pinMatched+addrOffset)){
+ //set the pullup
+ pinMode(pin, INPUT_PULLUP);
+ //setup the output address which should be /d/(pin)/u
+ char outputAddress[9];
+ strcpy(outputAddress, "/d");
+ strcat(outputAddress, numToOSCAddress(pin));
+ strcat(outputAddress,"/u");
+ //do the digital read and send the results
+ {
+ OSCMessage msgOut(outputAddress); msgOut.add(digitalRead(pin));
+ SLIPSerial.beginPacket(); msgOut.send(SLIPSerial); SLIPSerial.endPacket();
+ }
+ } //else without a pullup
+ else {
+ //set the pinmode
+ pinMode(pin, INPUT);
+ //setup the output address which should be /d/(pin)
+ char outputAddress[6];
+ strcpy(outputAddress, "/d");
+ strcat(outputAddress, numToOSCAddress(pin));
+ //do the digital read and send the results
+ {
+ OSCMessage msgOut(outputAddress); msgOut.add(digitalRead(pin));
+ SLIPSerial.beginPacket(); msgOut.send(SLIPSerial); SLIPSerial.endPacket();
+ }
+ }
+ }
+ }
+}
+
+/**
+ * ANALOG
+ *
+ * called when the address matches "/a"
+ *
+ * format:
+ * /a/(pin)
+ * /u = analogRead with pullup
+ * (no value) = analogRead without pullup
+ * (digital value) = digital write on that pin
+ * (float value) = analogWrite on that pin
+ *
+ **/
+
+void routeAnalog(OSCMessage &msg, int addrOffset ){
+ //iterate through all the analog pins
+ for(byte pin = 0; pin < NUM_ANALOG_INPUTS; pin++){
+ //match against the pin number strings
+ int pinMatched = msg.match(numToOSCAddress(pin), addrOffset);
+ if(pinMatched){
+ //if it has an int, then it's a digital write
+ if (msg.isInt(0)){
+ pinMode(analogInputToDigitalPin(pin), OUTPUT);
+ digitalWrite(analogInputToDigitalPin(pin), (msg.getInt(0) > 0)? HIGH: LOW);
+ } //otherwise it's an analog read
+ else if(msg.isFloat(0)){
+ analogWrite(pin, (int)(msg.getFloat(0)*255.0f));
+ }
+#ifdef BOARD_HAS_ANALOG_PULLUP
+ //with a pullup?
+ else if (msg.fullMatch("/u", pinMatched+addrOffset)){
+ //set the pullup
+
+ pinMode(analogInputToDigitalPin(pin), INPUT_PULLUP);
+
+ //setup the output address which should be /a/(pin)/u
+ char outputAddress[9];
+ strcpy(outputAddress, "/a");
+ strcat(outputAddress, numToOSCAddress(pin));
+ strcat(outputAddress,"/u");
+ //do the analog read and send the results
+ {
+ OSCMessage msgOut(outputAddress); msgOut.add((int32_t)analogRead(pin));
+ SLIPSerial.beginPacket();msgOut.send(SLIPSerial); SLIPSerial.endPacket();
+ }
+ } //else without a pullup
+#endif
+ else {
+ //set the pinmode
+ // This fails on Arduino 1.04 on Leanardo, I added this to fix it: #define analogInputToDigitalPin(p) (p+18)
+
+ pinMode(analogInputToDigitalPin(pin), INPUT);
+ //setup the output address which should be /a/(pin)
+ char outputAddress[6];
+ strcpy(outputAddress, "/a");
+ strcat(outputAddress, numToOSCAddress(pin));
+ //do the analog read and send the results
+ {
+ OSCMessage msgOut(outputAddress); msgOut.add((int32_t)analogRead(pin));
+ SLIPSerial.beginPacket(); msgOut.send(SLIPSerial); SLIPSerial.endPacket();
+ }
+ }
+ }
+ }
+}
+#ifdef BOARD_HAS_TONE
+/**
+ * TONE
+ *
+ * square wave output "/tone"
+ *
+ * format:
+ * /tone/pin
+ *
+ * (digital value) (float value) = frequency in Hz
+ * (no value) disable tone
+ *
+ **/
+
+void routeTone(OSCMessage &msg, int addrOffset ){
+ //iterate through all the analog pins
+ for(byte pin = 0; pin < NUM_DIGITAL_PINS; pin++){
+ //match against the pin number strings
+ int pinMatched = msg.match(numToOSCAddress(pin), addrOffset);
+ if(pinMatched){
+ unsigned int frequency = 0;
+ //if it has an int, then it's an integers frequency in Hz
+ if (msg.isInt(0)){
+ frequency = msg.getInt(0);
+ } //otherwise it's a floating point frequency in Hz
+ else if(msg.isFloat(0)){
+ frequency = msg.getFloat(0);
+ }
+ else
+ noTone(pin);
+ if(frequency>0)
+ {
+ if(msg.isInt(1))
+ tone(pin, frequency, msg.getInt(1));
+ else
+ tone(pin, frequency);
+ }
+ }
+ }
+}
+#endif
+
+
+#ifdef BOARD_HAS_CAPACITANCE_SENSING
+#if defined(__MKL26Z64__)
+// teensy 3.0LC
+#define NTPINS 11
+const int cpins[NTPINS] = {22,23,19,18,17,16,15,0,1,3,4 };
+#elif defined(__MK66FX1M0__)
+// teensy 3.6
+#define NTPINS 12
+const int cpins[NTPINS] = {0,1,14,15,16,17,18,19,22,23,29,30 };
+#else
+//Teensy 3.1 3.2
+#define NTPINS 12
+const int cpins[NTPINS] = {22,23,19,18,17,16,15,0,1,25,32, 33 };
+#endif
+
+void routeTouch(OSCMessage &msg, int addrOffset )
+{
+ for(int i=0;i 0)? HIGH: LOW);
+ { OSCMessage msgOut("/s/l"); msgOut.add(i); SLIPSerial.beginPacket();msgOut.send(SLIPSerial); SLIPSerial.endPacket(); }
+ }
+ }
+}
+
+/**
+ * MAIN METHODS
+ *
+ * setup and loop, bundle receiving/sending, initial routing
+ */
+void setup() {
+ SLIPSerial.begin(9600); // set this as high as you can reliably run on your platform
+}
+
+
+//reads and routes the incoming messages
+void loop(){
+ OSCBundle bundleIN;
+ int size;
+ while(!SLIPSerial.endofPacket())
+ if ((size =SLIPSerial.available()) > 0)
+ {
+ while(size--)
+ bundleIN.fill(SLIPSerial.read());
+ }
+
+ if(!bundleIN.hasError())
+ {
+ bundleIN.route("/s", routeSystem);
+ bundleIN.route("/a", routeAnalog);
+ bundleIN.route("/d", routeDigital);
+#ifdef BOARD_HAS_TONE
+ bundleIN.route("/tone", routeTone);
+#endif
+#ifdef BOARD_HAS_CAPACITANCE_SENSING
+ bundleIN.route("/c", routeTouch);
+#endif
+ }
+}
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/lib/OSC/examples/SerialReceive/SerialReceive.ino b/lib/OSC/examples/SerialReceive/SerialReceive.ino
new file mode 100644
index 0000000..4d96445
--- /dev/null
+++ b/lib/OSC/examples/SerialReceive/SerialReceive.ino
@@ -0,0 +1,66 @@
+/*
+* Set the LED according to incoming OSC control
+*/
+#include
+#include
+
+#include
+
+#ifdef BOARD_HAS_USB_SERIAL
+SLIPEncodedUSBSerial SLIPSerial( thisBoardsSerialUSB );
+#else
+ SLIPEncodedSerial SLIPSerial(Serial); // Change to Serial1 or Serial2 etc. for boards with multiple serial ports that don’t have Serial
+#endif
+
+
+void LEDcontrol(OSCMessage &msg)
+{
+ if (msg.isInt(0))
+ {
+ pinMode(LED_BUILTIN, OUTPUT);
+ digitalWrite(LED_BUILTIN, (msg.getInt(0) > 0)? HIGH: LOW);
+ }
+ else if(msg.isString(0))
+ {
+ int length=msg.getDataLength(0);
+ if(length<5)
+ {
+ char str[length];
+ msg.getString(0,str,length);
+ if((strcmp("on", str)==0)|| (strcmp("On",str)==0))
+ {
+ pinMode(LED_BUILTIN, OUTPUT);
+ digitalWrite(LED_BUILTIN, HIGH);
+ }
+ else if((strcmp("Of", str)==0)|| (strcmp("off",str)==0))
+ {
+ pinMode(LED_BUILTIN, OUTPUT);
+ digitalWrite(LED_BUILTIN, LOW);
+ }
+ }
+ }
+
+}
+
+
+void setup() {
+ SLIPSerial.begin(9600); // set this as high as you can reliably run on your platform
+}
+//reads and dispatches the incoming message
+void loop(){
+ OSCBundle bundleIN;
+ int size;
+
+ while(!SLIPSerial.endofPacket())
+ if( (size =SLIPSerial.available()) > 0)
+ {
+ while(size--)
+ bundleIN.fill(SLIPSerial.read());
+ }
+
+ if(!bundleIN.hasError())
+ bundleIN.dispatch("/led", LEDcontrol);
+
+}
+
+
diff --git a/lib/OSC/examples/SerialReceiveInfiniteLoop/SerialReceiveInfiniteLoop.ino b/lib/OSC/examples/SerialReceiveInfiniteLoop/SerialReceiveInfiniteLoop.ino
new file mode 100644
index 0000000..bef9323
--- /dev/null
+++ b/lib/OSC/examples/SerialReceiveInfiniteLoop/SerialReceiveInfiniteLoop.ino
@@ -0,0 +1,77 @@
+/*
+* Blink the LED according to incoming OSC on/off rates in quasi-asynchronous way
+*/
+#include
+#include
+
+#include
+
+#ifdef BOARD_HAS_USB_SERIAL
+SLIPEncodedUSBSerial SLIPSerial( thisBoardsSerialUSB );
+#else
+ SLIPEncodedSerial SLIPSerial(Serial); // Change to Serial1 or Serial2 etc. for boards with multiple serial ports that don’t have Serial
+#endif
+
+
+constexpr unsigned long blinkInterval = 2500;
+unsigned long blinkNow;
+
+unsigned long blinkRateOn = 50;
+unsigned long blinkRateOff = 50;
+
+void LEDcontrol(OSCMessage& msg)
+{
+ if (msg.isInt(0)) {
+ blinkRateOn = msg.getInt(0);
+ }
+
+ if (msg.isInt(1)) {
+ blinkRateOff = msg.getInt(1);
+ }
+}
+
+void setup()
+{
+ Serial.begin(9600);
+
+ const unsigned long startNow = millis() + 5000;
+ while(!Serial && millis() < startNow);
+
+ SLIPSerial.begin(9600); // set this as high as you can reliably run on your platform
+
+ blinkNow = millis() + blinkInterval;
+}
+
+//reads and dispatches the incoming message
+void loop()
+{
+ OSCBundle bundleIN;
+ int size;
+
+ if (SLIPSerial.available())
+ while (!SLIPSerial.endofPacket())
+ while (SLIPSerial.available())
+ bundleIN.fill(SLIPSerial.read());
+
+ if (!bundleIN.hasError())
+ bundleIN.dispatch("/led", LEDcontrol);
+
+ if (millis() >= blinkNow) {
+ pinMode(LED_BUILTIN, OUTPUT);
+
+ Serial.print("Blinking at ");
+ Serial.print(blinkRateOn);
+ Serial.print("/");
+ Serial.print(blinkRateOff);
+ Serial.println();
+
+ for (auto i = 0; i <= 5; i ++) {
+ digitalWrite(LED_BUILTIN, HIGH);
+ delay(blinkRateOn);
+ digitalWrite(LED_BUILTIN, LOW);
+ delay(blinkRateOff);
+ }
+ // blinkNow = millis() + blinkInterval;
+ blinkNow = millis() + blinkInterval - 5 * (blinkRateOn + blinkRateOff);
+ }
+}
diff --git a/lib/OSC/examples/SerialReceivewithServo/SerialReceivewithServo.ino b/lib/OSC/examples/SerialReceivewithServo/SerialReceivewithServo.ino
new file mode 100644
index 0000000..c9849a2
--- /dev/null
+++ b/lib/OSC/examples/SerialReceivewithServo/SerialReceivewithServo.ino
@@ -0,0 +1,67 @@
+/*
+* Control a servo according to incoming OSC control
+*
+*/
+#include
+#include
+#include
+
+#include
+
+#ifdef BOARD_HAS_USB_SERIAL
+SLIPEncodedUSBSerial SLIPSerial( thisBoardsSerialUSB );
+#else
+ SLIPEncodedSerial SLIPSerial(Serial); // Change to Serial1 or Serial2 etc. for boards with multiple serial ports that don’t have Serial
+#endif
+
+
+Servo myservo;
+
+void servoControl(OSCMessage &msg)
+{
+ if (msg.isInt(0))
+ {
+ myservo.write(msg.getInt(0));
+ }
+#ifdef TEMPoraray
+ else if (msg.isFloat(0))
+ {
+ //test if that pin is a PWM
+ if (digitalPinHasPWM(LED_BUILTIN))
+ {
+ pinMode(LED_BUILTIN, OUTPUT);
+ analogWrite(LED_BUILTIN, (int)(msg.getFloat(0)*127.0f));
+ }
+ else
+ SoftPWMSet(LED_BUILTIN, (int)(msg.getFloat(0)*127.0f));
+ }
+#endif
+
+}
+
+void setup() {
+ SLIPSerial.begin(9600);
+
+ myservo.attach(13);
+ myservo.write(90);
+
+
+}
+//reads and dispatches the incoming message
+void loop(){
+ OSCBundle bundleIN;
+ int size;
+
+ while(!SLIPSerial.endofPacket())
+ if( (size =SLIPSerial.available()) > 0)
+ {
+ while(size--)
+ bundleIN.fill(SLIPSerial.read());
+ }
+
+ if(!bundleIN.hasError())
+ bundleIN.dispatch("/servo", servoControl);
+
+}
+
+
diff --git a/lib/OSC/examples/SerialSendBundle/SerialSendBundle.ino b/lib/OSC/examples/SerialSendBundle/SerialSendBundle.ino
new file mode 100644
index 0000000..5241697
--- /dev/null
+++ b/lib/OSC/examples/SerialSendBundle/SerialSendBundle.ino
@@ -0,0 +1,47 @@
+
+/*
+ Make an OSC bundle and send it over SLIP serial
+
+ OSCBundles allow OSCMessages to be grouped together to preserve the order and completeness of related messages.
+ They also allow for timetags to be carried to represent the presentation time of the messages.
+*/
+#include
+#include
+
+#ifdef BOARD_HAS_USB_SERIAL
+SLIPEncodedUSBSerial SLIPSerial( thisBoardsSerialUSB );
+#else
+ SLIPEncodedSerial SLIPSerial(Serial); // Change to Serial1 or Serial2 etc. for boards with multiple serial ports that don’t have Serial
+#endif
+
+
+void setup() {
+ //begin SLIPSerial just like Serial
+ SLIPSerial.begin(9600); // set this as high as you can reliably run on your platform
+
+
+}
+
+void loop(){
+ //declare the bundle
+ OSCBundle bndl;
+ //BOSCBundle's add' returns the OSCMessage so the message's 'add' can be composed together
+ bndl.add("/analog/0").add((int32_t)analogRead(0));
+ bndl.add("/analog/1").add((int32_t)analogRead(1));
+ bndl.add("/digital/5").add((digitalRead(5)==HIGH)?"HIGH":"LOW");
+
+
+ SLIPSerial.beginPacket();
+ bndl.send(SLIPSerial); // send the bytes to the SLIP stream
+ SLIPSerial.endPacket(); // mark the end of the OSC Packet
+ bndl.empty(); // empty the bundle to free room for a new one
+
+ bndl.add("/mouse/step").add((int32_t)analogRead(0)).add((int32_t)analogRead(1));
+ bndl.add("/units").add("pixels");
+ SLIPSerial.beginPacket();
+ bndl.send(SLIPSerial); // send the bytes to the SLIP stream
+ SLIPSerial.endPacket(); // mark the end of the OSC Packet
+ bndl.empty(); // empty the bundle to free room for a new one
+
+ delay(100);
+}
diff --git a/lib/OSC/examples/SerialSendBundleWithTimeTag/SerialSendBundleWithTimeTag.ino b/lib/OSC/examples/SerialSendBundleWithTimeTag/SerialSendBundleWithTimeTag.ino
new file mode 100644
index 0000000..3a62218
--- /dev/null
+++ b/lib/OSC/examples/SerialSendBundleWithTimeTag/SerialSendBundleWithTimeTag.ino
@@ -0,0 +1,47 @@
+
+/*
+ Make an OSC bundle and send it over SLIP serial
+
+ OSCBundles allow OSCMessages to be grouped together to preserve the order and completeness of related messages.
+ They also allow for timetags to be carried to represent the presentation time of the messages.
+*/
+#include
+#include
+#include
+#include
+
+#ifdef BOARD_HAS_USB_SERIAL
+SLIPEncodedUSBSerial SLIPSerial( thisBoardsSerialUSB );
+#else
+ SLIPEncodedSerial SLIPSerial(Serial); // Change to Serial1 or Serial2 etc. for boards with multiple serial ports that don’t have Serial
+#endif
+
+
+void setup() {
+ //begin SLIPSerial just like Serial
+ SLIPSerial.begin(9600); // set this as high as you can reliably run on your platform
+
+}
+
+void loop(){
+ //declare the bundle
+ OSCBundle bndl;
+ osctime_t timetag;
+
+ //OSCBundle's add' returns the OSCMessage so the message's 'add' can be composed together
+ bndl.add("/analog/0").add((int32_t)adcRead(0, &timetag));
+ bndl.add("/analog/0/time").add(timetag);
+
+ bndl.add("/analog/1").add((int32_t)adcRead(1, &timetag));
+ bndl.add("/analog/1/time").add(timetag);
+
+ bndl.add("/digital/5").add((digitalRead(5)==HIGH)?"HIGH":"LOW");
+
+ SLIPSerial.beginPacket();
+ bndl.setTimetag(oscTime());
+ bndl.send(SLIPSerial); // send the bytes to the SLIP stream
+ SLIPSerial.endPacket(); // mark the end of the OSC Packet
+ bndl.empty(); // empty the bundle to free room for a new one
+
+ delay(100);
+}
diff --git a/lib/OSC/examples/SerialSendMessage/SerialSendMessage.ino b/lib/OSC/examples/SerialSendMessage/SerialSendMessage.ino
new file mode 100644
index 0000000..4618804
--- /dev/null
+++ b/lib/OSC/examples/SerialSendMessage/SerialSendMessage.ino
@@ -0,0 +1,33 @@
+#include
+#include
+/*
+Make an OSC message and send it over serial
+ */
+
+#ifdef BOARD_HAS_USB_SERIAL
+#include
+SLIPEncodedUSBSerial SLIPSerial( thisBoardsSerialUSB );
+#else
+#include
+ SLIPEncodedSerial SLIPSerial(Serial); // Change to Serial1 or Serial2 etc. for boards with multiple serial ports that don’t have Serial
+#endif
+
+
+void setup() {
+ //begin SLIPSerial just like Serial
+ SLIPSerial.begin(9600); // set this as high as you can reliably run on your platform
+}
+
+
+void loop(){
+ //the message wants an OSC address as first argument
+ OSCMessage msg("/analog/0");
+ msg.add((int32_t)analogRead(0));
+
+ SLIPSerial.beginPacket();
+ msg.send(SLIPSerial); // send the bytes to the SLIP stream
+ SLIPSerial.endPacket(); // mark the end of the OSC Packet
+ msg.empty(); // free space occupied by message
+
+ delay(20);
+}
diff --git a/lib/OSC/examples/SerialSendMessageInfiniteLoop/SerialSendMessageInfiniteLoop.ino b/lib/OSC/examples/SerialSendMessageInfiniteLoop/SerialSendMessageInfiniteLoop.ino
new file mode 100644
index 0000000..0ac18e0
--- /dev/null
+++ b/lib/OSC/examples/SerialSendMessageInfiniteLoop/SerialSendMessageInfiniteLoop.ino
@@ -0,0 +1,44 @@
+/*
+* Make an OSC message for controlling a remote LED blinking rates.
+*/
+
+#include
+#include
+
+#ifdef BOARD_HAS_USB_SERIAL
+#include
+SLIPEncodedUSBSerial SLIPSerial(thisBoardsSerialUSB);
+#else
+#include
+SLIPEncodedSerial SLIPSerial(Serial1); // Change to Serial1 or Serial2 etc. for boards with multiple serial ports that don’t have Serial
+#endif
+
+constexpr auto blinkRatesSize = 8;
+int blinkRates[blinkRatesSize] = { 25, 50, 100, 125, 150, 175, 200, 225 };
+
+void setup()
+{
+ //begin SLIPSerial just like Serial
+ SLIPSerial.begin(9600); // set this as high as you can reliably run on your platform
+}
+
+void loop()
+{
+ //the message wants an OSC address as first argument
+ OSCMessage msg("/led");
+
+ auto i = rand() % (blinkRatesSize - 1);
+ auto blinkRateOn = blinkRates[i];
+
+ auto j = rand() % (blinkRatesSize - 1);
+ auto blinkRateOff = blinkRates[j];
+
+ msg.add(blinkRateOn).add(blinkRateOff);
+
+ SLIPSerial.beginPacket();
+ msg.send(SLIPSerial); // send the bytes to the SLIP stream
+ SLIPSerial.endPacket(); // mark the end of the OSC Packet
+ msg.empty(); // free space occupied by message
+
+ delay(20);
+}
diff --git a/lib/OSC/examples/UDPCallResponse/UDPCallResponse.ino b/lib/OSC/examples/UDPCallResponse/UDPCallResponse.ino
new file mode 100644
index 0000000..bc7f7b5
--- /dev/null
+++ b/lib/OSC/examples/UDPCallResponse/UDPCallResponse.ino
@@ -0,0 +1,164 @@
+/*
+UDP Call Response
+
+Send responses to calls for information from a remote host
+*/
+
+#include
+#include
+#include
+#include
+#include
+
+//UDP communication
+EthernetUDP Udp;
+
+//the Arduino's IP
+IPAddress ip(128, 32, 122, 252);
+
+//port numbers
+const unsigned int inPort = 8888;
+const unsigned int outPort = 9999;
+
+
+//everything on the network needs a unique MAC
+#if defined(__MK20DX128__)
+// Teensy 3 has MAC burned in
+static byte mac[6];
+void read(uint8_t word, uint8_t *mac, uint8_t offset) {
+ FTFL_FCCOB0 = 0x41; // Selects the READONCE command
+ FTFL_FCCOB1 = word; // read the given word of read once area
+
+ // launch command and wait until complete
+ FTFL_FSTAT = FTFL_FSTAT_CCIF;
+ while(!(FTFL_FSTAT & FTFL_FSTAT_CCIF));
+
+ *(mac+offset) = FTFL_FCCOB5; // collect only the top three bytes,
+ *(mac+offset+1) = FTFL_FCCOB6; // in the right orientation (big endian).
+ *(mac+offset+2) = FTFL_FCCOB7; // Skip FTFL_FCCOB4 as it's always 0.
+}
+void read_mac() {
+ read(0xe,mac,0);
+ read(0xf,mac,3);
+}
+#else
+void read_mac() {}
+ byte mac[] = {
+ 0xDE, 0xAD, 0xBE, 0xEF, 0xFE, 0xED }; // you can find this written on the board of some Arduino Ethernets or shields
+#endif
+
+//outgoing messages
+
+OSCBundle bundleOUT;
+
+//converts the pin to an osc address
+char * numToOSCAddress( int pin){
+ static char s[10];
+ int i = 9;
+
+ s[i--]= '\0';
+ do
+ {
+ s[i] = "0123456789"[pin % 10];
+ --i;
+ pin /= 10;
+ }
+ while(pin && i);
+ s[i] = '/';
+ return &s[i];
+}
+
+/**
+ * ANALOG
+ *
+ * called when the address matches "/a"
+ *
+ * format:
+ * /analog/(pin)
+ * /u = analogRead with pullup
+ *
+ **/
+
+void routeAnalog(OSCMessage &msg, int addrOffset ){
+ int pinMatched;
+ pinMatched = msg.match("/0", addrOffset);
+ if(pinMatched){
+ if (msg.fullMatch("/u", pinMatched+addrOffset)) pinMode(analogInputToDigitalPin(0), INPUT_PULLUP); //set the pullup
+ //do the analog read and send the results
+ bundleOUT.add("/analog/0").add((int32_t)analogRead(0));
+ }
+ pinMatched = msg.match("/1", addrOffset);
+ if(pinMatched){
+ if (msg.fullMatch("/u", pinMatched+addrOffset)) pinMode(analogInputToDigitalPin(1), INPUT_PULLUP); //set the pullup
+ //do the analog read and send the results
+ bundleOUT.add("/analog/1").add((int32_t)analogRead(1));
+ }
+ pinMatched = msg.match("/2", addrOffset);
+ if(pinMatched){
+ if (msg.fullMatch("/u", pinMatched+addrOffset)) pinMode(analogInputToDigitalPin(2), INPUT_PULLUP); //set the pullup
+ //do the analog read and send the results
+ bundleOUT.add("/analog/2").add((int32_t)analogRead(2));
+ }
+ pinMatched = msg.match("/3", addrOffset);
+ if(pinMatched){
+ if (msg.fullMatch("/u", pinMatched+addrOffset)) pinMode(analogInputToDigitalPin(3), INPUT_PULLUP); //set the pullup
+ //do the analog read and send the results
+ bundleOUT.add("/analog/3").add((int32_t)analogRead(3));
+ }
+ pinMatched = msg.match("/4", addrOffset);
+ if(pinMatched){
+ if (msg.fullMatch("/u", pinMatched+addrOffset)) pinMode(analogInputToDigitalPin(4), INPUT_PULLUP); //set the pullup
+ //do the analog read and send the results
+ bundleOUT.add("/analog/4").add((int32_t)analogRead(4));
+ }
+ pinMatched = msg.match("/5", addrOffset);
+ if(pinMatched){
+ if (msg.fullMatch("/u", pinMatched+addrOffset)) pinMode(analogInputToDigitalPin(5), INPUT_PULLUP); //set the pullup
+ //do the analog read and send the results
+ bundleOUT.add("/analog/5").add((int32_t)analogRead(5));
+ }
+}
+
+/**
+ * MAIN METHODS
+ *
+ * setup and loop, bundle receiving/sending, initial routing
+ */
+void setup() {
+ //setup ethernet part
+ read_mac();
+ Ethernet.begin(mac,ip);
+ Udp.begin(inPort);
+
+}
+
+//reads and routes the incoming messages
+void loop(){
+ OSCBundle bundleIN;
+ int size;
+
+ if( (size = Udp.parsePacket())>0)
+ {
+// unsigned int outPort = Udp.remotePort();
+
+ while(size--)
+ bundleIN.fill(Udp.read());
+
+ if(!bundleIN.hasError())
+ bundleIN.route("/analog", routeAnalog);
+
+ // send the response bundle back to where the request came from
+ Udp.beginPacket(Udp.remoteIP(), outPort);
+ bundleOUT.send(Udp);
+ Udp.endPacket();
+ bundleOUT.empty(); // empty the bundle ready to use for new messages
+ }
+}
+
+
+
+
+
+
+
+
diff --git a/lib/OSC/examples/UDPEcho/UDPEcho.ino b/lib/OSC/examples/UDPEcho/UDPEcho.ino
new file mode 100644
index 0000000..3cfb0ee
--- /dev/null
+++ b/lib/OSC/examples/UDPEcho/UDPEcho.ino
@@ -0,0 +1,84 @@
+/*
+
+Leverage the UDP source IP and port calls to
+return OSC information back
+
+This example can be extended to build routers and forwarders of OSC packets
+
+ */
+#include
+#include
+#include
+#include
+
+EthernetUDP Udp;
+
+//the Arduino's IP
+IPAddress ip(128, 32, 122, 252);
+
+//port numbers
+const unsigned int inPort = 8888;
+const unsigned int outPort = 9999;
+
+//everything on the network needs a unique MAC
+#if defined(__MK20DX128__) || defined(__MK20DX256__) || defined(__MKL26Z64__)
+// Teensy 3.x has MAC burned in
+static byte mac[6];
+void read(uint8_t word, uint8_t *mac, uint8_t offset) {
+ Â FTFL_FCCOB0 = 0x41; Â Â Â Â Â Â // Selects the READONCE command
+ Â FTFL_FCCOB1 = word; Â Â Â Â Â Â // read the given word of read once area
+
+ Â // launch command and wait until complete
+ Â FTFL_FSTAT = FTFL_FSTAT_CCIF;
+ Â while(!(FTFL_FSTAT & FTFL_FSTAT_CCIF));
+
+ Â *(mac+offset) = Â FTFL_FCCOB5; Â Â Â // collect only the top three bytes,
+ Â *(mac+offset+1) = FTFL_FCCOB6; Â Â Â // in the right orientation (big endian).
+ Â *(mac+offset+2) = FTFL_FCCOB7; Â Â Â // Skip FTFL_FCCOB4 as it's always 0.
+}
+void read_mac() {
+ Â read(0xe,mac,0);
+ Â read(0xf,mac,3);
+}
+#else
+void read_mac() {}
+ byte mac[] = {
+ 0xDE, 0xAD, 0xBE, 0xEF, 0xFE, 0xED }; // you can find this written on the board of some Arduino Ethernets or shields
+#endif
+
+void setup() {
+ Ethernet.begin(mac,ip);
+ Udp.begin(inPort);
+}
+
+void loop(){
+ OSCBundle bndl;
+ int size;
+
+ //receive a bundle
+ if( (size = Udp.parsePacket())>0)
+ {
+// unsigned int outPort = Udp.remotePort();
+
+ while(size--)
+ bndl.fill(Udp.read());
+
+ if(!bndl.hasError())
+ {
+ //and echo it back
+ if(bndl.size() > 0)
+ {
+ static int32_t sequencenumber=0;
+
+ // we can sneak an addition onto the end of the bundle
+ bndl.add("/micros").add((int32_t)micros()); // (int32_t) is the type of OSC Integers
+ bndl.add("/sequencenumber").add(sequencenumber++);
+
+ Udp.beginPacket(Udp.remoteIP(), outPort);
+ bndl.send(Udp);
+ Udp.endPacket();
+ }
+ }
+ }
+}
+
diff --git a/lib/OSC/examples/UDPOscuino/UDPOscuino.ino b/lib/OSC/examples/UDPOscuino/UDPOscuino.ino
new file mode 100644
index 0000000..9fdafea
--- /dev/null
+++ b/lib/OSC/examples/UDPOscuino/UDPOscuino.ino
@@ -0,0 +1,378 @@
+
+// UDP OSCuino
+// system, analog and digital pin control and monitoring for Arduino
+// Yotam Mann and Adrian Freed
+
+
+#include
+#include
+#include
+#include
+#include
+
+EthernetUDP Udp;
+
+//the Arduino's IP
+IPAddress ip(128, 32, 122, 252);
+
+//port numbers
+const unsigned int inPort = 8888;
+const unsigned int outPort = 9999;
+
+//everything on the network needs a unique MAC
+#if defined(__MK20DX128__) || defined(__MK20DX256__) || defined(__MKL26Z64__) || defined(__MK66FX1M0__)
+// Teensy 3 has MAC burned in
+static byte mac[6];
+void read(uint8_t word, uint8_t *mac, uint8_t offset) {
+ FTFL_FCCOB0 = 0x41; // Selects the READONCE command
+ FTFL_FCCOB1 = word; // read the given word of read once area
+
+ // launch command and wait until complete
+ FTFL_FSTAT = FTFL_FSTAT_CCIF;
+ while(!(FTFL_FSTAT & FTFL_FSTAT_CCIF));
+
+ *(mac+offset) = FTFL_FCCOB5; // collect only the top three bytes,
+ *(mac+offset+1) = FTFL_FCCOB6; // in the right orientation (big endian).
+ *(mac+offset+2) = FTFL_FCCOB7; // Skip FTFL_FCCOB4 as it's always 0.
+}
+void read_mac() {
+ read(0xe,mac,0);
+ read(0xf,mac,3);
+}
+#else
+void read_mac() {}
+ byte mac[] = {
+ 0xDE, 0xAD, 0xBE, 0xEF, 0xFE, 0xED }; // you can find this written on the board of some Arduino Ethernets or shields
+#endif
+
+
+//outgoing messages
+
+OSCBundle bundleOUT;
+
+//converts the pin to an osc address
+char * numToOSCAddress( int pin){
+ static char s[10];
+ int i = 9;
+
+ s[i--]= '\0';
+ do
+ {
+ s[i] = "0123456789"[pin % 10];
+ --i;
+ pin /= 10;
+ }
+ while(pin && i);
+ s[i] = '/';
+ return &s[i];
+}
+
+/**
+ * ROUTES
+ *
+ * these are where the routing functions go
+ *
+ */
+
+/**
+ * DIGITAL
+ *
+ * called when address matched "/d"
+ * expected format:
+ * /d/(pin)
+ * /u = digitalRead with pullup
+ * (no value) = digitalRead without pullup
+ * (value) = digital write on that pin
+ *
+ */
+
+void routeDigital(OSCMessage &msg, int addrOffset ){
+ //match input or output
+ for(byte pin = 0; pin < NUM_DIGITAL_PINS; pin++){
+ //match against the pin number strings
+ int pinMatched = msg.match(numToOSCAddress(pin), addrOffset);
+ if(pinMatched){
+ //if it has an int, then it's a digital write
+ if (msg.isInt(0)){
+ pinMode(pin, OUTPUT);
+ digitalWrite(pin, (msg.getInt(0)>0) ? HIGH:LOW);
+ } //otherwise it's an analog read
+ else if(msg.isFloat(0)){
+ analogWrite(pin, (int)(msg.getFloat(0)*255.0f));
+ }
+
+
+ //otherwise it's an digital read
+ //with a pullup?
+ else if (msg.fullMatch("/u", pinMatched+addrOffset)){
+ //set the pullup
+ pinMode(pin, INPUT_PULLUP);
+ //setup the output address which should be /d/(pin)/u
+ char outputAddress[9];
+ strcpy(outputAddress, "/d");
+ strcat(outputAddress, numToOSCAddress(pin));
+ strcat(outputAddress,"/u");
+ //do the digital read and send the results
+ bundleOUT.add(outputAddress).add(digitalRead(pin));
+ } //else without a pullup
+ else {
+ //set the pinmode
+ pinMode(pin, INPUT);
+ //setup the output address which should be /d/(pin)
+ char outputAddress[6];
+ strcpy(outputAddress, "/d");
+ strcat(outputAddress, numToOSCAddress(pin));
+ //do the digital read and send the results
+ bundleOUT.add(outputAddress).add(digitalRead(pin));
+ }
+ }
+ }
+}
+
+/**
+ * ANALOG
+ *
+ * called when the address matches "/a"
+ *
+ * format:
+ * /a/(pin)
+ * /u = analogRead with pullup
+ * (no value) = analogRead without pullup
+ * (digital value) = digital write on that pin
+ * (float value) = analogWrite on that pin
+ *
+ **/
+
+void routeAnalog(OSCMessage &msg, int addrOffset ){
+ //iterate through all the analog pins
+ for(byte pin = 0; pin < NUM_ANALOG_INPUTS; pin++){
+ //match against the pin number strings
+ int pinMatched = msg.match(numToOSCAddress(pin), addrOffset);
+ if(pinMatched){
+ //if it has an int, then it's a digital write
+ if (msg.isInt(0)){
+ pinMode(analogInputToDigitalPin(pin), OUTPUT);
+ digitalWrite(analogInputToDigitalPin(pin), (msg.getInt(0) > 0)? HIGH: LOW);
+ } //otherwise it's an analog read
+ else if(msg.isFloat(0)){
+ analogWrite(pin, (int)(msg.getFloat(0)*255.0f));
+ }
+#ifdef BOARD_HAS_ANALOG_PULLUP
+ //with a pullup?
+ else if (msg.fullMatch("/u", pinMatched+addrOffset)){
+ //set the pullup
+
+ pinMode(analogInputToDigitalPin(pin), INPUT_PULLUP);
+
+ //setup the output address which should be /a/(pin)/u
+ char outputAddress[9];
+ strcpy(outputAddress, "/a");
+ strcat(outputAddress, numToOSCAddress(pin));
+ strcat(outputAddress,"/u");
+ strcat(outputAddress,"/u");
+ //do the analog read and send the results
+ bundleOUT.add(outputAddress).add((int32_t)analogRead(pin));
+ } //else without a pullup
+#endif
+ else {
+ //set the pinmode
+
+ pinMode(analogInputToDigitalPin(pin), INPUT);
+ //setup the output address which should be /a/(pin)
+ char outputAddress[6];
+ strcpy(outputAddress, "/a");
+ strcat(outputAddress, numToOSCAddress(pin));
+ //do the analog read and send the results
+ bundleOUT.add(outputAddress).add((int32_t)analogRead(pin));
+ }
+ }
+ }
+}
+
+#ifdef BOARD_HAS_TONE
+
+/**
+ * TONE
+ *
+ * square wave output "/tone"
+ *
+ * format:
+ * /tone/pin
+ *
+ * (digital value) (float value) = frequency in Hz
+ * (no value) disable tone
+ *
+ **/
+
+void routeTone(OSCMessage &msg, int addrOffset ){
+ //iterate through all the analog pins
+ for(byte pin = 0; pin < NUM_DIGITAL_PINS; pin++){
+ //match against the pin number strings
+ int pinMatched = msg.match(numToOSCAddress(pin), addrOffset);
+ if(pinMatched){
+ unsigned int frequency = 0;
+ //if it has an int, then it's an integers frequency in Hz
+ if (msg.isInt(0)){
+ frequency = msg.getInt(0);
+ } //otherwise it's a floating point frequency in Hz
+ else if(msg.isFloat(0)){
+ frequency = msg.getFloat(0);
+ }
+ else
+ noTone(pin);
+ if(frequency>0)
+ {
+ if(msg.isInt(1))
+ tone(pin, frequency, msg.getInt(1));
+ else
+ tone(pin, frequency);
+ }
+ }
+ }
+}
+
+#endif
+
+#ifdef BOARD_HAS_CAPACITANCE_SENSING
+
+#if defined(__MKL26Z64__)
+// teensy 3.0LC
+#define NTPINS 11
+const int cpins[NTPINS] = {22,23,19,18,17,16,15,0,1,3,4 };
+#elif defined(__MK66FX1M0__)
+// teensy 3.6
+#define NTPINS 12
+const int cpins[NTPINS] = {0,1,14,15,16,17,18,19,22,23,29,30 };
+#else
+//Teensy 3.1 3.2
+#define NTPINS 12
+const int cpins[NTPINS] = {22,23,19,18,17,16,15,0,1,25,32, 33 };
+#endif
+
+void routeTouch(OSCMessage &msg, int addrOffset )
+{
+ for(int i=0;i 0)? HIGH: LOW);
+ bundleOUT.add("/s/l").add(i);
+ }
+ }
+#endif
+}
+
+/**
+ * MAIN METHODS
+ *
+ * setup and loop, bundle receiving/sending, initial routing
+ */
+void setup() {
+ //setup ethernet port
+ read_mac();
+ Ethernet.begin(mac,ip);
+ Udp.begin(inPort);
+
+}
+
+//reads and routes the incoming messages
+void loop(){
+ OSCBundle bundleIN;
+ int size;
+
+ if( (size = Udp.parsePacket())>0)
+ {
+// unsigned int outPort = Udp.remotePort();
+
+ while(size--)
+ bundleIN.fill(Udp.read());
+
+ if(!bundleIN.hasError())
+ {
+ bundleIN.route("/s", routeSystem);
+ bundleIN.route("/a", routeAnalog);
+ bundleIN.route("/d", routeDigital);
+#ifdef BOARD_HAS_TONE
+ bundleIN.route("/tone", routeTone);
+#endif
+
+#ifdef TOUCHSUPPORT
+ bundleIN.route("/c", routeTouch);
+#endif
+
+ }
+ // send the response bundle back to where the request came from
+ Udp.beginPacket(Udp.remoteIP(),outPort);
+ bundleOUT.send(Udp);
+ Udp.endPacket();
+ bundleOUT.empty(); // empty the bundle ready to use for new messages
+ }
+}
+
+
+
+
+
+
+
+
diff --git a/lib/OSC/examples/UDPReceive/UDPReceive.ino b/lib/OSC/examples/UDPReceive/UDPReceive.ino
new file mode 100644
index 0000000..060db8b
--- /dev/null
+++ b/lib/OSC/examples/UDPReceive/UDPReceive.ino
@@ -0,0 +1,106 @@
+
+#include
+#include
+#include
+
+#include
+#include
+
+/*
+* UDPReceiveOSC
+* Set a tone according to incoming OSC control
+* Adrian Freed
+*/
+
+//UDP communication
+
+
+EthernetUDP Udp;
+byte mac[] = {
+ 0xDE, 0xAD, 0xBE, 0xEF, 0xFE, 0xED }; // you can find this written on the board of some Arduino Ethernets or shields
+
+//the Arduino's IP
+IPAddress ip(128, 32, 122, 252);
+
+//port numbers
+const unsigned int inPort = 8888;
+
+//converts the pin to an osc address
+char * numToOSCAddress( int pin){
+ static char s[10];
+ int i = 9;
+
+ s[i--]= '\0';
+ do
+ {
+ s[i] = "0123456789"[pin % 10];
+ --i;
+ pin /= 10;
+ }
+ while(pin && i);
+ s[i] = '/';
+ return &s[i];
+}
+
+/**
+ * TONE
+ *
+ * square wave output "/tone"
+ *
+ * format:
+ * /tone/pin
+ *
+ * (digital value) (float value) = frequency in Hz
+ * (no value) disable tone
+ *
+ **/
+
+void routeTone(OSCMessage &msg, int addrOffset ){
+ //iterate through all the analog pins
+ for(byte pin = 0; pin < NUM_DIGITAL_PINS; pin++){
+ //match against the pin number strings
+ int pinMatched = msg.match(numToOSCAddress(pin), addrOffset);
+ if(pinMatched){
+ unsigned int frequency = 0;
+ //if it has an int, then it's an integers frequency in Hz
+ if (msg.isInt(0)){
+ frequency = msg.getInt(0);
+ } //otherwise it's a floating point frequency in Hz
+ else if(msg.isFloat(0)){
+ frequency = msg.getFloat(0);
+ }
+ else
+ noTone(pin);
+ if(frequency>0)
+ {
+ if(msg.isInt(1))
+ tone(pin, frequency, msg.getInt(1));
+ else
+ tone(pin, frequency);
+ }
+ }
+ }
+}
+
+void setup() {
+ //setup ethernet part
+ Ethernet.begin(mac,ip);
+ Udp.begin(inPort);
+
+}
+//reads and dispatches the incoming message
+void loop(){
+ OSCBundle bundleIN;
+ int size;
+
+ if( (size = Udp.parsePacket())>0)
+ {
+ while(size--)
+ bundleIN.fill(Udp.read());
+
+ if(!bundleIN.hasError())
+ bundleIN.route("/tone", routeTone);
+ }
+}
+
+
diff --git a/lib/OSC/examples/UDPSendBundle/UDPSendBundle.ino b/lib/OSC/examples/UDPSendBundle/UDPSendBundle.ino
new file mode 100644
index 0000000..fec9de9
--- /dev/null
+++ b/lib/OSC/examples/UDPSendBundle/UDPSendBundle.ino
@@ -0,0 +1,55 @@
+
+/*
+Make an OSC bundle and send it over UDP
+
+OSCBundles allow OSCMessages to be grouped together
+to preserve the order and completeness of related messages.
+They also allow for timetags to be carried to represent the presentation time
+of the messages.
+ */
+#include
+#include
+#include
+#include
+
+EthernetUDP Udp;
+
+//the Arduino's IP
+IPAddress ip(128, 32, 122, 252);
+//destination IP
+IPAddress outIp(128, 32, 122, 125);
+const unsigned int outPort = 9999;
+
+ byte mac[] = {
+ 0xDE, 0xAD, 0xBE, 0xEF, 0xFE, 0xED }; // you can find this written on the board of some Arduino Ethernets or shields
+void setup() {
+ Ethernet.begin(mac,ip);
+ Udp.begin(8888);
+}
+
+
+
+void loop(){
+ //declare the bundle
+ OSCBundle bndl;
+
+ //BOSCBundle's add' returns the OSCMessage so the message's 'add' can be composed together
+ bndl.add("/analog/0").add((int32_t)analogRead(0));
+ bndl.add("/analog/1").add((int32_t)analogRead(1));
+ bndl.add("/digital/5").add((digitalRead(5)==HIGH)?"HIGH":"LOW");
+
+ Udp.beginPacket(outIp, outPort);
+ bndl.send(Udp); // send the bytes to the SLIP stream
+ Udp.endPacket(); // mark the end of the OSC Packet
+ bndl.empty(); // empty the bundle to free room for a new one
+
+ bndl.add("/mouse/step").add((int32_t)analogRead(0)).add((int32_t)analogRead(1));
+ bndl.add("/units").add("pixels");
+
+ Udp.beginPacket(outIp, outPort);
+ bndl.send(Udp); // send the bytes to the SLIP stream
+ Udp.endPacket(); // mark the end of the OSC Packet
+ bndl.empty(); // empty the bundle to free room for a new one
+
+ delay(1000);
+}
diff --git a/lib/OSC/examples/UDPSendBundlewithTimeTag/UDPSendBundlewithTimeTag.ino b/lib/OSC/examples/UDPSendBundlewithTimeTag/UDPSendBundlewithTimeTag.ino
new file mode 100644
index 0000000..c12b19e
--- /dev/null
+++ b/lib/OSC/examples/UDPSendBundlewithTimeTag/UDPSendBundlewithTimeTag.ino
@@ -0,0 +1,62 @@
+
+/*
+Make an OSC bundle and send it over UDP
+
+OSCBundles allow OSCMessages to be grouped together
+to preserve the order and completeness of related messages.
+They also allow for timetags to be carried to represent the presentation time
+of the messages.
+ */
+#include
+#include
+#include
+#include
+#include
+
+
+EthernetUDP Udp;
+
+//the Arduino's IP
+IPAddress ip(128, 32, 122, 26);
+//destination IP
+IPAddress outIp(128, 32, 122, 25);
+const unsigned int outPort = 9999;
+
+ byte mac[] = {
+ 0xDE, 0xAD, 0xBE, 0xEF, 0xFE, 0xED }; // you can find this written on the board of some Arduino Ethernets or shields
+void setup() {
+ Ethernet.begin(mac,ip);
+ Udp.begin(8888);
+}
+
+
+
+void loop(){
+ //declare the bundle
+ OSCBundle bndl;
+ osctime_t timetag;
+
+ //OSCBundle's add' returns the OSCMessage so the message's 'add' can be composed together
+ bndl.add("/analog/0").add((int32_t)adcRead(0, &timetag));
+ bndl.add("/analog/0/time").add(timetag);
+
+ bndl.add("/analog/1").add((int32_t)adcRead(1, &timetag));
+ bndl.add("/analog/1/time").add(timetag);
+
+ Udp.beginPacket(outIp, outPort);
+ bndl.setTimetag(oscTime());
+ bndl.send(Udp); // send the bytes to the SLIP stream
+ Udp.endPacket(); // mark the end of the OSC Packet
+ bndl.empty(); // empty the bundle to free room for a new one
+
+ bndl.add("/mouse/step").add((int32_t)analogRead(0)).add((int32_t)analogRead(1));
+ bndl.add("/units").add("pixels");
+
+ Udp.beginPacket(outIp, outPort);
+ bndl.setTimetag(oscTime());
+ bndl.send(Udp); // send the bytes to the SLIP stream
+ Udp.endPacket(); // mark the end of the OSC Packet
+ bndl.empty(); // empty the bundle to free room for a new one
+
+ delay(100);
+}
diff --git a/lib/OSC/examples/UDPSendMessage/UDPSendMessage.ino b/lib/OSC/examples/UDPSendMessage/UDPSendMessage.ino
new file mode 100644
index 0000000..011dba1
--- /dev/null
+++ b/lib/OSC/examples/UDPSendMessage/UDPSendMessage.ino
@@ -0,0 +1,41 @@
+#include
+
+/*
+ Make an OSC message and send it over UDP
+
+ Adrian Freed
+ */
+#include
+#include
+#include
+#include
+
+EthernetUDP Udp;
+
+//the Arduino's IP
+IPAddress ip(128, 32, 122, 252);
+//destination IP
+IPAddress outIp(128, 32, 122, 125);
+const unsigned int outPort = 9999;
+
+ byte mac[] = {
+ 0xDE, 0xAD, 0xBE, 0xEF, 0xFE, 0xED }; // you can find this written on the board of some Arduino Ethernets or shields
+void setup() {
+ Ethernet.begin(mac,ip);
+ Udp.begin(8888);
+
+}
+
+
+void loop(){
+ //the message wants an OSC address as first argument
+ OSCMessage msg("/analog/0");
+ msg.add((int32_t)analogRead(0));
+
+ Udp.beginPacket(outIp, outPort);
+ msg.send(Udp); // send the bytes to the SLIP stream
+ Udp.endPacket(); // mark the end of the OSC Packet
+ msg.empty(); // free space occupied by message
+
+ delay(20);
+}
diff --git a/lib/OSC/keywords.txt b/lib/OSC/keywords.txt
new file mode 100644
index 0000000..7ad684b
--- /dev/null
+++ b/lib/OSC/keywords.txt
@@ -0,0 +1,91 @@
+getOSCMessage KEYWORD2
+fill KEYWORD2
+send KEYWORD2
+dispatch KEYWORD2
+route KEYWORD2
+setTimetag KEYWORD2
+getTimetag KEYWORD2
+hasError KEYWORD2
+add KEYWORD2
+set KEYWORD2
+match KEYWORD2
+fullMatch KEYWORD2
+getInt KEYWORD2
+getFloat KEYWORD2
+getBoolean KEYWORD2
+getTime KEYWORD2
+getDouble KEYWORD2
+getBlob KEYWORD2
+getString KEYWORD2
+getAddress KEYWORD2
+getDataLength KEYWORD2
+getBlobLength KEYWORD2
+getType KEYWORD2
+isInt KEYWORD2
+isFloat KEYWORD2
+isBlob KEYWORD2
+isString KEYWORD2
+isBoolean KEYWORD2
+isDouble KEYWORD2
+isTime KEYWORD2
+size KEYWORD2
+bytes KEYWORD2
+empty KEYWORD2
+OSCBundle KEYWORD1
+OSCMessage KEYWORD1
+OSCMatch KEYWORD1
+OSCData KEYWORD1
+endTransmission KEYWORD1
+endofTransmission KEYWORD1
+SLIPEncodedSerial KEYWORD3
+SLIPEncodedUSBSerial KEYWORD3
+SLIPEncodedSPISerial KEYWORD3
+oscTime KEYWORD1
+adcRead KEYWORD1
+capacitanceRead KEYWORD1
+inputRead KEYWORD1
+#######################################
+# Syntax Coloring Map SPI
+#######################################
+#######################################
+# Class
+#######################################
+StreamSPI0 KEYWORD3
+
+#######################################
+# Datatypes (KEYWORD1)
+#######################################
+
+SPI KEYWORD1
+StreamSPI KEYWORD1
+
+#######################################
+# Methods and Functions (KEYWORD2)
+#######################################
+begin KEYWORD2
+end KEYWORD2
+transfer KEYWORD2
+setBitOrder KEYWORD2
+setDataMode KEYWORD2
+setClockDivider KEYWORD2
+
+
+#######################################
+# Constants (LITERAL1)
+#######################################
+SPI_CLOCK_DIV4 LITERAL1
+SPI_CLOCK_DIV16 LITERAL1
+SPI_CLOCK_DIV64 LITERAL1
+SPI_CLOCK_DIV128 LITERAL1
+SPI_CLOCK_DIV2 LITERAL1
+SPI_CLOCK_DIV8 LITERAL1
+SPI_CLOCK_DIV32 LITERAL1
+SPI_CLOCK_DIV64 LITERAL1
+SPI_MODE0 LITERAL1
+SPI_MODE1 LITERAL1
+SPI_MODE2 LITERAL1
+SPI_MODE3 LITERAL1
+
+
+
+
diff --git a/lib/OSC/library.json b/lib/OSC/library.json
new file mode 100644
index 0000000..d5662fd
--- /dev/null
+++ b/lib/OSC/library.json
@@ -0,0 +1,25 @@
+{
+ "name": "OSC",
+ "version": "1.0.0",
+ "keywords": "sound, encoding, OSC",
+ "description": "Open Sound Control (OSC) is an open, transport-independent, message-based encidubg developed for communication among computers, sound synthesizers, and other multimedia devices.",
+ "authors": [
+ {
+ "name": "Adrian Freed",
+ "email": "adrian@adrianfreed.com",
+ "url": "http://www.adrianfreed.com"
+ },
+ {
+ "name": "Yotam Mann",
+ "url": "http://yotammann.info"
+ }
+ ],
+ "repository":
+ {
+ "type": "git",
+ "url": "https://github.com/CNMAT/OSC.git"
+ },
+ "frameworks": "arduino",
+ "platforms": "*"
+ ]
+}
diff --git a/lib/OSC/library.properties b/lib/OSC/library.properties
new file mode 100644
index 0000000..1c3a54e
--- /dev/null
+++ b/lib/OSC/library.properties
@@ -0,0 +1,9 @@
+name=OSC
+version=1.3.7
+author=Adrian Freed , Yotam Mann
+maintainer=Adrian Freed
+sentence=Open Sound Control (OSC)
+paragraph=Open Sound Control (OSC) is an open, transport-independent, message-based encoding developed for communication among computers, sound synthesizers, and other multimedia devices.
+category=Device Control
+url=https://github.com/CNMAT/OSC
+architectures=*
diff --git a/lib/OSC/test/OSCBundle_test/OSCBundle_test.ino b/lib/OSC/test/OSCBundle_test/OSCBundle_test.ino
new file mode 100644
index 0000000..81438c5
--- /dev/null
+++ b/lib/OSC/test/OSCBundle_test/OSCBundle_test.ino
@@ -0,0 +1,123 @@
+#include
+#include
+#include "TestPrint.h"
+
+#define HAS_DOUBLE sizeof(double) == 8
+
+test(bundle_address){
+ OSCBundle bundle;
+ bundle.add("/address").add(1);
+ assertEqual(bundle.size(), 1);
+ OSCMessage msg = bundle.getOSCMessage("/address");
+ assertTrue(msg.isInt(0));
+ assertEqual(msg.getInt(0), 1);
+}
+
+test(bundle_message_position){
+ OSCBundle bundle;
+ bundle.add("/one").add(1);
+ bundle.add("/two").add(2);
+ assertEqual(bundle.size(), 2);
+ OSCMessage msg0 = bundle.getOSCMessage(0);
+ assertTrue(msg0.isInt(0));
+ assertEqual(msg0.getInt(0), 1);
+ OSCMessage msg1 = bundle.getOSCMessage(1);
+ assertTrue(msg1.isInt(0));
+ assertEqual(msg1.getInt(0), 2);
+}
+
+test(bundle_add_message){
+ OSCMessage msg("/msg");
+ OSCBundle bundle;
+ bundle.add(msg).add(1);
+ assertEqual(bundle.size(), 1);
+ OSCMessage test_msg = bundle.getOSCMessage(0);
+ assertTrue(test_msg.isInt(0));
+ assertEqual(test_msg.getInt(0), 1);
+}
+
+void routeA(OSCMessage & msg, int offset){
+ assertTrue(msg.isInt(0));
+ assertEqual(msg.getInt(0), 1);
+}
+
+void routeB(OSCMessage & msg, int offset){
+ assertTrue(msg.isInt(0));
+ assertEqual(msg.getInt(0), 2);
+}
+
+test(bundle_route){
+ OSCMessage msg("/msg");
+ OSCBundle bundle;
+ bundle.add("/a").add(1);
+ bundle.add("/b/1").add(2);
+ assertEqual(bundle.size(), 2);
+ assertTrue(bundle.route("/a", routeA));
+ assertTrue(bundle.route("/b", routeB));
+}
+
+void dispatchA(OSCMessage & msg){
+ assertTrue(msg.isInt(0));
+ assertEqual(msg.getInt(0), 1);
+}
+
+void dispatchB(OSCMessage & msg){
+ assertTrue(msg.isInt(0));
+ assertEqual(msg.getInt(0), 2);
+}
+
+test(bundle_dispatch){
+ OSCMessage msg("/msg");
+ OSCBundle bundle;
+ bundle.add("/a").add(1);
+ bundle.add("/b").add(2);
+ assertEqual(bundle.size(), 2);
+ assertTrue(bundle.route("/a", routeA));
+ assertTrue(bundle.route("/b", routeB));
+}
+
+test(bundle_encode){
+ TestPrint printer;
+ //this is the desired output
+ uint8_t testBuffer[] = {35, 98, 117, 110, 100, 108, 101, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 12, 47, 97, 0, 0, 44, 105, 0, 0, 0, 0, 0, 1, 0, 0, 0, 12, 47, 98, 0, 0, 44, 105, 0, 0, 0, 0, 0, 2};
+ OSCBundle bundle;
+ bundle.add("/a").add(1);
+ bundle.add("/b").add(2);
+ bundle.send(printer);
+ assertEqual(printer.size(), sizeof(testBuffer));
+ for (int i = 0; i < sizeof(testBuffer); i++){
+ assertEqual(testBuffer[i], printer.at(i));
+ }
+}
+
+test(bundle_decode){
+ uint8_t testBuffer[] = {35, 98, 117, 110, 100, 108, 101, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 12, 47, 97, 0, 0, 44, 105, 0, 0, 0, 0, 0, 1, 0, 0, 0, 12, 47, 98, 0, 0, 44, 105, 0, 0, 0, 0, 0, 2};
+ OSCBundle bundle;
+ bundle.fill(testBuffer, sizeof(testBuffer));
+ assertEqual(bundle.size(), 2);
+ OSCMessage msgA = bundle.getOSCMessage("/a");
+ assertTrue(msgA.isInt(0));
+ assertEqual(msgA.getInt(0), 1);
+ OSCMessage msgB = bundle.getOSCMessage("/b");
+ assertTrue(msgB.isInt(0));
+ assertEqual(msgB.getInt(0), 2);
+}
+
+test(bundle_decode_invalid){
+ uint8_t testBuffer[] = {35, 98, 117, 110, 100, 108, 101, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 12, 47, 97, 0, 0, 44, 105, 0, 0, 0, 0, 0, 1, 0, 0, 0, 12, 47, 98, 0, 0, 44, 105, 0, 0, 0, 0, 2};
+ OSCBundle bundle;
+ bundle.fill(testBuffer, sizeof(testBuffer));
+ assertTrue(bundle.hasError());
+}
+
+
+void setup()
+{
+ Serial.begin(9600);
+ while(!Serial); // for the Arduino Leonardo/Micro only
+}
+
+void loop()
+{
+ Test::run();
+}
diff --git a/lib/OSC/test/OSCBundle_test/TestPrint.h b/lib/OSC/test/OSCBundle_test/TestPrint.h
new file mode 100644
index 0000000..8caf749
--- /dev/null
+++ b/lib/OSC/test/OSCBundle_test/TestPrint.h
@@ -0,0 +1,36 @@
+
+/**
+ * A print class for testing the encoder
+ */
+class TestPrint : public Print {
+
+ private:
+ //a small test buffer
+ uint8_t buffer[64];
+
+ //pointer to the current write spot
+ int bufferPointer;
+
+ public:
+
+ TestPrint(){
+ bufferPointer = 0;
+ }
+
+ size_t write(uint8_t character) {
+ buffer[bufferPointer++] = character;
+ return character;
+ }
+
+ int size(){
+ return bufferPointer;
+ }
+
+ uint8_t at(int index){
+ return buffer[index];
+ }
+
+ void clear(){
+ bufferPointer = 0;
+ }
+};
diff --git a/lib/OSC/test/OSCData_test/OSCData_test.ino b/lib/OSC/test/OSCData_test/OSCData_test.ino
new file mode 100644
index 0000000..b07ae53
--- /dev/null
+++ b/lib/OSC/test/OSCData_test/OSCData_test.ino
@@ -0,0 +1,96 @@
+#include
+#include
+
+#define HAS_DOUBLE sizeof(double) == 8
+
+test(data_int){
+ int i = 1;
+ OSCData datum(i);
+ assertEqual(datum.getInt(), i);
+ assertEqual(datum.type, 'i');
+}
+
+test(data_float){
+ float f = 1.1;
+ OSCData datum(f);
+ assertEqual(datum.getFloat(), f);
+ assertEqual(datum.type, 'f');
+}
+
+test(data_string){
+ const char * testStr = "data";
+ int testStrLen = strlen(testStr) + 1;
+ OSCData datum(testStr);
+ char str[testStrLen];
+ datum.getString(str, testStrLen);
+ assertEqual(strcmp(str, testStr), 0);
+ assertEqual(datum.type, 's');
+}
+
+test(data_string_partial_copy){
+ const char * testStr = "data";
+ int testStrLen = strlen(testStr) + 1;
+ OSCData datum(testStr);
+ char str[testStrLen];
+ assertEqual(datum.getString(str, 2), 2);
+ assertEqual(strncmp(str, testStr, 2), 0);
+}
+
+test(data_bool){
+ bool f = false;
+ OSCData datum(f);
+ assertFalse(datum.getBoolean());
+}
+
+test(has_double){
+ assertEqual(sizeof(double), 8U);
+}
+
+test(data_double){
+ if (HAS_DOUBLE){
+ double d = 1.1;
+ OSCData datum = OSCData(d);
+ assertEqual(datum.getDouble(), d);
+ assertEqual(datum.type, 'd');
+ }
+}
+
+test(data_blob){
+ uint8_t b[] = {0, 1, 2, 3};
+ OSCData datum(b, 4);
+ uint8_t blob[4];
+ datum.getBlob(blob, 4);
+ for (int i = 0; i < 4; i++){
+ assertEqual(blob[i], b[i]);
+ }
+ assertEqual(datum.type, 'b');
+}
+
+test(data_blob_partial_copy){
+ uint8_t b[] = {0, 1, 2, 3};
+ OSCData datum(b, 4);
+ uint8_t blob[4];
+ assertEqual(datum.getBlob(blob, 2), 2);
+ for (int i = 0; i < 2; i++){
+ assertEqual(blob[i], b[i]);
+ }
+}
+
+test(data_copy){
+ OSCData datum = OSCData(1);
+ OSCData cpy(datum);
+ assertEqual(cpy.getInt(), 1);
+ assertEqual(cpy.type, 'i');
+}
+
+
+void setup()
+{
+ Serial.begin(9600);
+ while(!Serial); // for the Arduino Leonardo/Micro only
+}
+
+void loop()
+{
+ Test::run();
+}
diff --git a/lib/OSC/test/OSCMessage_encode_decode_test/OSCMessage_encode_decode_test.ino b/lib/OSC/test/OSCMessage_encode_decode_test/OSCMessage_encode_decode_test.ino
new file mode 100644
index 0000000..649deea
--- /dev/null
+++ b/lib/OSC/test/OSCMessage_encode_decode_test/OSCMessage_encode_decode_test.ino
@@ -0,0 +1,182 @@
+#include
+#include
+#include "TestPrint.h"
+
+#define HAS_DOUBLE sizeof(double) == 8
+
+test(message_encode_int){
+ TestPrint printer;
+ //this is the desired output
+ uint8_t testBuffer[] = {47, 102, 111, 111, 0, 0, 0, 0, 44, 105, 105, 105, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 2, 255, 255, 255, 236};
+ OSCMessage msg("/foo");
+ msg.add(1);
+ msg.add(2);
+ msg.add(-20);
+ msg.send(printer);
+ assertEqual(printer.size(), sizeof(testBuffer));
+ for (unsigned int i = 0; i < sizeof(testBuffer); i++){
+ assertEqual(testBuffer[i], printer.at(i));
+ }
+}
+
+test(message_encode_string){
+ TestPrint printer;
+ //this is the desired output
+ uint8_t testBuffer[] = {47, 116, 101, 115, 116, 0, 0, 0, 44, 115, 115, 0, 104, 105, 0, 0, 104, 111, 119, 100, 121, 0, 0, 0};
+ OSCMessage msg("/test");
+ msg.add("hi");
+ msg.add("howdy");
+ msg.send(printer);
+ assertEqual(printer.size(), sizeof(testBuffer));
+ for (unsigned int i = 0; i < sizeof(testBuffer); i++){
+ assertEqual(testBuffer[i], printer.at(i));
+ }
+}
+
+test(message_encode_float){
+ TestPrint printer;
+ //this is the desired output
+ uint8_t testBuffer[] = {47, 97, 100, 100, 114, 101, 115, 115, 0, 0, 0, 0, 44, 102, 102, 0, 63, 128, 0, 0, 192, 6, 102, 102};
+ OSCMessage msg("/address");
+ msg.add(1.0f);
+ msg.add(-2.1f);
+ msg.send(printer);
+ assertEqual(printer.size(), sizeof(testBuffer));
+ for (unsigned int i = 0; i < sizeof(testBuffer); i++){
+ assertEqual(testBuffer[i], printer.at(i));
+ }
+}
+
+test(message_encode_double){
+ if (HAS_DOUBLE){
+ TestPrint printer;
+ //this is the desired output
+ uint8_t testBuffer[] = {47, 97, 0, 0, 44, 100, 100, 0, 64, 89, 0, 0, 0, 0, 0, 0, 63, 80, 98, 77, 210, 241, 169, 252};
+ OSCMessage msg("/a");
+ double d0 = 100;
+ double d1 = 0.001;
+ msg.add(d0);
+ msg.add(d1);
+ msg.send(printer);
+ assertEqual(printer.size(), sizeof(testBuffer));
+ for (unsigned int i = 0; i < sizeof(testBuffer); i++){
+ assertEqual(testBuffer[i], printer.at(i));
+ }
+ }
+}
+
+test(message_encode_blob){
+ TestPrint printer;
+ //this is the desired output
+ uint8_t testBuffer[] = {47, 98, 0, 0, 44, 98, 0, 0, 0, 0, 0, 5, 1, 2, 3, 4, 5, 0, 0, 0};
+ OSCMessage msg("/b");
+ uint8_t blob[] = {1, 2, 3, 4, 5};
+ msg.add(blob, 5);
+ msg.send(printer);
+ assertEqual(printer.size(), sizeof(testBuffer));
+ for (unsigned int i = 0; i < sizeof(testBuffer); i++){
+ assertEqual(testBuffer[i], printer.at(i));
+ }
+}
+
+test(message_encode_mixed){
+ TestPrint printer;
+ //this is the desired output
+ uint8_t testBuffer[] = {47, 109, 105, 120, 101, 100, 0, 0, 44, 115, 105, 102, 0, 0, 0, 0, 111, 110, 101, 0, 0, 0, 0, 1, 63, 128, 0, 0};
+ OSCMessage msg("/mixed");
+ msg.add("one");
+ msg.add(1);
+ msg.add(1.0f);
+ msg.send(printer);
+ assertEqual(printer.size(), sizeof(testBuffer));
+ for (unsigned int i = 0; i < sizeof(testBuffer); i++){
+ assertEqual(testBuffer[i], printer.at(i));
+ }
+}
+
+test(message_decode_int){
+ uint8_t testBuffer[] = {47, 105, 110, 116, 115, 0, 0, 0, 44, 105, 105, 105, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 200, 255, 255, 255, 231};
+ OSCMessage msg;
+ msg.fill(testBuffer, sizeof(testBuffer));
+ assertEqual(msg.size(), 3);
+ assertTrue(msg.isInt(0));
+ assertTrue(msg.isInt(1));
+ assertTrue(msg.isInt(2));
+ assertEqual(msg.getInt(0), 1);
+ assertEqual(msg.getInt(1), 200);
+ assertEqual(msg.getInt(2), -25);
+}
+
+test(message_decode_float){
+ uint8_t testBuffer[] = {47, 102, 108, 111, 97, 116, 115, 0, 44, 102, 102, 0, 191, 128, 0, 0, 67, 72, 2, 143};
+ OSCMessage msg;
+ msg.fill(testBuffer, sizeof(testBuffer));
+ assertEqual(msg.size(), 2);
+ assertFalse(msg.isInt(0));
+ assertTrue(msg.isFloat(0));
+ assertTrue(msg.isFloat(1));
+ assertEqual(msg.getFloat(0), -1.0f);
+ assertEqual(msg.getFloat(1), 200.01f);
+}
+
+test(message_decode_double){
+ if (HAS_DOUBLE){
+ uint8_t testBuffer[] = {47, 100, 0, 0, 44, 100, 0, 0, 64, 36, 5, 30, 184, 81, 235, 133};
+ OSCMessage msg;
+ msg.fill(testBuffer, sizeof(testBuffer));
+ double d = 10.01;
+ assertEqual(msg.size(), 1);
+ assertTrue(msg.isDouble(0));
+ assertEqual(msg.getDouble(0), d);
+ }
+}
+
+test(message_decode_string){
+ uint8_t testBuffer[] = {47, 115, 116, 114, 105, 110, 103, 115, 0, 0, 0, 0, 44, 115, 115, 0, 104, 101, 121, 0, 104, 105, 0, 0};
+ OSCMessage msg;
+ msg.fill(testBuffer, sizeof(testBuffer));
+ assertEqual(msg.size(), 2);
+ assertTrue(msg.isString(0));
+ assertTrue(msg.isString(1));
+ char str[4];
+ msg.getString(0, str, 5);
+ assertEqual(strcmp(str, "hey"), 0);
+ msg.getString(1, str, 3);
+ assertEqual(strcmp(str, "hi"), 0);
+}
+
+test(message_decode_blob){
+ uint8_t testBuffer[] = {47, 98, 0, 0, 44, 98, 0, 0, 0, 0, 0, 4, 0, 1, 2, 3};
+ OSCMessage msg;
+ msg.fill(testBuffer, sizeof(testBuffer));
+ assertEqual(msg.size(), 1);
+ assertTrue(msg.isBlob(0));
+ uint8_t blob[4];
+ msg.getBlob(0, blob, 4);
+ for (int i = 0; i < 4; i++){
+ assertEqual(i, blob[i]);
+ }
+}
+
+test(message_decode_mixed){
+ uint8_t testBuffer[] = {47, 109, 105, 120, 101, 100, 0, 0, 44, 115, 105, 102, 0, 0, 0, 0, 111, 110, 101, 0, 0, 0, 0, 1, 63, 128, 0, 0};
+ OSCMessage msg;
+ msg.fill(testBuffer, sizeof(testBuffer));
+ assertEqual(msg.size(), 3);
+ assertTrue(msg.isString(0));
+ assertTrue(msg.isInt(1));
+ assertTrue(msg.isFloat(2));
+ assertEqual(msg.getInt(1), 1);
+ assertEqual(msg.getFloat(2), 1.0f);
+}
+
+void setup()
+{
+ Serial.begin(9600);
+ while(!Serial); // for the Arduino Leonardo/Micro only
+}
+
+void loop()
+{
+ Test::run();
+}
diff --git a/lib/OSC/test/OSCMessage_encode_decode_test/TestPrint.h b/lib/OSC/test/OSCMessage_encode_decode_test/TestPrint.h
new file mode 100644
index 0000000..2644f2d
--- /dev/null
+++ b/lib/OSC/test/OSCMessage_encode_decode_test/TestPrint.h
@@ -0,0 +1,36 @@
+
+/**
+ * A print class for testing the encoder
+ */
+class TestPrint : public Print {
+
+ private:
+ //a small test buffer
+ uint8_t buffer[64];
+
+ //pointer to the current write spot
+ unsigned int bufferPointer;
+
+ public:
+
+ TestPrint(){
+ bufferPointer = 0;
+ }
+
+ size_t write(uint8_t character) {
+ buffer[bufferPointer++] = character;
+ return character;
+ }
+
+ unsigned int size(){
+ return bufferPointer;
+ }
+
+ uint8_t at(int index){
+ return buffer[index];
+ }
+
+ void clear(){
+ bufferPointer = 0;
+ }
+};
diff --git a/lib/OSC/test/OSCMessage_match_test/OSCMessage_match_test.ino b/lib/OSC/test/OSCMessage_match_test/OSCMessage_match_test.ino
new file mode 100644
index 0000000..41aeddc
--- /dev/null
+++ b/lib/OSC/test/OSCMessage_match_test/OSCMessage_match_test.ino
@@ -0,0 +1,86 @@
+#include
+#include
+
+
+test(message_address_match){
+ OSCMessage msg("/a/0");
+ assertEqual(msg.match("/a"), 2);
+ assertEqual(msg.match("/a/0"), 4);
+}
+
+test(message_address_match_offset){
+ OSCMessage msg("/a/0");
+ assertEqual(msg.match("/0", 2), 2);
+ assertEqual(msg.match("/1", 2), 0);
+}
+
+test(message_address_match_range){
+ OSCMessage msg("/[a-z]/0");
+ assertEqual(msg.match("/a"), 6);
+ assertEqual(msg.match("/b/0"), 8);
+}
+
+test(message_address_match_or){
+ OSCMessage msg("/{a,b}/0");
+ assertEqual(msg.match("/a/0"), 8);
+ assertEqual(msg.match("/b/0"), 8);
+ assertEqual(msg.match("/c/0"), 0);
+}
+
+test(message_address_match_char){
+ OSCMessage msg("/a/?");
+ assertEqual(msg.match("/a/0"), 4);
+ assertEqual(msg.match("/a/1"), 4);
+ assertEqual(msg.match("/a/10"), 0);
+}
+
+test(message_address_match_star){
+ OSCMessage msg("/a/*");
+ assertEqual(msg.match("/a/0"), 4);
+ assertEqual(msg.match("/a/10"), 4);
+ assertEqual(msg.match("/a/100"), 4);
+}
+
+test(message_address_fullMatch){
+ OSCMessage msg("/a/0");
+ assertTrue(msg.fullMatch("/a/0"));
+ assertFalse(msg.fullMatch("/a/1"));
+ assertTrue(msg.fullMatch("/0", 2));
+}
+
+void dispatchMsg(OSCMessage &m){
+ assertTrue(m.isInt(0));
+ assertEqual(m.getInt(0), 1);
+}
+
+test(message_address_dispatch){
+ OSCMessage msg("/a/[0-9]");
+ msg.add(1);
+ assertTrue(msg.dispatch("/a/0", dispatchMsg));
+ assertTrue(msg.dispatch("/1", dispatchMsg, 2));
+}
+
+
+void routeMsg(OSCMessage &m, int offset){
+ assertTrue(m.isInt(0));
+ assertEqual(m.getInt(0), 2);
+ assertEqual(offset, 2);
+}
+
+test(message_address_route){
+ OSCMessage msg("/?/[0-9]");
+ msg.add(2);
+ assertTrue(msg.route("/a", routeMsg));
+ assertTrue(msg.route("/b", routeMsg));
+}
+
+void setup()
+{
+ Serial.begin(9600);
+ while(!Serial); // for the Arduino Leonardo/Micro only
+}
+
+void loop()
+{
+ Test::run();
+}
diff --git a/lib/OSC/test/OSCMessage_test/OSCMessage_test.ino b/lib/OSC/test/OSCMessage_test/OSCMessage_test.ino
new file mode 100644
index 0000000..072ecac
--- /dev/null
+++ b/lib/OSC/test/OSCMessage_test/OSCMessage_test.ino
@@ -0,0 +1,104 @@
+#include
+#include
+
+#define HAS_DOUBLE sizeof(double) == 8
+
+
+test(message_address){
+ OSCMessage msg("/hihi");
+ char addr[6];
+ msg.getAddress(addr);
+ assertEqual(strcmp(addr, "/hihi"), 0);
+}
+
+test(message_address_offset){
+ OSCMessage msg("/foo/bar");
+ char addr[5];
+ msg.getAddress(addr, 4);
+ assertEqual(strcmp(addr, "/bar"), 0);
+}
+
+test(message_copy){
+ OSCMessage msg("/hihi");
+ msg.add(1);
+ OSCMessage cpy(&msg);
+ assertEqual(cpy.size(), 1);
+ assertTrue(cpy.isInt(0));
+ assertEqual(cpy.getInt(0), 1);
+}
+
+test(message_int){
+ OSCMessage msg("/foo");
+ msg.add(1);
+ assertTrue(msg.isInt(0));
+ assertEqual(msg.getInt(0), 1);
+ assertEqual(msg.getDataLength(0), 4);
+}
+
+test(message_float){
+ OSCMessage msg("/foo");
+ msg.add(1.0f);
+ assertTrue(msg.isFloat(0));
+ assertEqual(msg.getFloat(0), 1.0f);
+ assertEqual(msg.getDataLength(0), 4);
+}
+
+test(message_string){
+ OSCMessage msg("/foo");
+ msg.add("oh hi");
+ assertTrue(msg.isString(0));
+ char str[6];
+ msg.getString(0, str, 6);
+ assertEqual(strcmp(str, "oh hi"), 0);
+ assertEqual(msg.getDataLength(0), 6);
+}
+
+test(message_blob){
+ OSCMessage msg("/foo");
+ uint8_t b[] = {0, 1, 2, 3, 4};
+ msg.add(b, 5);
+ assertTrue(msg.isBlob(0));
+ uint8_t blob[5];
+ msg.getBlob(0, blob, 5);
+ for (int i = 0; i < 5; i++){
+ assertEqual(blob[i], b[i]);
+ }
+ //9 because it includes the 4 byte length
+ assertEqual(msg.getDataLength(0), 9);
+}
+
+test(message_boolean){
+ OSCMessage msg("/foo");
+ msg.add(true);
+ assertTrue(msg.isBoolean(0));
+ assertEqual(msg.getBoolean(0), true);
+ assertEqual(msg.getDataLength(0), 0);
+}
+
+test(mixed_message_type){
+ OSCMessage msg("/foo");
+ msg.add(true);
+ msg.add(1.0f);
+ msg.add(2);
+ msg.add("test");
+ assertEqual(msg.size(), 4);
+ assertEqual(msg.getType(0), 'T');
+ assertTrue(msg.isBoolean(0));
+ assertFalse(msg.isBoolean(1));
+ assertTrue(msg.isFloat(1));
+ assertTrue(msg.isInt(2));
+ assertTrue(msg.isString(3));
+ assertEqual(msg.getInt(2), 2);
+ assertEqual(msg.getInt(3), (int)NULL);
+}
+
+void setup()
+{
+ Serial.begin(9600);
+ while(!Serial); // for the Arduino Leonardo/Micro only
+}
+
+void loop()
+{
+ Test::run();
+}
diff --git a/monitor.sh b/monitor.sh
new file mode 100755
index 0000000..1185d93
--- /dev/null
+++ b/monitor.sh
@@ -0,0 +1,5 @@
+#!/bin/bash
+
+source venv/bin/activate
+
+pio device monitor -b 115200
diff --git a/platformio.ini b/platformio.ini
new file mode 100644
index 0000000..d009352
--- /dev/null
+++ b/platformio.ini
@@ -0,0 +1,33 @@
+; PlatformIO Project Configuration File
+;
+; Build options: build flags, source filter
+; Upload options: custom upload port, speed and extra flags
+; Library options: dependencies, extra library storages
+; Advanced options: extra scripting
+;
+; Please visit documentation for the other options and examples
+; https://docs.platformio.org/page/projectconf.html
+
+[env]
+platform = espressif32
+board = esp32-s2-saola-1
+framework = arduino
+
+[env:main]
+build_src_filter =
+ +
+lib_deps =
+ adafruit/Adafruit NeoPixel@^1.12.3
+
+[env:sprejemnik]
+board = esp32dev
+build_src_filter =
+ +
+
+[env:kalibracija]
+build_src_filter =
+ +
+
+[env:detect]
+build_src_filter =
+ +
diff --git a/requirements.txt b/requirements.txt
new file mode 100644
index 0000000..c837717
--- /dev/null
+++ b/requirements.txt
@@ -0,0 +1 @@
+platformio == 6.1.15
diff --git a/src/debug.cfg b/src/debug.cfg
new file mode 100644
index 0000000..aa99b3e
--- /dev/null
+++ b/src/debug.cfg
@@ -0,0 +1,14 @@
+# SPDX-License-Identifier: GPL-2.0-or-later
+#
+# Example OpenOCD configuration file for ESP32-WROVER-KIT board.
+#
+# For example, OpenOCD can be started for ESP32 debugging on
+#
+# openocd -f board/esp32-wrover-kit-3.3v.cfg
+#
+
+# Source the JTAG interface configuration file
+source [find interface/ftdi/esp32_devkitj_v1.cfg]
+set ESP32_FLASH_VOLTAGE 3.3
+# Source the ESP32 configuration file
+source [find target/esp32.cfg]
diff --git a/src/debug.svd b/src/debug.svd
new file mode 100644
index 0000000..783023f
--- /dev/null
+++ b/src/debug.svd
@@ -0,0 +1,46087 @@
+
+
+ ESPRESSIF SYSTEMS (SHANGHAI) CO., LTD.
+ ESPRESSIF
+ ESP32
+ ESP32
+ 8
+ 32-bit MCU & 2.4 GHz Wi-Fi & Bluetooth/Bluetooth LE
+
+ Copyright 2022 Espressif Systems (Shanghai) PTE LTD
+
+ Licensed under the Apache License, Version 2.0 (the "License");
+ you may not use this file except in compliance with the License.
+ You may obtain a copy of the License at
+
+ http://www.apache.org/licenses/LICENSE-2.0
+
+ Unless required by applicable law or agreed to in writing, software
+ distributed under the License is distributed on an "AS IS" BASIS,
+ WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+ See the License for the specific language governing permissions and
+ limitations under the License.
+
+
+ Xtensa LX6
+ r0p0
+ little
+ false
+ true
+ 3
+ false
+
+ 32
+ 32
+ 0x00000000
+ 0xFFFFFFFF
+
+
+ AES
+ AES (Advanced Encryption Standard) Accelerator
+ AES
+ 0x3FF01000
+
+ 0x0
+ 0x40
+ registers
+
+
+
+ START
+ 0x0
+ 0x20
+
+
+ START
+ Write 1 to start the AES operation.
+ 0
+ 1
+ write-only
+
+
+
+
+ IDLE
+ 0x4
+ 0x20
+
+
+ IDLE
+ AES Idle register. Reads ’zero’ while the AES Accelerator is busy processing; reads ’one’ otherwise.
+ 0
+ 1
+ read-only
+
+
+
+
+ MODE
+ 0x8
+ 0x20
+
+
+ MODE
+ Selects the AES accelerator mode of operation. See Table 22-1 for details.
+ 0
+ 8
+ read-write
+
+
+
+
+ 8
+ 0x4
+ KEY_%s
+ 0x10
+ 0x20
+
+
+ KEY
+ AES key material register.
+ 0
+ 8
+ read-write
+
+
+
+
+ 4
+ 0x4
+ TEXT_%s
+ 0x30
+ 0x20
+
+
+ TEXT
+ Plaintext and ciphertext register.
+ 0
+ 8
+ read-write
+
+
+
+
+ ENDIAN
+ 0x40
+ 0x20
+
+
+ ENDIAN
+ Endianness selection register. See Table 22-2 for details.
+ 0
+ 2
+ read-write
+
+
+
+
+
+
+ APB_CTRL
+ Advanced Peripheral Bus Controller
+ APB_CTRL
+ 0x3FF66000
+
+ 0x0
+ 0x44
+ registers
+
+
+
+ SYSCLK_CONF
+ 0x0
+ 0x20
+ 0x00002000
+
+
+ PRE_DIV_CNT
+ 0
+ 10
+ read-write
+
+
+ CLK_320M_EN
+ 10
+ 1
+ read-write
+
+
+ CLK_EN
+ 11
+ 1
+ read-write
+
+
+ RST_TICK_CNT
+ 12
+ 1
+ read-write
+
+
+ QUICK_CLK_CHNG
+ 13
+ 1
+ read-write
+
+
+
+
+ XTAL_TICK_CONF
+ 0x4
+ 0x20
+ 0x00000027
+
+
+ XTAL_TICK_NUM
+ 0
+ 8
+ read-write
+
+
+
+
+ PLL_TICK_CONF
+ 0x8
+ 0x20
+ 0x0000004F
+
+
+ PLL_TICK_NUM
+ 0
+ 8
+ read-write
+
+
+
+
+ CK8M_TICK_CONF
+ 0xC
+ 0x20
+ 0x0000000B
+
+
+ CK8M_TICK_NUM
+ 0
+ 8
+ read-write
+
+
+
+
+ APB_SARADC_CTRL
+ 0x10
+ 0x20
+ 0x007F8240
+
+
+ SARADC_START_FORCE
+ 0
+ 1
+ read-write
+
+
+ SARADC_START
+ 1
+ 1
+ read-write
+
+
+ SARADC_SAR2_MUX
+ 1: SAR ADC2 is controlled by DIG ADC2 CTRL 0: SAR ADC2 is controlled by PWDET CTRL
+ 2
+ 1
+ read-write
+
+
+ SARADC_WORK_MODE
+ 0: single mode 1: double mode 2: alternate mode
+ 3
+ 2
+ read-write
+
+
+ SARADC_SAR_SEL
+ 0: SAR1 1: SAR2 only work for single SAR mode
+ 5
+ 1
+ read-write
+
+
+ SARADC_SAR_CLK_GATED
+ 6
+ 1
+ read-write
+
+
+ SARADC_SAR_CLK_DIV
+ SAR clock divider
+ 7
+ 8
+ read-write
+
+
+ SARADC_SAR1_PATT_LEN
+ 0 ~ 15 means length 1 ~ 16
+ 15
+ 4
+ read-write
+
+
+ SARADC_SAR2_PATT_LEN
+ 0 ~ 15 means length 1 ~ 16
+ 19
+ 4
+ read-write
+
+
+ SARADC_SAR1_PATT_P_CLEAR
+ clear the pointer of pattern table for DIG ADC1 CTRL
+ 23
+ 1
+ read-write
+
+
+ SARADC_SAR2_PATT_P_CLEAR
+ clear the pointer of pattern table for DIG ADC2 CTRL
+ 24
+ 1
+ read-write
+
+
+ SARADC_DATA_SAR_SEL
+ 1: sar_sel will be coded by the MSB of the 16-bit output data in this case the resolution should not be larger than 11 bits.
+ 25
+ 1
+ read-write
+
+
+ SARADC_DATA_TO_I2S
+ 1: I2S input data is from SAR ADC (for DMA) 0: I2S input data is from GPIO matrix
+ 26
+ 1
+ read-write
+
+
+
+
+ APB_SARADC_CTRL2
+ 0x14
+ 0x20
+ 0x000001FE
+
+
+ SARADC_MEAS_NUM_LIMIT
+ 0
+ 1
+ read-write
+
+
+ SARADC_MAX_MEAS_NUM
+ max conversion number
+ 1
+ 8
+ read-write
+
+
+ SARADC_SAR1_INV
+ 1: data to DIG ADC1 CTRL is inverted otherwise not
+ 9
+ 1
+ read-write
+
+
+ SARADC_SAR2_INV
+ 1: data to DIG ADC2 CTRL is inverted otherwise not
+ 10
+ 1
+ read-write
+
+
+
+
+ APB_SARADC_FSM
+ 0x18
+ 0x20
+ 0x0208FF08
+
+
+ SARADC_RSTB_WAIT
+ 0
+ 8
+ read-write
+
+
+ SARADC_STANDBY_WAIT
+ 8
+ 8
+ read-write
+
+
+ SARADC_START_WAIT
+ 16
+ 8
+ read-write
+
+
+ SARADC_SAMPLE_CYCLE
+ sample cycles
+ 24
+ 8
+ read-write
+
+
+
+
+ APB_SARADC_SAR1_PATT_TAB1
+ 0x1C
+ 0x20
+ 0x0F0F0F0F
+
+
+ SARADC_SAR1_PATT_TAB1
+ item 0 ~ 3 for pattern table 1 (each item one byte)
+ 0
+ 32
+ read-write
+
+
+
+
+ APB_SARADC_SAR1_PATT_TAB2
+ 0x20
+ 0x20
+ 0x0F0F0F0F
+
+
+ SARADC_SAR1_PATT_TAB2
+ Item 4 ~ 7 for pattern table 1 (each item one byte)
+ 0
+ 32
+ read-write
+
+
+
+
+ APB_SARADC_SAR1_PATT_TAB3
+ 0x24
+ 0x20
+ 0x0F0F0F0F
+
+
+ SARADC_SAR1_PATT_TAB3
+ Item 8 ~ 11 for pattern table 1 (each item one byte)
+ 0
+ 32
+ read-write
+
+
+
+
+ APB_SARADC_SAR1_PATT_TAB4
+ 0x28
+ 0x20
+ 0x0F0F0F0F
+
+
+ SARADC_SAR1_PATT_TAB4
+ Item 12 ~ 15 for pattern table 1 (each item one byte)
+ 0
+ 32
+ read-write
+
+
+
+
+ APB_SARADC_SAR2_PATT_TAB1
+ 0x2C
+ 0x20
+ 0x0F0F0F0F
+
+
+ SARADC_SAR2_PATT_TAB1
+ item 0 ~ 3 for pattern table 2 (each item one byte)
+ 0
+ 32
+ read-write
+
+
+
+
+ APB_SARADC_SAR2_PATT_TAB2
+ 0x30
+ 0x20
+ 0x0F0F0F0F
+
+
+ SARADC_SAR2_PATT_TAB2
+ Item 4 ~ 7 for pattern table 2 (each item one byte)
+ 0
+ 32
+ read-write
+
+
+
+
+ APB_SARADC_SAR2_PATT_TAB3
+ 0x34
+ 0x20
+ 0x0F0F0F0F
+
+
+ SARADC_SAR2_PATT_TAB3
+ Item 8 ~ 11 for pattern table 2 (each item one byte)
+ 0
+ 32
+ read-write
+
+
+
+
+ APB_SARADC_SAR2_PATT_TAB4
+ 0x38
+ 0x20
+ 0x0F0F0F0F
+
+
+ SARADC_SAR2_PATT_TAB4
+ Item 12 ~ 15 for pattern table 2 (each item one byte)
+ 0
+ 32
+ read-write
+
+
+
+
+ APLL_TICK_CONF
+ 0x3C
+ 0x20
+ 0x00000063
+
+
+ APLL_TICK_NUM
+ 0
+ 8
+ read-write
+
+
+
+
+ DATE
+ 0x7C
+ 0x20
+ 0x16042000
+
+
+ DATE
+ 0
+ 32
+ read-write
+
+
+
+
+
+
+ BB
+ Peripheral BB
+ BB
+ 0x3FF5D000
+
+ 0x0
+ 0x4
+ registers
+
+
+
+ BBPD_CTRL
+ Baseband control register
+ 0x54
+ 0x20
+
+
+ DC_EST_FORCE_PD
+ 0
+ 1
+ read-write
+
+
+ DC_EST_FORCE_PU
+ 1
+ 1
+ read-write
+
+
+ FFT_FORCE_PD
+ 2
+ 1
+ read-write
+
+
+ FFT_FORCE_PU
+ 3
+ 1
+ read-write
+
+
+
+
+
+
+ DPORT
+ Peripheral DPORT
+ DPORT
+ 0x3FF00000
+
+ 0x0
+ 0x5C0
+ registers
+
+
+ WIFI_MAC
+ 0
+
+
+ WIFI_NMI
+ 1
+
+
+ WIFI_BB
+ 2
+
+
+ BT_MAC
+ 3
+
+
+ BT_BB
+ 4
+
+
+ BT_BB_NMI
+ 5
+
+
+ RWBT
+ 6
+
+
+ RWBLE
+ 7
+
+
+ RWBT_NMI
+ 8
+
+
+ RWBLE_NMI
+ 9
+
+
+
+ PRO_BOOT_REMAP_CTRL
+ 0x0
+ 0x20
+
+
+ PRO_BOOT_REMAP
+ 0
+ 1
+ read-write
+
+
+
+
+ APP_BOOT_REMAP_CTRL
+ 0x4
+ 0x20
+
+
+ APP_BOOT_REMAP
+ 0
+ 1
+ read-write
+
+
+
+
+ ACCESS_CHECK
+ 0x8
+ 0x20
+
+
+ PRO
+ 0
+ 1
+ read-only
+
+
+ APP
+ 8
+ 1
+ read-only
+
+
+
+
+ PRO_DPORT_APB_MASK0
+ 0xC
+ 0x20
+
+
+ PRODPORT_APB_MASK0
+ 0
+ 32
+ read-write
+
+
+
+
+ PRO_DPORT_APB_MASK1
+ 0x10
+ 0x20
+
+
+ PRODPORT_APB_MASK1
+ 0
+ 32
+ read-write
+
+
+
+
+ APP_DPORT_APB_MASK0
+ 0x14
+ 0x20
+
+
+ APPDPORT_APB_MASK0
+ 0
+ 32
+ read-write
+
+
+
+
+ APP_DPORT_APB_MASK1
+ 0x18
+ 0x20
+
+
+ APPDPORT_APB_MASK1
+ 0
+ 32
+ read-write
+
+
+
+
+ PERI_CLK_EN
+ 0x1C
+ 0x20
+
+
+ PERI_CLK_EN
+ 0
+ 32
+ read-write
+
+
+
+
+ PERI_RST_EN
+ 0x20
+ 0x20
+
+
+ PERI_RST_EN
+ 0
+ 32
+ read-write
+
+
+
+
+ WIFI_BB_CFG
+ 0x24
+ 0x20
+
+
+ WIFI_BB_CFG
+ 0
+ 32
+ read-write
+
+
+
+
+ WIFI_BB_CFG_2
+ 0x28
+ 0x20
+
+
+ WIFI_BB_CFG_2
+ 0
+ 32
+ read-write
+
+
+
+
+ APPCPU_CTRL_A
+ 0x2C
+ 0x20
+ 0x00000001
+
+
+ APPCPU_RESETTING
+ 0
+ 1
+ read-write
+
+
+
+
+ APPCPU_CTRL_B
+ 0x30
+ 0x20
+
+
+ APPCPU_CLKGATE_EN
+ 0
+ 1
+ read-write
+
+
+
+
+ APPCPU_CTRL_C
+ 0x34
+ 0x20
+
+
+ APPCPU_RUNSTALL
+ 0
+ 1
+ read-write
+
+
+
+
+ APPCPU_CTRL_D
+ 0x38
+ 0x20
+
+
+ APPCPU_BOOT_ADDR
+ 0
+ 32
+ read-write
+
+
+
+
+ CPU_PER_CONF
+ 0x3C
+ 0x20
+
+
+ CPUPERIOD_SEL
+ 0
+ 2
+ read-write
+
+
+ LOWSPEED_CLK_SEL
+ 2
+ 1
+ read-write
+
+
+ FAST_CLK_RTC_SEL
+ 3
+ 1
+ read-write
+
+
+
+
+ PRO_CACHE_CTRL
+ 0x40
+ 0x20
+ 0x00000010
+
+
+ PRO_CACHE_MODE
+ 2
+ 1
+ read-write
+
+
+ PRO_CACHE_ENABLE
+ 3
+ 1
+ read-write
+
+
+ PRO_CACHE_FLUSH_ENA
+ 4
+ 1
+ read-write
+
+
+ PRO_CACHE_FLUSH_DONE
+ 5
+ 1
+ read-only
+
+
+ PRO_CACHE_LOCK_0_EN
+ 6
+ 1
+ read-write
+
+
+ PRO_CACHE_LOCK_1_EN
+ 7
+ 1
+ read-write
+
+
+ PRO_CACHE_LOCK_2_EN
+ 8
+ 1
+ read-write
+
+
+ PRO_CACHE_LOCK_3_EN
+ 9
+ 1
+ read-write
+
+
+ PRO_SINGLE_IRAM_ENA
+ 10
+ 1
+ read-write
+
+
+ PRO_DRAM_SPLIT
+ 11
+ 1
+ read-write
+
+
+ PRO_AHB_SPI_REQ
+ 12
+ 1
+ read-only
+
+
+ PRO_SLAVE_REQ
+ 13
+ 1
+ read-only
+
+
+ AHB_SPI_REQ
+ 14
+ 1
+ read-only
+
+
+ SLAVE_REQ
+ 15
+ 1
+ read-only
+
+
+ PRO_DRAM_HL
+ 16
+ 1
+ read-write
+
+
+
+
+ PRO_CACHE_CTRL1
+ 0x44
+ 0x20
+ 0x000008FF
+
+
+ PRO_CACHE_MASK_IRAM0
+ 0
+ 1
+ read-write
+
+
+ PRO_CACHE_MASK_IRAM1
+ 1
+ 1
+ read-write
+
+
+ PRO_CACHE_MASK_IROM0
+ 2
+ 1
+ read-write
+
+
+ PRO_CACHE_MASK_DRAM1
+ 3
+ 1
+ read-write
+
+
+ PRO_CACHE_MASK_DROM0
+ 4
+ 1
+ read-write
+
+
+ PRO_CACHE_MASK_OPSDRAM
+ 5
+ 1
+ read-write
+
+
+ PRO_CMMU_SRAM_PAGE_MODE
+ 6
+ 3
+ read-write
+
+
+ PRO_CMMU_FLASH_PAGE_MODE
+ 9
+ 2
+ read-write
+
+
+ PRO_CMMU_FORCE_ON
+ 11
+ 1
+ read-write
+
+
+ PRO_CMMU_PD
+ 12
+ 1
+ read-write
+
+
+ PRO_CACHE_MMU_IA_CLR
+ 13
+ 1
+ read-write
+
+
+
+
+ PRO_CACHE_LOCK_0_ADDR
+ 0x48
+ 0x20
+
+
+ PRE
+ 0
+ 14
+ read-write
+
+
+ MIN
+ 14
+ 4
+ read-write
+
+
+ MAX
+ 18
+ 4
+ read-write
+
+
+
+
+ PRO_CACHE_LOCK_1_ADDR
+ 0x4C
+ 0x20
+
+
+ PRE
+ 0
+ 14
+ read-write
+
+
+ MIN
+ 14
+ 4
+ read-write
+
+
+ MAX
+ 18
+ 4
+ read-write
+
+
+
+
+ PRO_CACHE_LOCK_2_ADDR
+ 0x50
+ 0x20
+
+
+ PRE
+ 0
+ 14
+ read-write
+
+
+ MIN
+ 14
+ 4
+ read-write
+
+
+ MAX
+ 18
+ 4
+ read-write
+
+
+
+
+ PRO_CACHE_LOCK_3_ADDR
+ 0x54
+ 0x20
+
+
+ PRE
+ 0
+ 14
+ read-write
+
+
+ MIN
+ 14
+ 4
+ read-write
+
+
+ MAX
+ 18
+ 4
+ read-write
+
+
+
+
+ APP_CACHE_CTRL
+ 0x58
+ 0x20
+ 0x00000010
+
+
+ APP_CACHE_MODE
+ 2
+ 1
+ read-write
+
+
+ APP_CACHE_ENABLE
+ 3
+ 1
+ read-write
+
+
+ APP_CACHE_FLUSH_ENA
+ 4
+ 1
+ read-write
+
+
+ APP_CACHE_FLUSH_DONE
+ 5
+ 1
+ read-only
+
+
+ APP_CACHE_LOCK_0_EN
+ 6
+ 1
+ read-write
+
+
+ APP_CACHE_LOCK_1_EN
+ 7
+ 1
+ read-write
+
+
+ APP_CACHE_LOCK_2_EN
+ 8
+ 1
+ read-write
+
+
+ APP_CACHE_LOCK_3_EN
+ 9
+ 1
+ read-write
+
+
+ APP_SINGLE_IRAM_ENA
+ 10
+ 1
+ read-write
+
+
+ APP_DRAM_SPLIT
+ 11
+ 1
+ read-write
+
+
+ APP_AHB_SPI_REQ
+ 12
+ 1
+ read-only
+
+
+ APP_SLAVE_REQ
+ 13
+ 1
+ read-only
+
+
+ APP_DRAM_HL
+ 14
+ 1
+ read-write
+
+
+
+
+ APP_CACHE_CTRL1
+ 0x5C
+ 0x20
+ 0x000008FF
+
+
+ APP_CACHE_MASK_IRAM0
+ 0
+ 1
+ read-write
+
+
+ APP_CACHE_MASK_IRAM1
+ 1
+ 1
+ read-write
+
+
+ APP_CACHE_MASK_IROM0
+ 2
+ 1
+ read-write
+
+
+ APP_CACHE_MASK_DRAM1
+ 3
+ 1
+ read-write
+
+
+ APP_CACHE_MASK_DROM0
+ 4
+ 1
+ read-write
+
+
+ APP_CACHE_MASK_OPSDRAM
+ 5
+ 1
+ read-write
+
+
+ APP_CMMU_SRAM_PAGE_MODE
+ 6
+ 3
+ read-write
+
+
+ APP_CMMU_FLASH_PAGE_MODE
+ 9
+ 2
+ read-write
+
+
+ APP_CMMU_FORCE_ON
+ 11
+ 1
+ read-write
+
+
+ APP_CMMU_PD
+ 12
+ 1
+ read-write
+
+
+ APP_CACHE_MMU_IA_CLR
+ 13
+ 1
+ read-write
+
+
+
+
+ APP_CACHE_LOCK_0_ADDR
+ 0x60
+ 0x20
+
+
+ PRE
+ 0
+ 14
+ read-write
+
+
+ MIN
+ 14
+ 4
+ read-write
+
+
+ MAX
+ 18
+ 4
+ read-write
+
+
+
+
+ APP_CACHE_LOCK_1_ADDR
+ 0x64
+ 0x20
+
+
+ PRE
+ 0
+ 14
+ read-write
+
+
+ MIN
+ 14
+ 4
+ read-write
+
+
+ MAX
+ 18
+ 4
+ read-write
+
+
+
+
+ APP_CACHE_LOCK_2_ADDR
+ 0x68
+ 0x20
+
+
+ PRE
+ 0
+ 14
+ read-write
+
+
+ MIN
+ 14
+ 4
+ read-write
+
+
+ MAX
+ 18
+ 4
+ read-write
+
+
+
+
+ APP_CACHE_LOCK_3_ADDR
+ 0x6C
+ 0x20
+
+
+ PRE
+ 0
+ 14
+ read-write
+
+
+ MIN
+ 14
+ 4
+ read-write
+
+
+ MAX
+ 18
+ 4
+ read-write
+
+
+
+
+ TRACEMEM_MUX_MODE
+ 0x70
+ 0x20
+
+
+ TRACEMEM_MUX_MODE
+ 0
+ 2
+ read-write
+
+
+
+
+ PRO_TRACEMEM_ENA
+ 0x74
+ 0x20
+
+
+ PRO_TRACEMEM_ENA
+ 0
+ 1
+ read-write
+
+
+
+
+ APP_TRACEMEM_ENA
+ 0x78
+ 0x20
+
+
+ APP_TRACEMEM_ENA
+ 0
+ 1
+ read-write
+
+
+
+
+ CACHE_MUX_MODE
+ 0x7C
+ 0x20
+
+
+ CACHE_MUX_MODE
+ 0
+ 2
+ read-write
+
+
+
+
+ IMMU_PAGE_MODE
+ 0x80
+ 0x20
+
+
+ INTERNAL_SRAM_IMMU_ENA
+ 0
+ 1
+ read-write
+
+
+ IMMU_PAGE_MODE
+ 1
+ 2
+ read-write
+
+
+
+
+ DMMU_PAGE_MODE
+ 0x84
+ 0x20
+
+
+ INTERNAL_SRAM_DMMU_ENA
+ 0
+ 1
+ read-write
+
+
+ DMMU_PAGE_MODE
+ 1
+ 2
+ read-write
+
+
+
+
+ ROM_MPU_ENA
+ 0x88
+ 0x20
+
+
+ SHARE_ROM_MPU_ENA
+ 0
+ 1
+ read-write
+
+
+ PRO_ROM_MPU_ENA
+ 1
+ 1
+ read-write
+
+
+ APP_ROM_MPU_ENA
+ 2
+ 1
+ read-write
+
+
+
+
+ MEM_PD_MASK
+ 0x8C
+ 0x20
+ 0x00000001
+
+
+ LSLP_MEM_PD_MASK
+ 0
+ 1
+ read-write
+
+
+
+
+ ROM_PD_CTRL
+ 0x90
+ 0x20
+
+
+ PRO_ROM_PD
+ 0
+ 1
+ read-write
+
+
+ APP_ROM_PD
+ 1
+ 1
+ read-write
+
+
+ SHARE_ROM_PD
+ 2
+ 6
+ read-write
+
+
+
+
+ ROM_FO_CTRL
+ 0x94
+ 0x20
+ 0x00000003
+
+
+ PRO_ROM_FO
+ 0
+ 1
+ read-write
+
+
+ APP_ROM_FO
+ 1
+ 1
+ read-write
+
+
+ SHARE_ROM_FO
+ 2
+ 6
+ read-write
+
+
+
+
+ SRAM_PD_CTRL_0
+ 0x98
+ 0x20
+
+
+ SRAM_PD_0
+ 0
+ 32
+ read-write
+
+
+
+
+ SRAM_PD_CTRL_1
+ 0x9C
+ 0x20
+
+
+ SRAM_PD_1
+ 0
+ 1
+ read-write
+
+
+
+
+ SRAM_FO_CTRL_0
+ 0xA0
+ 0x20
+ 0xFFFFFFFF
+
+
+ SRAM_FO_0
+ 0
+ 32
+ read-write
+
+
+
+
+ SRAM_FO_CTRL_1
+ 0xA4
+ 0x20
+ 0x00000001
+
+
+ SRAM_FO_1
+ 0
+ 1
+ read-write
+
+
+
+
+ IRAM_DRAM_AHB_SEL
+ 0xA8
+ 0x20
+
+
+ MASK_PRO_IRAM
+ 0
+ 1
+ read-write
+
+
+ MASK_APP_IRAM
+ 1
+ 1
+ read-write
+
+
+ MASK_PRO_DRAM
+ 2
+ 1
+ read-write
+
+
+ MASK_APP_DRAM
+ 3
+ 1
+ read-write
+
+
+ MASK_AHB
+ 4
+ 1
+ read-write
+
+
+ MAC_DUMP_MODE
+ 5
+ 2
+ read-write
+
+
+
+
+ TAG_FO_CTRL
+ 0xAC
+ 0x20
+ 0x00000101
+
+
+ PRO_CACHE_TAG_FORCE_ON
+ 0
+ 1
+ read-write
+
+
+ PRO_CACHE_TAG_PD
+ 1
+ 1
+ read-write
+
+
+ APP_CACHE_TAG_FORCE_ON
+ 8
+ 1
+ read-write
+
+
+ APP_CACHE_TAG_PD
+ 9
+ 1
+ read-write
+
+
+
+
+ AHB_LITE_MASK
+ 0xB0
+ 0x20
+
+
+ PRO
+ 0
+ 1
+ read-write
+
+
+ APP
+ 4
+ 1
+ read-write
+
+
+ SDIO
+ 8
+ 1
+ read-write
+
+
+ PRODPORT
+ 9
+ 1
+ read-write
+
+
+ APPDPORT
+ 10
+ 1
+ read-write
+
+
+ AHB_LITE_SDHOST_PID
+ 11
+ 3
+ read-write
+
+
+
+
+ AHB_MPU_TABLE_0
+ 0xB4
+ 0x20
+ 0xFFFFFFFF
+
+
+ AHB_ACCESS_GRANT_0
+ 0
+ 32
+ read-write
+
+
+
+
+ AHB_MPU_TABLE_1
+ 0xB8
+ 0x20
+ 0x000001FF
+
+
+ AHB_ACCESS_GRANT_1
+ 0
+ 9
+ read-write
+
+
+
+
+ HOST_INF_SEL
+ 0xBC
+ 0x20
+
+
+ PERI_IO_SWAP
+ 0
+ 8
+ read-write
+
+
+ LINK_DEVICE_SEL
+ 8
+ 8
+ read-write
+
+
+
+
+ PERIP_CLK_EN
+ 0xC0
+ 0x20
+ 0xF9C1E06F
+
+
+ TIMERS_CLK_EN
+ 0
+ 1
+ read-write
+
+
+ SPI01_CLK_EN
+ 1
+ 1
+ read-write
+
+
+ UART_CLK_EN
+ 2
+ 1
+ read-write
+
+
+ WDG_CLK_EN
+ 3
+ 1
+ read-write
+
+
+ I2S0_CLK_EN
+ 4
+ 1
+ read-write
+
+
+ UART1_CLK_EN
+ 5
+ 1
+ read-write
+
+
+ SPI2_CLK_EN
+ 6
+ 1
+ read-write
+
+
+ I2C0_EXT0_CLK_EN
+ 7
+ 1
+ read-write
+
+
+ UHCI0_CLK_EN
+ 8
+ 1
+ read-write
+
+
+ RMT_CLK_EN
+ 9
+ 1
+ read-write
+
+
+ PCNT_CLK_EN
+ 10
+ 1
+ read-write
+
+
+ LEDC_CLK_EN
+ 11
+ 1
+ read-write
+
+
+ UHCI1_CLK_EN
+ 12
+ 1
+ read-write
+
+
+ TIMERGROUP_CLK_EN
+ 13
+ 1
+ read-write
+
+
+ EFUSE_CLK_EN
+ 14
+ 1
+ read-write
+
+
+ TIMERGROUP1_CLK_EN
+ 15
+ 1
+ read-write
+
+
+ SPI3_CLK_EN
+ 16
+ 1
+ read-write
+
+
+ PWM0_CLK_EN
+ 17
+ 1
+ read-write
+
+
+ I2C_EXT1_CLK_EN
+ 18
+ 1
+ read-write
+
+
+ TWAI_CLK_EN
+ 19
+ 1
+ read-write
+
+
+ PWM1_CLK_EN
+ 20
+ 1
+ read-write
+
+
+ I2S1_CLK_EN
+ 21
+ 1
+ read-write
+
+
+ SPI_DMA_CLK_EN
+ 22
+ 1
+ read-write
+
+
+ UART2_CLK_EN
+ 23
+ 1
+ read-write
+
+
+ UART_MEM_CLK_EN
+ 24
+ 1
+ read-write
+
+
+ PWM2_CLK_EN
+ 25
+ 1
+ read-write
+
+
+ PWM3_CLK_EN
+ 26
+ 1
+ read-write
+
+
+
+
+ PERIP_RST_EN
+ 0xC4
+ 0x20
+
+
+ TIMERS_RST
+ 0
+ 1
+ read-write
+
+
+ SPI01_RST
+ 1
+ 1
+ read-write
+
+
+ UART_RST
+ 2
+ 1
+ read-write
+
+
+ WDG_RST
+ 3
+ 1
+ read-write
+
+
+ I2S0_RST
+ 4
+ 1
+ read-write
+
+
+ UART1_RST
+ 5
+ 1
+ read-write
+
+
+ SPI2_RST
+ 6
+ 1
+ read-write
+
+
+ I2C0_EXT0_RST
+ 7
+ 1
+ read-write
+
+
+ UHCI0_RST
+ 8
+ 1
+ read-write
+
+
+ RMT_RST
+ 9
+ 1
+ read-write
+
+
+ PCNT_RST
+ 10
+ 1
+ read-write
+
+
+ LEDC_RST
+ 11
+ 1
+ read-write
+
+
+ UHCI1_RST
+ 12
+ 1
+ read-write
+
+
+ TIMERGROUP_RST
+ 13
+ 1
+ read-write
+
+
+ EFUSE_RST
+ 14
+ 1
+ read-write
+
+
+ TIMERGROUP1_RST
+ 15
+ 1
+ read-write
+
+
+ SPI3_RST
+ 16
+ 1
+ read-write
+
+
+ PWM0_RST
+ 17
+ 1
+ read-write
+
+
+ I2C_EXT1_RST
+ 18
+ 1
+ read-write
+
+
+ TWAI_RST
+ 19
+ 1
+ read-write
+
+
+ PWM1_RST
+ 20
+ 1
+ read-write
+
+
+ I2S1_RST
+ 21
+ 1
+ read-write
+
+
+ SPI_DMA_RST
+ 22
+ 1
+ read-write
+
+
+ UART2_RST
+ 23
+ 1
+ read-write
+
+
+ UART_MEM_RST
+ 24
+ 1
+ read-write
+
+
+ PWM2_RST
+ 25
+ 1
+ read-write
+
+
+ PWM3_RST
+ 26
+ 1
+ read-write
+
+
+
+
+ SLAVE_SPI_CONFIG
+ 0xC8
+ 0x20
+
+
+ SLAVE_SPI_MASK_PRO
+ 0
+ 1
+ read-write
+
+
+ SLAVE_SPI_MASK_APP
+ 4
+ 1
+ read-write
+
+
+ SPI_ENCRYPT_ENABLE
+ 8
+ 1
+ read-write
+
+
+ SPI_DECRYPT_ENABLE
+ 12
+ 1
+ read-write
+
+
+
+
+ WIFI_CLK_EN
+ 0xCC
+ 0x20
+ 0xFFFCE030
+
+
+ WIFI_CLK_EN
+ 0
+ 32
+ read-write
+
+
+ WIFI_CLK_WIFI_EN
+ 0
+ 3
+ read-write
+
+
+ WIFI_CLK_WIFI_BT_COMMON
+ 0
+ 6
+ read-write
+
+
+ WIFI_CLK_BT_EN
+ 11
+ 3
+ read-write
+
+
+
+
+ CORE_RST_EN
+ 0xD0
+ 0x20
+
+
+ CORE_RST
+ 0
+ 8
+ read-write
+
+
+ BB_RST
+ 0
+ 1
+ read-write
+
+
+ FE_RST
+ 1
+ 1
+ read-write
+
+
+ MAC_RST
+ 2
+ 1
+ read-write
+
+
+ BT_RST
+ 3
+ 1
+ read-write
+
+
+ BTMAC_RST
+ 4
+ 1
+ read-write
+
+
+ SDIO_RST
+ 5
+ 1
+ read-write
+
+
+ SDIO_HOST_RST
+ 6
+ 1
+ read-write
+
+
+ EMAC_RST
+ 7
+ 1
+ read-write
+
+
+ MACPWR_RST
+ 8
+ 1
+ read-write
+
+
+ RW_BTMAC_RST
+ 9
+ 1
+ read-write
+
+
+ RW_BTLP_RST
+ 10
+ 1
+ read-write
+
+
+
+
+ BT_LPCK_DIV_INT
+ 0xD4
+ 0x20
+ 0x000000FF
+
+
+ BT_LPCK_DIV_NUM
+ 0
+ 12
+ read-write
+
+
+ BTEXTWAKEUP_REQ
+ 12
+ 1
+ read-write
+
+
+
+
+ BT_LPCK_DIV_FRAC
+ 0xD8
+ 0x20
+ 0x02001001
+
+
+ BT_LPCK_DIV_B
+ 0
+ 12
+ read-write
+
+
+ BT_LPCK_DIV_A
+ 12
+ 12
+ read-write
+
+
+ LPCLK_SEL_RTC_SLOW
+ 24
+ 1
+ read-write
+
+
+ LPCLK_SEL_8M
+ 25
+ 1
+ read-write
+
+
+ LPCLK_SEL_XTAL
+ 26
+ 1
+ read-write
+
+
+ LPCLK_SEL_XTAL32K
+ 27
+ 1
+ read-write
+
+
+
+
+ CPU_INTR_FROM_CPU_0
+ 0xDC
+ 0x20
+
+
+ CPU_INTR_FROM_CPU_0
+ 0
+ 1
+ read-write
+
+
+
+
+ CPU_INTR_FROM_CPU_1
+ 0xE0
+ 0x20
+
+
+ CPU_INTR_FROM_CPU_1
+ 0
+ 1
+ read-write
+
+
+
+
+ CPU_INTR_FROM_CPU_2
+ 0xE4
+ 0x20
+
+
+ CPU_INTR_FROM_CPU_2
+ 0
+ 1
+ read-write
+
+
+
+
+ CPU_INTR_FROM_CPU_3
+ 0xE8
+ 0x20
+
+
+ CPU_INTR_FROM_CPU_3
+ 0
+ 1
+ read-write
+
+
+
+
+ PRO_INTR_STATUS_0
+ 0xEC
+ 0x20
+
+
+ PRO_INTR_STATUS_0
+ 0
+ 32
+ read-only
+
+
+
+
+ PRO_INTR_STATUS_1
+ 0xF0
+ 0x20
+
+
+ PRO_INTR_STATUS_1
+ 0
+ 32
+ read-only
+
+
+
+
+ PRO_INTR_STATUS_2
+ 0xF4
+ 0x20
+
+
+ PRO_INTR_STATUS_2
+ 0
+ 32
+ read-only
+
+
+
+
+ APP_INTR_STATUS_0
+ 0xF8
+ 0x20
+
+
+ APP_INTR_STATUS_0
+ 0
+ 32
+ read-only
+
+
+
+
+ APP_INTR_STATUS_1
+ 0xFC
+ 0x20
+
+
+ APP_INTR_STATUS_1
+ 0
+ 32
+ read-only
+
+
+
+
+ APP_INTR_STATUS_2
+ 0x100
+ 0x20
+
+
+ APP_INTR_STATUS_2
+ 0
+ 32
+ read-only
+
+
+
+
+ PRO_MAC_INTR_MAP
+ 0x104
+ 0x20
+ 0x00000010
+
+
+ PRO_MAC_INTR_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_MAC_NMI_MAP
+ 0x108
+ 0x20
+ 0x00000010
+
+
+ PRO_MAC_NMI_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_BB_INT_MAP
+ 0x10C
+ 0x20
+ 0x00000010
+
+
+ PRO_BB_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_BT_MAC_INT_MAP
+ 0x110
+ 0x20
+ 0x00000010
+
+
+ PRO_BT_MAC_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_BT_BB_INT_MAP
+ 0x114
+ 0x20
+ 0x00000010
+
+
+ PRO_BT_BB_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_BT_BB_NMI_MAP
+ 0x118
+ 0x20
+ 0x00000010
+
+
+ PRO_BT_BB_NMI_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_RWBT_IRQ_MAP
+ 0x11C
+ 0x20
+ 0x00000010
+
+
+ PRO_RWBT_IRQ_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_RWBLE_IRQ_MAP
+ 0x120
+ 0x20
+ 0x00000010
+
+
+ PRO_RWBLE_IRQ_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_RWBT_NMI_MAP
+ 0x124
+ 0x20
+ 0x00000010
+
+
+ PRO_RWBT_NMI_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_RWBLE_NMI_MAP
+ 0x128
+ 0x20
+ 0x00000010
+
+
+ PRO_RWBLE_NMI_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_SLC0_INTR_MAP
+ 0x12C
+ 0x20
+ 0x00000010
+
+
+ PRO_SLC0_INTR_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_SLC1_INTR_MAP
+ 0x130
+ 0x20
+ 0x00000010
+
+
+ PRO_SLC1_INTR_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_UHCI0_INTR_MAP
+ 0x134
+ 0x20
+ 0x00000010
+
+
+ PRO_UHCI0_INTR_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_UHCI1_INTR_MAP
+ 0x138
+ 0x20
+ 0x00000010
+
+
+ PRO_UHCI1_INTR_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_TG_T0_LEVEL_INT_MAP
+ 0x13C
+ 0x20
+ 0x00000010
+
+
+ PRO_TG_T0_LEVEL_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_TG_T1_LEVEL_INT_MAP
+ 0x140
+ 0x20
+ 0x00000010
+
+
+ PRO_TG_T1_LEVEL_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_TG_WDT_LEVEL_INT_MAP
+ 0x144
+ 0x20
+ 0x00000010
+
+
+ PRO_TG_WDT_LEVEL_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_TG_LACT_LEVEL_INT_MAP
+ 0x148
+ 0x20
+ 0x00000010
+
+
+ PRO_TG_LACT_LEVEL_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_TG1_T0_LEVEL_INT_MAP
+ 0x14C
+ 0x20
+ 0x00000010
+
+
+ PRO_TG1_T0_LEVEL_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_TG1_T1_LEVEL_INT_MAP
+ 0x150
+ 0x20
+ 0x00000010
+
+
+ PRO_TG1_T1_LEVEL_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_TG1_WDT_LEVEL_INT_MAP
+ 0x154
+ 0x20
+ 0x00000010
+
+
+ PRO_TG1_WDT_LEVEL_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_TG1_LACT_LEVEL_INT_MAP
+ 0x158
+ 0x20
+ 0x00000010
+
+
+ PRO_TG1_LACT_LEVEL_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_GPIO_INTERRUPT_MAP
+ 0x15C
+ 0x20
+ 0x00000010
+
+
+ PRO_GPIO_INTERRUPT_PRO_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_GPIO_INTERRUPT_NMI_MAP
+ 0x160
+ 0x20
+ 0x00000010
+
+
+ PRO_GPIO_INTERRUPT_PRO_NMI_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_CPU_INTR_FROM_CPU_0_MAP
+ 0x164
+ 0x20
+ 0x00000010
+
+
+ PRO_CPU_INTR_FROM_CPU_0_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_CPU_INTR_FROM_CPU_1_MAP
+ 0x168
+ 0x20
+ 0x00000010
+
+
+ PRO_CPU_INTR_FROM_CPU_1_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_CPU_INTR_FROM_CPU_2_MAP
+ 0x16C
+ 0x20
+ 0x00000010
+
+
+ PRO_CPU_INTR_FROM_CPU_2_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_CPU_INTR_FROM_CPU_3_MAP
+ 0x170
+ 0x20
+ 0x00000010
+
+
+ PRO_CPU_INTR_FROM_CPU_3_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_SPI_INTR_0_MAP
+ 0x174
+ 0x20
+ 0x00000010
+
+
+ PRO_SPI_INTR_0_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_SPI_INTR_1_MAP
+ 0x178
+ 0x20
+ 0x00000010
+
+
+ PRO_SPI_INTR_1_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_SPI_INTR_2_MAP
+ 0x17C
+ 0x20
+ 0x00000010
+
+
+ PRO_SPI_INTR_2_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_SPI_INTR_3_MAP
+ 0x180
+ 0x20
+ 0x00000010
+
+
+ PRO_SPI_INTR_3_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_I2S0_INT_MAP
+ 0x184
+ 0x20
+ 0x00000010
+
+
+ PRO_I2S0_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_I2S1_INT_MAP
+ 0x188
+ 0x20
+ 0x00000010
+
+
+ PRO_I2S1_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_UART_INTR_MAP
+ 0x18C
+ 0x20
+ 0x00000010
+
+
+ PRO_UART_INTR_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_UART1_INTR_MAP
+ 0x190
+ 0x20
+ 0x00000010
+
+
+ PRO_UART1_INTR_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_UART2_INTR_MAP
+ 0x194
+ 0x20
+ 0x00000010
+
+
+ PRO_UART2_INTR_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_SDIO_HOST_INTERRUPT_MAP
+ 0x198
+ 0x20
+ 0x00000010
+
+
+ PRO_SDIO_HOST_INTERRUPT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_EMAC_INT_MAP
+ 0x19C
+ 0x20
+ 0x00000010
+
+
+ PRO_EMAC_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_PWM0_INTR_MAP
+ 0x1A0
+ 0x20
+ 0x00000010
+
+
+ PRO_PWM0_INTR_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_PWM1_INTR_MAP
+ 0x1A4
+ 0x20
+ 0x00000010
+
+
+ PRO_PWM1_INTR_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_PWM2_INTR_MAP
+ 0x1A8
+ 0x20
+ 0x00000010
+
+
+ PRO_PWM2_INTR_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_PWM3_INTR_MAP
+ 0x1AC
+ 0x20
+ 0x00000010
+
+
+ PRO_PWM3_INTR_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_LEDC_INT_MAP
+ 0x1B0
+ 0x20
+ 0x00000010
+
+
+ PRO_LEDC_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_EFUSE_INT_MAP
+ 0x1B4
+ 0x20
+ 0x00000010
+
+
+ PRO_EFUSE_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_CAN_INT_MAP
+ 0x1B8
+ 0x20
+ 0x00000010
+
+
+ PRO_CAN_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_RTC_CORE_INTR_MAP
+ 0x1BC
+ 0x20
+ 0x00000010
+
+
+ PRO_RTC_CORE_INTR_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_RMT_INTR_MAP
+ 0x1C0
+ 0x20
+ 0x00000010
+
+
+ PRO_RMT_INTR_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_PCNT_INTR_MAP
+ 0x1C4
+ 0x20
+ 0x00000010
+
+
+ PRO_PCNT_INTR_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_I2C_EXT0_INTR_MAP
+ 0x1C8
+ 0x20
+ 0x00000010
+
+
+ PRO_I2C_EXT0_INTR_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_I2C_EXT1_INTR_MAP
+ 0x1CC
+ 0x20
+ 0x00000010
+
+
+ PRO_I2C_EXT1_INTR_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_RSA_INTR_MAP
+ 0x1D0
+ 0x20
+ 0x00000010
+
+
+ PRO_RSA_INTR_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_SPI1_DMA_INT_MAP
+ 0x1D4
+ 0x20
+ 0x00000010
+
+
+ PRO_SPI1_DMA_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_SPI2_DMA_INT_MAP
+ 0x1D8
+ 0x20
+ 0x00000010
+
+
+ PRO_SPI2_DMA_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_SPI3_DMA_INT_MAP
+ 0x1DC
+ 0x20
+ 0x00000010
+
+
+ PRO_SPI3_DMA_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_WDG_INT_MAP
+ 0x1E0
+ 0x20
+ 0x00000010
+
+
+ PRO_WDG_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_TIMER_INT1_MAP
+ 0x1E4
+ 0x20
+ 0x00000010
+
+
+ PRO_TIMER_INT1_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_TIMER_INT2_MAP
+ 0x1E8
+ 0x20
+ 0x00000010
+
+
+ PRO_TIMER_INT2_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_TG_T0_EDGE_INT_MAP
+ 0x1EC
+ 0x20
+ 0x00000010
+
+
+ PRO_TG_T0_EDGE_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_TG_T1_EDGE_INT_MAP
+ 0x1F0
+ 0x20
+ 0x00000010
+
+
+ PRO_TG_T1_EDGE_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_TG_WDT_EDGE_INT_MAP
+ 0x1F4
+ 0x20
+ 0x00000010
+
+
+ PRO_TG_WDT_EDGE_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_TG_LACT_EDGE_INT_MAP
+ 0x1F8
+ 0x20
+ 0x00000010
+
+
+ PRO_TG_LACT_EDGE_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_TG1_T0_EDGE_INT_MAP
+ 0x1FC
+ 0x20
+ 0x00000010
+
+
+ PRO_TG1_T0_EDGE_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_TG1_T1_EDGE_INT_MAP
+ 0x200
+ 0x20
+ 0x00000010
+
+
+ PRO_TG1_T1_EDGE_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_TG1_WDT_EDGE_INT_MAP
+ 0x204
+ 0x20
+ 0x00000010
+
+
+ PRO_TG1_WDT_EDGE_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_TG1_LACT_EDGE_INT_MAP
+ 0x208
+ 0x20
+ 0x00000010
+
+
+ PRO_TG1_LACT_EDGE_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_MMU_IA_INT_MAP
+ 0x20C
+ 0x20
+ 0x00000010
+
+
+ PRO_MMU_IA_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_MPU_IA_INT_MAP
+ 0x210
+ 0x20
+ 0x00000010
+
+
+ PRO_MPU_IA_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ PRO_CACHE_IA_INT_MAP
+ 0x214
+ 0x20
+ 0x00000010
+
+
+ PRO_CACHE_IA_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_MAC_INTR_MAP
+ 0x218
+ 0x20
+ 0x00000010
+
+
+ APP_MAC_INTR_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_MAC_NMI_MAP
+ 0x21C
+ 0x20
+ 0x00000010
+
+
+ APP_MAC_NMI_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_BB_INT_MAP
+ 0x220
+ 0x20
+ 0x00000010
+
+
+ APP_BB_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_BT_MAC_INT_MAP
+ 0x224
+ 0x20
+ 0x00000010
+
+
+ APP_BT_MAC_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_BT_BB_INT_MAP
+ 0x228
+ 0x20
+ 0x00000010
+
+
+ APP_BT_BB_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_BT_BB_NMI_MAP
+ 0x22C
+ 0x20
+ 0x00000010
+
+
+ APP_BT_BB_NMI_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_RWBT_IRQ_MAP
+ 0x230
+ 0x20
+ 0x00000010
+
+
+ APP_RWBT_IRQ_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_RWBLE_IRQ_MAP
+ 0x234
+ 0x20
+ 0x00000010
+
+
+ APP_RWBLE_IRQ_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_RWBT_NMI_MAP
+ 0x238
+ 0x20
+ 0x00000010
+
+
+ APP_RWBT_NMI_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_RWBLE_NMI_MAP
+ 0x23C
+ 0x20
+ 0x00000010
+
+
+ APP_RWBLE_NMI_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_SLC0_INTR_MAP
+ 0x240
+ 0x20
+ 0x00000010
+
+
+ APP_SLC0_INTR_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_SLC1_INTR_MAP
+ 0x244
+ 0x20
+ 0x00000010
+
+
+ APP_SLC1_INTR_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_UHCI0_INTR_MAP
+ 0x248
+ 0x20
+ 0x00000010
+
+
+ APP_UHCI0_INTR_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_UHCI1_INTR_MAP
+ 0x24C
+ 0x20
+ 0x00000010
+
+
+ APP_UHCI1_INTR_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_TG_T0_LEVEL_INT_MAP
+ 0x250
+ 0x20
+ 0x00000010
+
+
+ APP_TG_T0_LEVEL_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_TG_T1_LEVEL_INT_MAP
+ 0x254
+ 0x20
+ 0x00000010
+
+
+ APP_TG_T1_LEVEL_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_TG_WDT_LEVEL_INT_MAP
+ 0x258
+ 0x20
+ 0x00000010
+
+
+ APP_TG_WDT_LEVEL_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_TG_LACT_LEVEL_INT_MAP
+ 0x25C
+ 0x20
+ 0x00000010
+
+
+ APP_TG_LACT_LEVEL_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_TG1_T0_LEVEL_INT_MAP
+ 0x260
+ 0x20
+ 0x00000010
+
+
+ APP_TG1_T0_LEVEL_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_TG1_T1_LEVEL_INT_MAP
+ 0x264
+ 0x20
+ 0x00000010
+
+
+ APP_TG1_T1_LEVEL_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_TG1_WDT_LEVEL_INT_MAP
+ 0x268
+ 0x20
+ 0x00000010
+
+
+ APP_TG1_WDT_LEVEL_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_TG1_LACT_LEVEL_INT_MAP
+ 0x26C
+ 0x20
+ 0x00000010
+
+
+ APP_TG1_LACT_LEVEL_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_GPIO_INTERRUPT_MAP
+ 0x270
+ 0x20
+ 0x00000010
+
+
+ APP_GPIO_INTERRUPT_APP_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_GPIO_INTERRUPT_NMI_MAP
+ 0x274
+ 0x20
+ 0x00000010
+
+
+ APP_GPIO_INTERRUPT_APP_NMI_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_CPU_INTR_FROM_CPU_0_MAP
+ 0x278
+ 0x20
+ 0x00000010
+
+
+ APP_CPU_INTR_FROM_CPU_0_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_CPU_INTR_FROM_CPU_1_MAP
+ 0x27C
+ 0x20
+ 0x00000010
+
+
+ APP_CPU_INTR_FROM_CPU_1_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_CPU_INTR_FROM_CPU_2_MAP
+ 0x280
+ 0x20
+ 0x00000010
+
+
+ APP_CPU_INTR_FROM_CPU_2_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_CPU_INTR_FROM_CPU_3_MAP
+ 0x284
+ 0x20
+ 0x00000010
+
+
+ APP_CPU_INTR_FROM_CPU_3_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_SPI_INTR_0_MAP
+ 0x288
+ 0x20
+ 0x00000010
+
+
+ APP_SPI_INTR_0_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_SPI_INTR_1_MAP
+ 0x28C
+ 0x20
+ 0x00000010
+
+
+ APP_SPI_INTR_1_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_SPI_INTR_2_MAP
+ 0x290
+ 0x20
+ 0x00000010
+
+
+ APP_SPI_INTR_2_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_SPI_INTR_3_MAP
+ 0x294
+ 0x20
+ 0x00000010
+
+
+ APP_SPI_INTR_3_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_I2S0_INT_MAP
+ 0x298
+ 0x20
+ 0x00000010
+
+
+ APP_I2S0_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_I2S1_INT_MAP
+ 0x29C
+ 0x20
+ 0x00000010
+
+
+ APP_I2S1_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_UART_INTR_MAP
+ 0x2A0
+ 0x20
+ 0x00000010
+
+
+ APP_UART_INTR_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_UART1_INTR_MAP
+ 0x2A4
+ 0x20
+ 0x00000010
+
+
+ APP_UART1_INTR_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_UART2_INTR_MAP
+ 0x2A8
+ 0x20
+ 0x00000010
+
+
+ APP_UART2_INTR_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_SDIO_HOST_INTERRUPT_MAP
+ 0x2AC
+ 0x20
+ 0x00000010
+
+
+ APP_SDIO_HOST_INTERRUPT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_EMAC_INT_MAP
+ 0x2B0
+ 0x20
+ 0x00000010
+
+
+ APP_EMAC_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_PWM0_INTR_MAP
+ 0x2B4
+ 0x20
+ 0x00000010
+
+
+ APP_PWM0_INTR_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_PWM1_INTR_MAP
+ 0x2B8
+ 0x20
+ 0x00000010
+
+
+ APP_PWM1_INTR_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_PWM2_INTR_MAP
+ 0x2BC
+ 0x20
+ 0x00000010
+
+
+ APP_PWM2_INTR_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_PWM3_INTR_MAP
+ 0x2C0
+ 0x20
+ 0x00000010
+
+
+ APP_PWM3_INTR_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_LEDC_INT_MAP
+ 0x2C4
+ 0x20
+ 0x00000010
+
+
+ APP_LEDC_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_EFUSE_INT_MAP
+ 0x2C8
+ 0x20
+ 0x00000010
+
+
+ APP_EFUSE_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_CAN_INT_MAP
+ 0x2CC
+ 0x20
+ 0x00000010
+
+
+ APP_CAN_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_RTC_CORE_INTR_MAP
+ 0x2D0
+ 0x20
+ 0x00000010
+
+
+ APP_RTC_CORE_INTR_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_RMT_INTR_MAP
+ 0x2D4
+ 0x20
+ 0x00000010
+
+
+ APP_RMT_INTR_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_PCNT_INTR_MAP
+ 0x2D8
+ 0x20
+ 0x00000010
+
+
+ APP_PCNT_INTR_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_I2C_EXT0_INTR_MAP
+ 0x2DC
+ 0x20
+ 0x00000010
+
+
+ APP_I2C_EXT0_INTR_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_I2C_EXT1_INTR_MAP
+ 0x2E0
+ 0x20
+ 0x00000010
+
+
+ APP_I2C_EXT1_INTR_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_RSA_INTR_MAP
+ 0x2E4
+ 0x20
+ 0x00000010
+
+
+ APP_RSA_INTR_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_SPI1_DMA_INT_MAP
+ 0x2E8
+ 0x20
+ 0x00000010
+
+
+ APP_SPI1_DMA_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_SPI2_DMA_INT_MAP
+ 0x2EC
+ 0x20
+ 0x00000010
+
+
+ APP_SPI2_DMA_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_SPI3_DMA_INT_MAP
+ 0x2F0
+ 0x20
+ 0x00000010
+
+
+ APP_SPI3_DMA_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_WDG_INT_MAP
+ 0x2F4
+ 0x20
+ 0x00000010
+
+
+ APP_WDG_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_TIMER_INT1_MAP
+ 0x2F8
+ 0x20
+ 0x00000010
+
+
+ APP_TIMER_INT1_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_TIMER_INT2_MAP
+ 0x2FC
+ 0x20
+ 0x00000010
+
+
+ APP_TIMER_INT2_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_TG_T0_EDGE_INT_MAP
+ 0x300
+ 0x20
+ 0x00000010
+
+
+ APP_TG_T0_EDGE_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_TG_T1_EDGE_INT_MAP
+ 0x304
+ 0x20
+ 0x00000010
+
+
+ APP_TG_T1_EDGE_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_TG_WDT_EDGE_INT_MAP
+ 0x308
+ 0x20
+ 0x00000010
+
+
+ APP_TG_WDT_EDGE_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_TG_LACT_EDGE_INT_MAP
+ 0x30C
+ 0x20
+ 0x00000010
+
+
+ APP_TG_LACT_EDGE_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_TG1_T0_EDGE_INT_MAP
+ 0x310
+ 0x20
+ 0x00000010
+
+
+ APP_TG1_T0_EDGE_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_TG1_T1_EDGE_INT_MAP
+ 0x314
+ 0x20
+ 0x00000010
+
+
+ APP_TG1_T1_EDGE_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_TG1_WDT_EDGE_INT_MAP
+ 0x318
+ 0x20
+ 0x00000010
+
+
+ APP_TG1_WDT_EDGE_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_TG1_LACT_EDGE_INT_MAP
+ 0x31C
+ 0x20
+ 0x00000010
+
+
+ APP_TG1_LACT_EDGE_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_MMU_IA_INT_MAP
+ 0x320
+ 0x20
+ 0x00000010
+
+
+ APP_MMU_IA_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_MPU_IA_INT_MAP
+ 0x324
+ 0x20
+ 0x00000010
+
+
+ APP_MPU_IA_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ APP_CACHE_IA_INT_MAP
+ 0x328
+ 0x20
+ 0x00000010
+
+
+ APP_CACHE_IA_INT_MAP
+ 0
+ 5
+ read-write
+
+
+
+
+ AHBLITE_MPU_TABLE_UART
+ 0x32C
+ 0x20
+
+
+ UART_ACCESS_GRANT_CONFIG
+ 0
+ 6
+ read-write
+
+
+
+
+ AHBLITE_MPU_TABLE_SPI1
+ 0x330
+ 0x20
+
+
+ SPI1_ACCESS_GRANT_CONFIG
+ 0
+ 6
+ read-write
+
+
+
+
+ AHBLITE_MPU_TABLE_SPI0
+ 0x334
+ 0x20
+
+
+ SPI0_ACCESS_GRANT_CONFIG
+ 0
+ 6
+ read-write
+
+
+
+
+ AHBLITE_MPU_TABLE_GPIO
+ 0x338
+ 0x20
+
+
+ GPIO_ACCESS_GRANT_CONFIG
+ 0
+ 6
+ read-write
+
+
+
+
+ AHBLITE_MPU_TABLE_FE2
+ 0x33C
+ 0x20
+
+
+ FE2_ACCESS_GRANT_CONFIG
+ 0
+ 6
+ read-write
+
+
+
+
+ AHBLITE_MPU_TABLE_FE
+ 0x340
+ 0x20
+
+
+ FE_ACCESS_GRANT_CONFIG
+ 0
+ 6
+ read-write
+
+
+
+
+ AHBLITE_MPU_TABLE_TIMER
+ 0x344
+ 0x20
+
+
+ TIMER_ACCESS_GRANT_CONFIG
+ 0
+ 6
+ read-write
+
+
+
+
+ AHBLITE_MPU_TABLE_RTC
+ 0x348
+ 0x20
+
+
+ RTC_ACCESS_GRANT_CONFIG
+ 0
+ 6
+ read-write
+
+
+
+
+ AHBLITE_MPU_TABLE_IO_MUX
+ 0x34C
+ 0x20
+
+
+ IOMUX_ACCESS_GRANT_CONFIG
+ 0
+ 6
+ read-write
+
+
+
+
+ AHBLITE_MPU_TABLE_WDG
+ 0x350
+ 0x20
+
+
+ WDG_ACCESS_GRANT_CONFIG
+ 0
+ 6
+ read-write
+
+
+
+
+ AHBLITE_MPU_TABLE_HINF
+ 0x354
+ 0x20
+
+
+ HINF_ACCESS_GRANT_CONFIG
+ 0
+ 6
+ read-write
+
+
+
+
+ AHBLITE_MPU_TABLE_UHCI1
+ 0x358
+ 0x20
+
+
+ UHCI1_ACCESS_GRANT_CONFIG
+ 0
+ 6
+ read-write
+
+
+
+
+ AHBLITE_MPU_TABLE_MISC
+ 0x35C
+ 0x20
+
+
+ MISC_ACCESS_GRANT_CONFIG
+ 0
+ 6
+ read-write
+
+
+
+
+ AHBLITE_MPU_TABLE_I2C
+ 0x360
+ 0x20
+
+
+ I2C_ACCESS_GRANT_CONFIG
+ 0
+ 6
+ read-write
+
+
+
+
+ AHBLITE_MPU_TABLE_I2S0
+ 0x364
+ 0x20
+
+
+ I2S0_ACCESS_GRANT_CONFIG
+ 0
+ 6
+ read-write
+
+
+
+
+ AHBLITE_MPU_TABLE_UART1
+ 0x368
+ 0x20
+
+
+ UART1_ACCESS_GRANT_CONFIG
+ 0
+ 6
+ read-write
+
+
+
+
+ AHBLITE_MPU_TABLE_BT
+ 0x36C
+ 0x20
+
+
+ BT_ACCESS_GRANT_CONFIG
+ 0
+ 6
+ read-write
+
+
+
+
+ AHBLITE_MPU_TABLE_BT_BUFFER
+ 0x370
+ 0x20
+
+
+ BTBUFFER_ACCESS_GRANT_CONFIG
+ 0
+ 6
+ read-write
+
+
+
+
+ AHBLITE_MPU_TABLE_I2C_EXT0
+ 0x374
+ 0x20
+
+
+ I2CEXT0_ACCESS_GRANT_CONFIG
+ 0
+ 6
+ read-write
+
+
+
+
+ AHBLITE_MPU_TABLE_UHCI0
+ 0x378
+ 0x20
+
+
+ UHCI0_ACCESS_GRANT_CONFIG
+ 0
+ 6
+ read-write
+
+
+
+
+ AHBLITE_MPU_TABLE_SLCHOST
+ 0x37C
+ 0x20
+
+
+ SLCHOST_ACCESS_GRANT_CONFIG
+ 0
+ 6
+ read-write
+
+
+
+
+ AHBLITE_MPU_TABLE_RMT
+ 0x380
+ 0x20
+
+
+ RMT_ACCESS_GRANT_CONFIG
+ 0
+ 6
+ read-write
+
+
+
+
+ AHBLITE_MPU_TABLE_PCNT
+ 0x384
+ 0x20
+
+
+ PCNT_ACCESS_GRANT_CONFIG
+ 0
+ 6
+ read-write
+
+
+
+
+ AHBLITE_MPU_TABLE_SLC
+ 0x388
+ 0x20
+
+
+ SLC_ACCESS_GRANT_CONFIG
+ 0
+ 6
+ read-write
+
+
+
+
+ AHBLITE_MPU_TABLE_LEDC
+ 0x38C
+ 0x20
+
+
+ LEDC_ACCESS_GRANT_CONFIG
+ 0
+ 6
+ read-write
+
+
+
+
+ AHBLITE_MPU_TABLE_EFUSE
+ 0x390
+ 0x20
+
+
+ EFUSE_ACCESS_GRANT_CONFIG
+ 0
+ 6
+ read-write
+
+
+
+
+ AHBLITE_MPU_TABLE_SPI_ENCRYPT
+ 0x394
+ 0x20
+
+
+ SPI_ENCRYPY_ACCESS_GRANT_CONFIG
+ 0
+ 6
+ read-write
+
+
+
+
+ AHBLITE_MPU_TABLE_BB
+ 0x398
+ 0x20
+
+
+ BB_ACCESS_GRANT_CONFIG
+ 0
+ 6
+ read-write
+
+
+
+
+ AHBLITE_MPU_TABLE_PWM0
+ 0x39C
+ 0x20
+
+
+ PWM0_ACCESS_GRANT_CONFIG
+ 0
+ 6
+ read-write
+
+
+
+
+ AHBLITE_MPU_TABLE_TIMERGROUP
+ 0x3A0
+ 0x20
+
+
+ TIMERGROUP_ACCESS_GRANT_CONFIG
+ 0
+ 6
+ read-write
+
+
+
+
+ AHBLITE_MPU_TABLE_TIMERGROUP1
+ 0x3A4
+ 0x20
+
+
+ TIMERGROUP1_ACCESS_GRANT_CONFIG
+ 0
+ 6
+ read-write
+
+
+
+
+ AHBLITE_MPU_TABLE_SPI2
+ 0x3A8
+ 0x20
+
+
+ SPI2_ACCESS_GRANT_CONFIG
+ 0
+ 6
+ read-write
+
+
+
+
+ AHBLITE_MPU_TABLE_SPI3
+ 0x3AC
+ 0x20
+
+
+ SPI3_ACCESS_GRANT_CONFIG
+ 0
+ 6
+ read-write
+
+
+
+
+ AHBLITE_MPU_TABLE_APB_CTRL
+ 0x3B0
+ 0x20
+
+
+ APBCTRL_ACCESS_GRANT_CONFIG
+ 0
+ 6
+ read-write
+
+
+
+
+ AHBLITE_MPU_TABLE_I2C_EXT1
+ 0x3B4
+ 0x20
+
+
+ I2CEXT1_ACCESS_GRANT_CONFIG
+ 0
+ 6
+ read-write
+
+
+
+
+ AHBLITE_MPU_TABLE_SDIO_HOST
+ 0x3B8
+ 0x20
+
+
+ SDIOHOST_ACCESS_GRANT_CONFIG
+ 0
+ 6
+ read-write
+
+
+
+
+ AHBLITE_MPU_TABLE_EMAC
+ 0x3BC
+ 0x20
+
+
+ EMAC_ACCESS_GRANT_CONFIG
+ 0
+ 6
+ read-write
+
+
+
+
+ AHBLITE_MPU_TABLE_CAN
+ 0x3C0
+ 0x20
+
+
+ CAN_ACCESS_GRANT_CONFIG
+ 0
+ 6
+ read-write
+
+
+
+
+ AHBLITE_MPU_TABLE_PWM1
+ 0x3C4
+ 0x20
+
+
+ PWM1_ACCESS_GRANT_CONFIG
+ 0
+ 6
+ read-write
+
+
+
+
+ AHBLITE_MPU_TABLE_I2S1
+ 0x3C8
+ 0x20
+
+
+ I2S1_ACCESS_GRANT_CONFIG
+ 0
+ 6
+ read-write
+
+
+
+
+ AHBLITE_MPU_TABLE_UART2
+ 0x3CC
+ 0x20
+
+
+ UART2_ACCESS_GRANT_CONFIG
+ 0
+ 6
+ read-write
+
+
+
+
+ AHBLITE_MPU_TABLE_PWM2
+ 0x3D0
+ 0x20
+
+
+ PWM2_ACCESS_GRANT_CONFIG
+ 0
+ 6
+ read-write
+
+
+
+
+ AHBLITE_MPU_TABLE_PWM3
+ 0x3D4
+ 0x20
+
+
+ PWM3_ACCESS_GRANT_CONFIG
+ 0
+ 6
+ read-write
+
+
+
+
+ AHBLITE_MPU_TABLE_RWBT
+ 0x3D8
+ 0x20
+
+
+ RWBT_ACCESS_GRANT_CONFIG
+ 0
+ 6
+ read-write
+
+
+
+
+ AHBLITE_MPU_TABLE_BTMAC
+ 0x3DC
+ 0x20
+
+
+ BTMAC_ACCESS_GRANT_CONFIG
+ 0
+ 6
+ read-write
+
+
+
+
+ AHBLITE_MPU_TABLE_WIFIMAC
+ 0x3E0
+ 0x20
+
+
+ WIFIMAC_ACCESS_GRANT_CONFIG
+ 0
+ 6
+ read-write
+
+
+
+
+ AHBLITE_MPU_TABLE_PWR
+ 0x3E4
+ 0x20
+
+
+ PWR_ACCESS_GRANT_CONFIG
+ 0
+ 6
+ read-write
+
+
+
+
+ MEM_ACCESS_DBUG0
+ 0x3E8
+ 0x20
+
+
+ PRO_ROM_MPU_AD
+ 0
+ 1
+ read-only
+
+
+ PRO_ROM_IA
+ 1
+ 1
+ read-only
+
+
+ APP_ROM_MPU_AD
+ 2
+ 1
+ read-only
+
+
+ APP_ROM_IA
+ 3
+ 1
+ read-only
+
+
+ SHARE_ROM_MPU_AD
+ 4
+ 2
+ read-only
+
+
+ SHARE_ROM_IA
+ 6
+ 4
+ read-only
+
+
+ INTERNAL_SRAM_MMU_AD
+ 10
+ 4
+ read-only
+
+
+ INTERNAL_SRAM_IA
+ 14
+ 12
+ read-only
+
+
+ INTERNAL_SRAM_MMU_MULTI_HIT
+ 26
+ 4
+ read-only
+
+
+
+
+ MEM_ACCESS_DBUG1
+ 0x3EC
+ 0x20
+
+
+ INTERNAL_SRAM_MMU_MISS
+ 0
+ 4
+ read-only
+
+
+ ARB_IA
+ 4
+ 2
+ read-only
+
+
+ PIDGEN_IA
+ 6
+ 2
+ read-only
+
+
+ AHB_ACCESS_DENY
+ 8
+ 1
+ read-only
+
+
+ AHBLITE_ACCESS_DENY
+ 9
+ 1
+ read-only
+
+
+ AHBLITE_IA
+ 10
+ 1
+ read-only
+
+
+
+
+ PRO_DCACHE_DBUG0
+ 0x3F0
+ 0x20
+
+
+ PRO_SLAVE_WDATA
+ 0
+ 1
+ read-write
+
+
+ PRO_CACHE_MMU_IA
+ 0
+ 1
+ read-only
+
+
+ PRO_CACHE_IA
+ 1
+ 6
+ read-only
+
+
+ PRO_CACHE_STATE
+ 7
+ 12
+ read-only
+
+
+ PRO_WR_BAK_TO_READ
+ 19
+ 1
+ read-only
+
+
+ PRO_TX_END
+ 20
+ 1
+ read-only
+
+
+ PRO_SLAVE_WR
+ 21
+ 1
+ read-only
+
+
+ PRO_SLAVE_WDATA_V
+ 22
+ 1
+ read-only
+
+
+ PRO_RX_END
+ 23
+ 1
+ read-only
+
+
+
+
+ PRO_DCACHE_DBUG1
+ 0x3F4
+ 0x20
+
+
+ PRO_CTAG_RAM_RDATA
+ 0
+ 32
+ read-only
+
+
+
+
+ PRO_DCACHE_DBUG2
+ 0x3F8
+ 0x20
+
+
+ PRO_CACHE_VADDR
+ 0
+ 27
+ read-only
+
+
+
+
+ PRO_DCACHE_DBUG3
+ 0x3FC
+ 0x20
+
+
+ PRO_MMU_RDATA
+ 0
+ 9
+ read-only
+
+
+ PRO_CPU_DISABLED_CACHE_IA
+ 9
+ 6
+ read-only
+
+
+ PRO_CPU_DISABLED_CACHE_IA_OPPOSITE
+ 9
+ 1
+ read-write
+
+
+ PRO_CPU_DISABLED_CACHE_IA_DRAM1
+ 10
+ 1
+ read-write
+
+
+ PRO_CPU_DISABLED_CACHE_IA_IROM0
+ 11
+ 1
+ read-write
+
+
+ PRO_CPU_DISABLED_CACHE_IA_IRAM1
+ 12
+ 1
+ read-write
+
+
+ PRO_CPU_DISABLED_CACHE_IA_IRAM0
+ 13
+ 1
+ read-write
+
+
+ PRO_CPU_DISABLED_CACHE_IA_DROM0
+ 14
+ 1
+ read-write
+
+
+ PRO_CACHE_IRAM0_PID_ERROR
+ 15
+ 1
+ read-only
+
+
+
+
+ PRO_DCACHE_DBUG4
+ 0x400
+ 0x20
+
+
+ PRO_DRAM1ADDR0_IA
+ 0
+ 20
+ read-only
+
+
+
+
+ PRO_DCACHE_DBUG5
+ 0x404
+ 0x20
+
+
+ PRO_DROM0ADDR0_IA
+ 0
+ 20
+ read-only
+
+
+
+
+ PRO_DCACHE_DBUG6
+ 0x408
+ 0x20
+
+
+ PRO_IRAM0ADDR_IA
+ 0
+ 20
+ read-only
+
+
+
+
+ PRO_DCACHE_DBUG7
+ 0x40C
+ 0x20
+
+
+ PRO_IRAM1ADDR_IA
+ 0
+ 20
+ read-only
+
+
+
+
+ PRO_DCACHE_DBUG8
+ 0x410
+ 0x20
+
+
+ PRO_IROM0ADDR_IA
+ 0
+ 20
+ read-only
+
+
+
+
+ PRO_DCACHE_DBUG9
+ 0x414
+ 0x20
+
+
+ PRO_OPSDRAMADDR_IA
+ 0
+ 20
+ read-only
+
+
+
+
+ APP_DCACHE_DBUG0
+ 0x418
+ 0x20
+
+
+ APP_SLAVE_WDATA
+ 0
+ 1
+ read-write
+
+
+ APP_CACHE_MMU_IA
+ 0
+ 1
+ read-only
+
+
+ APP_CACHE_IA
+ 1
+ 6
+ read-only
+
+
+ APP_CACHE_STATE
+ 7
+ 12
+ read-only
+
+
+ APP_WR_BAK_TO_READ
+ 19
+ 1
+ read-only
+
+
+ APP_TX_END
+ 20
+ 1
+ read-only
+
+
+ APP_SLAVE_WR
+ 21
+ 1
+ read-only
+
+
+ APP_SLAVE_WDATA_V
+ 22
+ 1
+ read-only
+
+
+ APP_RX_END
+ 23
+ 1
+ read-only
+
+
+
+
+ APP_DCACHE_DBUG1
+ 0x41C
+ 0x20
+
+
+ APP_CTAG_RAM_RDATA
+ 0
+ 32
+ read-only
+
+
+
+
+ APP_DCACHE_DBUG2
+ 0x420
+ 0x20
+
+
+ APP_CACHE_VADDR
+ 0
+ 27
+ read-only
+
+
+
+
+ APP_DCACHE_DBUG3
+ 0x424
+ 0x20
+
+
+ APP_MMU_RDATA
+ 0
+ 9
+ read-only
+
+
+ APP_CPU_DISABLED_CACHE_IA
+ 9
+ 6
+ read-only
+
+
+ APP_CPU_DISABLED_CACHE_IA_OPPOSITE
+ 9
+ 1
+ read-write
+
+
+ APP_CPU_DISABLED_CACHE_IA_DRAM1
+ 10
+ 1
+ read-write
+
+
+ APP_CPU_DISABLED_CACHE_IA_IROM0
+ 11
+ 1
+ read-write
+
+
+ APP_CPU_DISABLED_CACHE_IA_IRAM1
+ 12
+ 1
+ read-write
+
+
+ APP_CPU_DISABLED_CACHE_IA_IRAM0
+ 13
+ 1
+ read-write
+
+
+ APP_CPU_DISABLED_CACHE_IA_DROM0
+ 14
+ 1
+ read-write
+
+
+ APP_CACHE_IRAM0_PID_ERROR
+ 15
+ 1
+ read-only
+
+
+
+
+ APP_DCACHE_DBUG4
+ 0x428
+ 0x20
+
+
+ APP_DRAM1ADDR0_IA
+ 0
+ 20
+ read-only
+
+
+
+
+ APP_DCACHE_DBUG5
+ 0x42C
+ 0x20
+
+
+ APP_DROM0ADDR0_IA
+ 0
+ 20
+ read-only
+
+
+
+
+ APP_DCACHE_DBUG6
+ 0x430
+ 0x20
+
+
+ APP_IRAM0ADDR_IA
+ 0
+ 20
+ read-only
+
+
+
+
+ APP_DCACHE_DBUG7
+ 0x434
+ 0x20
+
+
+ APP_IRAM1ADDR_IA
+ 0
+ 20
+ read-only
+
+
+
+
+ APP_DCACHE_DBUG8
+ 0x438
+ 0x20
+
+
+ APP_IROM0ADDR_IA
+ 0
+ 20
+ read-only
+
+
+
+
+ APP_DCACHE_DBUG9
+ 0x43C
+ 0x20
+
+
+ APP_OPSDRAMADDR_IA
+ 0
+ 20
+ read-only
+
+
+
+
+ PRO_CPU_RECORD_CTRL
+ 0x440
+ 0x20
+ 0x00000100
+
+
+ PRO_CPU_RECORD_ENABLE
+ 0
+ 1
+ read-write
+
+
+ PRO_CPU_RECORD_DISABLE
+ 4
+ 1
+ read-write
+
+
+ PRO_CPU_PDEBUG_ENABLE
+ 8
+ 1
+ read-write
+
+
+
+
+ PRO_CPU_RECORD_STATUS
+ 0x444
+ 0x20
+
+
+ PRO_CPU_RECORDING
+ 0
+ 1
+ read-only
+
+
+
+
+ PRO_CPU_RECORD_PID
+ 0x448
+ 0x20
+
+
+ RECORD_PRO_PID
+ 0
+ 3
+ read-only
+
+
+
+
+ PRO_CPU_RECORD_PDEBUGINST
+ 0x44C
+ 0x20
+
+
+ RECORD_PRO_PDEBUGINST
+ 0
+ 32
+ read-only
+
+
+ RECORD_PDEBUGINST_SZ
+ 0
+ 8
+ read-write
+
+
+ RECORD_PDEBUGINST_ISRC
+ 12
+ 3
+ read-write
+
+
+ RECORD_PDEBUGINST_LOOP_REP
+ 20
+ 1
+ read-write
+
+
+ RECORD_PDEBUGINST_LOOP
+ 21
+ 1
+ read-write
+
+
+ RECORD_PDEBUGINST_CINTL
+ 24
+ 4
+ read-write
+
+
+
+
+ PRO_CPU_RECORD_PDEBUGSTATUS
+ 0x450
+ 0x20
+
+
+ RECORD_PRO_PDEBUGSTATUS
+ 0
+ 8
+ read-only
+
+
+ RECORD_PDEBUGSTATUS_BBCAUSE
+ 0
+ 6
+ read-write
+
+
+ RECORD_PDEBUGSTATUS_INSNTYPE
+ 0
+ 6
+ read-write
+
+
+
+
+ PRO_CPU_RECORD_PDEBUGDATA
+ 0x454
+ 0x20
+
+
+ RECORD_PRO_PDEBUGDATA
+ 0
+ 32
+ read-only
+
+
+ RECORD_PDEBUGDATA_DEP_OTHER
+ 0
+ 1
+ read-write
+
+
+ RECORD_PDEBUGDATA_EXCVEC
+ 0
+ 5
+ read-write
+
+
+ RECORD_PDEBUGDATA_INSNTYPE_SR
+ 0
+ 8
+ read-write
+
+
+ RECORD_PDEBUGDATA_INSNTYPE_RER
+ 0
+ 1
+ read-write
+
+
+ RECORD_PDEBUGDATA_STALL_BUFF
+ 1
+ 1
+ read-write
+
+
+ RECORD_PDEBUGDATA_INSNTYPE_WER
+ 1
+ 1
+ read-write
+
+
+ RECORD_PDEBUGDATA_STALL_BUFFCONFL
+ 2
+ 1
+ read-write
+
+
+ RECORD_PDEBUGDATA_INSNTYPE_ER
+ 2
+ 12
+ read-write
+
+
+ RECORD_PDEBUGDATA_STALL_DCM
+ 3
+ 1
+ read-write
+
+
+ RECORD_PDEBUGDATA_STALL_LSU
+ 4
+ 1
+ read-write
+
+
+ RECORD_PDEBUGDATA_STALL_ICM
+ 6
+ 1
+ read-write
+
+
+ RECORD_PDEBUGDATA_STALL_IRAMBUSY
+ 7
+ 1
+ read-write
+
+
+ RECORD_PDEBUGDATA_DEP_LSU
+ 8
+ 1
+ read-write
+
+
+ RECORD_PDEBUGDATA_STALL_IPIF
+ 8
+ 1
+ read-write
+
+
+ RECORD_PDEBUGDATA_INSNTYPE_RSR
+ 8
+ 1
+ read-write
+
+
+ RECORD_PDEBUGDATA_STALL_TIE
+ 9
+ 1
+ read-write
+
+
+ RECORD_PDEBUGDATA_INSNTYPE_WSR
+ 9
+ 1
+ read-write
+
+
+ RECORD_PDEBUGDATA_STALL_RUN
+ 10
+ 1
+ read-write
+
+
+ RECORD_PDEBUGDATA_INSNTYPE_XSR
+ 10
+ 1
+ read-write
+
+
+ RECORD_PDEBUGDATA_DEP_STR
+ 11
+ 1
+ read-write
+
+
+ RECORD_PDEBUGDATA_DEP
+ 12
+ 1
+ read-write
+
+
+ RECORD_PDEBUGDATA_STALL_BPIFETCH
+ 12
+ 1
+ read-write
+
+
+ RECORD_PDEBUGDATA_STALL_L32R
+ 13
+ 1
+ read-write
+
+
+ RECORD_PDEBUGDATA_STALL_LSPROC
+ 14
+ 1
+ read-write
+
+
+ RECORD_PDEBUGDATA_STALL_BPLOAD
+ 15
+ 1
+ read-write
+
+
+ RECORD_PDEBUGDATA_DEP_MEMW
+ 16
+ 1
+ read-write
+
+
+ RECORD_PDEBUGDATA_EXCCAUSE
+ 16
+ 6
+ read-write
+
+
+ RECORD_PDEBUGDATA_STALL_BANKCONFL
+ 16
+ 1
+ read-write
+
+
+ RECORD_PDEBUGDATA_DEP_HALT
+ 17
+ 1
+ read-write
+
+
+ RECORD_PDEBUGDATA_STALL_ITERMUL
+ 18
+ 1
+ read-write
+
+
+ RECORD_PDEBUGDATA_STALL_ITERDIV
+ 19
+ 1
+ read-write
+
+
+
+
+ PRO_CPU_RECORD_PDEBUGPC
+ 0x458
+ 0x20
+
+
+ RECORD_PRO_PDEBUGPC
+ 0
+ 32
+ read-only
+
+
+
+
+ PRO_CPU_RECORD_PDEBUGLS0STAT
+ 0x45C
+ 0x20
+
+
+ RECORD_PRO_PDEBUGLS0STAT
+ 0
+ 32
+ read-only
+
+
+ RECORD_PDEBUGLS0STAT_TYPE
+ 0
+ 4
+ read-write
+
+
+ RECORD_PDEBUGLS0STAT_SZ
+ 4
+ 4
+ read-write
+
+
+ RECORD_PDEBUGLS0STAT_DTLBM
+ 8
+ 1
+ read-write
+
+
+ RECORD_PDEBUGLS0STAT_DCM
+ 9
+ 1
+ read-write
+
+
+ RECORD_PDEBUGLS0STAT_DCH
+ 10
+ 1
+ read-write
+
+
+ RECORD_PDEBUGLS0STAT_UC
+ 12
+ 1
+ read-write
+
+
+ RECORD_PDEBUGLS0STAT_WB
+ 13
+ 1
+ read-write
+
+
+ RECORD_PDEBUGLS0STAT_COH
+ 16
+ 1
+ read-write
+
+
+ RECORD_PDEBUGLS0STAT_STCOH
+ 17
+ 2
+ read-write
+
+
+ RECORD_PDEBUGLS0STAT_TGT
+ 20
+ 4
+ read-write
+
+
+
+
+ PRO_CPU_RECORD_PDEBUGLS0ADDR
+ 0x460
+ 0x20
+
+
+ RECORD_PRO_PDEBUGLS0ADDR
+ 0
+ 32
+ read-only
+
+
+
+
+ PRO_CPU_RECORD_PDEBUGLS0DATA
+ 0x464
+ 0x20
+
+
+ RECORD_PRO_PDEBUGLS0DATA
+ 0
+ 32
+ read-only
+
+
+
+
+ APP_CPU_RECORD_CTRL
+ 0x468
+ 0x20
+ 0x00000100
+
+
+ APP_CPU_RECORD_ENABLE
+ 0
+ 1
+ read-write
+
+
+ APP_CPU_RECORD_DISABLE
+ 4
+ 1
+ read-write
+
+
+ APP_CPU_PDEBUG_ENABLE
+ 8
+ 1
+ read-write
+
+
+
+
+ APP_CPU_RECORD_STATUS
+ 0x46C
+ 0x20
+
+
+ APP_CPU_RECORDING
+ 0
+ 1
+ read-only
+
+
+
+
+ APP_CPU_RECORD_PID
+ 0x470
+ 0x20
+
+
+ RECORD_APP_PID
+ 0
+ 3
+ read-only
+
+
+
+
+ APP_CPU_RECORD_PDEBUGINST
+ 0x474
+ 0x20
+
+
+ RECORD_APP_PDEBUGINST
+ 0
+ 32
+ read-only
+
+
+
+
+ APP_CPU_RECORD_PDEBUGSTATUS
+ 0x478
+ 0x20
+
+
+ RECORD_APP_PDEBUGSTATUS
+ 0
+ 8
+ read-only
+
+
+
+
+ APP_CPU_RECORD_PDEBUGDATA
+ 0x47C
+ 0x20
+
+
+ RECORD_APP_PDEBUGDATA
+ 0
+ 32
+ read-only
+
+
+
+
+ APP_CPU_RECORD_PDEBUGPC
+ 0x480
+ 0x20
+
+
+ RECORD_APP_PDEBUGPC
+ 0
+ 32
+ read-only
+
+
+
+
+ APP_CPU_RECORD_PDEBUGLS0STAT
+ 0x484
+ 0x20
+
+
+ RECORD_APP_PDEBUGLS0STAT
+ 0
+ 32
+ read-only
+
+
+
+
+ APP_CPU_RECORD_PDEBUGLS0ADDR
+ 0x488
+ 0x20
+
+
+ RECORD_APP_PDEBUGLS0ADDR
+ 0
+ 32
+ read-only
+
+
+
+
+ APP_CPU_RECORD_PDEBUGLS0DATA
+ 0x48C
+ 0x20
+
+
+ RECORD_APP_PDEBUGLS0DATA
+ 0
+ 32
+ read-only
+
+
+
+
+ RSA_PD_CTRL
+ 0x490
+ 0x20
+
+
+ RSA_PD
+ 0
+ 1
+ read-write
+
+
+
+
+ ROM_MPU_TABLE0
+ 0x494
+ 0x20
+ 0x00000001
+
+
+ ROM_MPU_TABLE0
+ 0
+ 2
+ read-write
+
+
+
+
+ ROM_MPU_TABLE1
+ 0x498
+ 0x20
+ 0x00000001
+
+
+ ROM_MPU_TABLE1
+ 0
+ 2
+ read-write
+
+
+
+
+ ROM_MPU_TABLE2
+ 0x49C
+ 0x20
+ 0x00000001
+
+
+ ROM_MPU_TABLE2
+ 0
+ 2
+ read-write
+
+
+
+
+ ROM_MPU_TABLE3
+ 0x4A0
+ 0x20
+ 0x00000001
+
+
+ ROM_MPU_TABLE3
+ 0
+ 2
+ read-write
+
+
+
+
+ SHROM_MPU_TABLE0
+ 0x4A4
+ 0x20
+ 0x00000001
+
+
+ SHROM_MPU_TABLE0
+ 0
+ 2
+ read-write
+
+
+
+
+ SHROM_MPU_TABLE1
+ 0x4A8
+ 0x20
+ 0x00000001
+
+
+ SHROM_MPU_TABLE1
+ 0
+ 2
+ read-write
+
+
+
+
+ SHROM_MPU_TABLE2
+ 0x4AC
+ 0x20
+ 0x00000001
+
+
+ SHROM_MPU_TABLE2
+ 0
+ 2
+ read-write
+
+
+
+
+ SHROM_MPU_TABLE3
+ 0x4B0
+ 0x20
+ 0x00000001
+
+
+ SHROM_MPU_TABLE3
+ 0
+ 2
+ read-write
+
+
+
+
+ SHROM_MPU_TABLE4
+ 0x4B4
+ 0x20
+ 0x00000001
+
+
+ SHROM_MPU_TABLE4
+ 0
+ 2
+ read-write
+
+
+
+
+ SHROM_MPU_TABLE5
+ 0x4B8
+ 0x20
+ 0x00000001
+
+
+ SHROM_MPU_TABLE5
+ 0
+ 2
+ read-write
+
+
+
+
+ SHROM_MPU_TABLE6
+ 0x4BC
+ 0x20
+ 0x00000001
+
+
+ SHROM_MPU_TABLE6
+ 0
+ 2
+ read-write
+
+
+
+
+ SHROM_MPU_TABLE7
+ 0x4C0
+ 0x20
+ 0x00000001
+
+
+ SHROM_MPU_TABLE7
+ 0
+ 2
+ read-write
+
+
+
+
+ SHROM_MPU_TABLE8
+ 0x4C4
+ 0x20
+ 0x00000001
+
+
+ SHROM_MPU_TABLE8
+ 0
+ 2
+ read-write
+
+
+
+
+ SHROM_MPU_TABLE9
+ 0x4C8
+ 0x20
+ 0x00000001
+
+
+ SHROM_MPU_TABLE9
+ 0
+ 2
+ read-write
+
+
+
+
+ SHROM_MPU_TABLE10
+ 0x4CC
+ 0x20
+ 0x00000001
+
+
+ SHROM_MPU_TABLE10
+ 0
+ 2
+ read-write
+
+
+
+
+ SHROM_MPU_TABLE11
+ 0x4D0
+ 0x20
+ 0x00000001
+
+
+ SHROM_MPU_TABLE11
+ 0
+ 2
+ read-write
+
+
+
+
+ SHROM_MPU_TABLE12
+ 0x4D4
+ 0x20
+ 0x00000001
+
+
+ SHROM_MPU_TABLE12
+ 0
+ 2
+ read-write
+
+
+
+
+ SHROM_MPU_TABLE13
+ 0x4D8
+ 0x20
+ 0x00000001
+
+
+ SHROM_MPU_TABLE13
+ 0
+ 2
+ read-write
+
+
+
+
+ SHROM_MPU_TABLE14
+ 0x4DC
+ 0x20
+ 0x00000001
+
+
+ SHROM_MPU_TABLE14
+ 0
+ 2
+ read-write
+
+
+
+
+ SHROM_MPU_TABLE15
+ 0x4E0
+ 0x20
+ 0x00000001
+
+
+ SHROM_MPU_TABLE15
+ 0
+ 2
+ read-write
+
+
+
+
+ SHROM_MPU_TABLE16
+ 0x4E4
+ 0x20
+ 0x00000001
+
+
+ SHROM_MPU_TABLE16
+ 0
+ 2
+ read-write
+
+
+
+
+ SHROM_MPU_TABLE17
+ 0x4E8
+ 0x20
+ 0x00000001
+
+
+ SHROM_MPU_TABLE17
+ 0
+ 2
+ read-write
+
+
+
+
+ SHROM_MPU_TABLE18
+ 0x4EC
+ 0x20
+ 0x00000001
+
+
+ SHROM_MPU_TABLE18
+ 0
+ 2
+ read-write
+
+
+
+
+ SHROM_MPU_TABLE19
+ 0x4F0
+ 0x20
+ 0x00000001
+
+
+ SHROM_MPU_TABLE19
+ 0
+ 2
+ read-write
+
+
+
+
+ SHROM_MPU_TABLE20
+ 0x4F4
+ 0x20
+ 0x00000001
+
+
+ SHROM_MPU_TABLE20
+ 0
+ 2
+ read-write
+
+
+
+
+ SHROM_MPU_TABLE21
+ 0x4F8
+ 0x20
+ 0x00000001
+
+
+ SHROM_MPU_TABLE21
+ 0
+ 2
+ read-write
+
+
+
+
+ SHROM_MPU_TABLE22
+ 0x4FC
+ 0x20
+ 0x00000001
+
+
+ SHROM_MPU_TABLE22
+ 0
+ 2
+ read-write
+
+
+
+
+ SHROM_MPU_TABLE23
+ 0x500
+ 0x20
+ 0x00000001
+
+
+ SHROM_MPU_TABLE23
+ 0
+ 2
+ read-write
+
+
+
+
+ IMMU_TABLE0
+ 0x504
+ 0x20
+
+
+ IMMU_TABLE0
+ 0
+ 7
+ read-write
+
+
+
+
+ IMMU_TABLE1
+ 0x508
+ 0x20
+ 0x00000001
+
+
+ IMMU_TABLE1
+ 0
+ 7
+ read-write
+
+
+
+
+ IMMU_TABLE2
+ 0x50C
+ 0x20
+ 0x00000002
+
+
+ IMMU_TABLE2
+ 0
+ 7
+ read-write
+
+
+
+
+ IMMU_TABLE3
+ 0x510
+ 0x20
+ 0x00000003
+
+
+ IMMU_TABLE3
+ 0
+ 7
+ read-write
+
+
+
+
+ IMMU_TABLE4
+ 0x514
+ 0x20
+ 0x00000004
+
+
+ IMMU_TABLE4
+ 0
+ 7
+ read-write
+
+
+
+
+ IMMU_TABLE5
+ 0x518
+ 0x20
+ 0x00000005
+
+
+ IMMU_TABLE5
+ 0
+ 7
+ read-write
+
+
+
+
+ IMMU_TABLE6
+ 0x51C
+ 0x20
+ 0x00000006
+
+
+ IMMU_TABLE6
+ 0
+ 7
+ read-write
+
+
+
+
+ IMMU_TABLE7
+ 0x520
+ 0x20
+ 0x00000007
+
+
+ IMMU_TABLE7
+ 0
+ 7
+ read-write
+
+
+
+
+ IMMU_TABLE8
+ 0x524
+ 0x20
+ 0x00000008
+
+
+ IMMU_TABLE8
+ 0
+ 7
+ read-write
+
+
+
+
+ IMMU_TABLE9
+ 0x528
+ 0x20
+ 0x00000009
+
+
+ IMMU_TABLE9
+ 0
+ 7
+ read-write
+
+
+
+
+ IMMU_TABLE10
+ 0x52C
+ 0x20
+ 0x0000000A
+
+
+ IMMU_TABLE10
+ 0
+ 7
+ read-write
+
+
+
+
+ IMMU_TABLE11
+ 0x530
+ 0x20
+ 0x0000000B
+
+
+ IMMU_TABLE11
+ 0
+ 7
+ read-write
+
+
+
+
+ IMMU_TABLE12
+ 0x534
+ 0x20
+ 0x0000000C
+
+
+ IMMU_TABLE12
+ 0
+ 7
+ read-write
+
+
+
+
+ IMMU_TABLE13
+ 0x538
+ 0x20
+ 0x0000000D
+
+
+ IMMU_TABLE13
+ 0
+ 7
+ read-write
+
+
+
+
+ IMMU_TABLE14
+ 0x53C
+ 0x20
+ 0x0000000E
+
+
+ IMMU_TABLE14
+ 0
+ 7
+ read-write
+
+
+
+
+ IMMU_TABLE15
+ 0x540
+ 0x20
+ 0x0000000F
+
+
+ IMMU_TABLE15
+ 0
+ 7
+ read-write
+
+
+
+
+ DMMU_TABLE0
+ 0x544
+ 0x20
+
+
+ DMMU_TABLE0
+ 0
+ 7
+ read-write
+
+
+
+
+ DMMU_TABLE1
+ 0x548
+ 0x20
+ 0x00000001
+
+
+ DMMU_TABLE1
+ 0
+ 7
+ read-write
+
+
+
+
+ DMMU_TABLE2
+ 0x54C
+ 0x20
+ 0x00000002
+
+
+ DMMU_TABLE2
+ 0
+ 7
+ read-write
+
+
+
+
+ DMMU_TABLE3
+ 0x550
+ 0x20
+ 0x00000003
+
+
+ DMMU_TABLE3
+ 0
+ 7
+ read-write
+
+
+
+
+ DMMU_TABLE4
+ 0x554
+ 0x20
+ 0x00000004
+
+
+ DMMU_TABLE4
+ 0
+ 7
+ read-write
+
+
+
+
+ DMMU_TABLE5
+ 0x558
+ 0x20
+ 0x00000005
+
+
+ DMMU_TABLE5
+ 0
+ 7
+ read-write
+
+
+
+
+ DMMU_TABLE6
+ 0x55C
+ 0x20
+ 0x00000006
+
+
+ DMMU_TABLE6
+ 0
+ 7
+ read-write
+
+
+
+
+ DMMU_TABLE7
+ 0x560
+ 0x20
+ 0x00000007
+
+
+ DMMU_TABLE7
+ 0
+ 7
+ read-write
+
+
+
+
+ DMMU_TABLE8
+ 0x564
+ 0x20
+ 0x00000008
+
+
+ DMMU_TABLE8
+ 0
+ 7
+ read-write
+
+
+
+
+ DMMU_TABLE9
+ 0x568
+ 0x20
+ 0x00000009
+
+
+ DMMU_TABLE9
+ 0
+ 7
+ read-write
+
+
+
+
+ DMMU_TABLE10
+ 0x56C
+ 0x20
+ 0x0000000A
+
+
+ DMMU_TABLE10
+ 0
+ 7
+ read-write
+
+
+
+
+ DMMU_TABLE11
+ 0x570
+ 0x20
+ 0x0000000B
+
+
+ DMMU_TABLE11
+ 0
+ 7
+ read-write
+
+
+
+
+ DMMU_TABLE12
+ 0x574
+ 0x20
+ 0x0000000C
+
+
+ DMMU_TABLE12
+ 0
+ 7
+ read-write
+
+
+
+
+ DMMU_TABLE13
+ 0x578
+ 0x20
+ 0x0000000D
+
+
+ DMMU_TABLE13
+ 0
+ 7
+ read-write
+
+
+
+
+ DMMU_TABLE14
+ 0x57C
+ 0x20
+ 0x0000000E
+
+
+ DMMU_TABLE14
+ 0
+ 7
+ read-write
+
+
+
+
+ DMMU_TABLE15
+ 0x580
+ 0x20
+ 0x0000000F
+
+
+ DMMU_TABLE15
+ 0
+ 7
+ read-write
+
+
+
+
+ PRO_INTRUSION_CTRL
+ 0x584
+ 0x20
+ 0x00000001
+
+
+ PRO_INTRUSION_RECORD_RESET_N
+ 0
+ 1
+ read-write
+
+
+
+
+ PRO_INTRUSION_STATUS
+ 0x588
+ 0x20
+
+
+ PRO_INTRUSION_RECORD
+ 0
+ 4
+ read-only
+
+
+
+
+ APP_INTRUSION_CTRL
+ 0x58C
+ 0x20
+ 0x00000001
+
+
+ APP_INTRUSION_RECORD_RESET_N
+ 0
+ 1
+ read-write
+
+
+
+
+ APP_INTRUSION_STATUS
+ 0x590
+ 0x20
+
+
+ APP_INTRUSION_RECORD
+ 0
+ 4
+ read-only
+
+
+
+
+ FRONT_END_MEM_PD
+ 0x594
+ 0x20
+ 0x00000005
+
+
+ AGC_MEM_FORCE_PU
+ 0
+ 1
+ read-write
+
+
+ AGC_MEM_FORCE_PD
+ 1
+ 1
+ read-write
+
+
+ PBUS_MEM_FORCE_PU
+ 2
+ 1
+ read-write
+
+
+ PBUS_MEM_FORCE_PD
+ 3
+ 1
+ read-write
+
+
+
+
+ MMU_IA_INT_EN
+ 0x598
+ 0x20
+
+
+ MMU_IA_INT_EN
+ 0
+ 24
+ read-write
+
+
+
+
+ MPU_IA_INT_EN
+ 0x59C
+ 0x20
+
+
+ MPU_IA_INT_EN
+ 0
+ 17
+ read-write
+
+
+
+
+ CACHE_IA_INT_EN
+ 0x5A0
+ 0x20
+
+
+ CACHE_IA_INT_EN
+ Interrupt enable bits for various invalid cache access reasons
+ 0
+ 28
+ read-write
+
+
+ CACHE_IA_INT_APP_DROM0
+ APP CPU invalid access to DROM0 when cache is disabled
+ 0
+ 1
+ read-write
+
+
+ CACHE_IA_INT_APP_IRAM0
+ APP CPU invalid access to IRAM0 when cache is disabled
+ 1
+ 1
+ read-write
+
+
+ CACHE_IA_INT_APP_IRAM1
+ APP CPU invalid access to IRAM1 when cache is disabled
+ 2
+ 1
+ read-write
+
+
+ CACHE_IA_INT_APP_IROM0
+ APP CPU invalid access to IROM0 when cache is disabled
+ 3
+ 1
+ read-write
+
+
+ CACHE_IA_INT_APP_DRAM1
+ APP CPU invalid access to DRAM1 when cache is disabled
+ 4
+ 1
+ read-write
+
+
+ CACHE_IA_INT_APP_OPPOSITE
+ APP CPU invalid access to APP CPU cache when cache disabled
+ 5
+ 1
+ read-write
+
+
+ CACHE_IA_INT_PRO_DROM0
+ PRO CPU invalid access to DROM0 when cache is disabled
+ 14
+ 1
+ read-write
+
+
+ CACHE_IA_INT_PRO_IRAM0
+ PRO CPU invalid access to IRAM0 when cache is disabled
+ 15
+ 1
+ read-write
+
+
+ CACHE_IA_INT_PRO_IRAM1
+ PRO CPU invalid access to IRAM1 when cache is disabled
+ 16
+ 1
+ read-write
+
+
+ CACHE_IA_INT_PRO_IROM0
+ PRO CPU invalid access to IROM0 when cache is disabled
+ 17
+ 1
+ read-write
+
+
+ CACHE_IA_INT_PRO_DRAM1
+ PRO CPU invalid access to DRAM1 when cache is disabled
+ 18
+ 1
+ read-write
+
+
+ CACHE_IA_INT_PRO_OPPOSITE
+ PRO CPU invalid access to APP CPU cache when cache disabled
+ 19
+ 1
+ read-write
+
+
+
+
+ SECURE_BOOT_CTRL
+ 0x5A4
+ 0x20
+
+
+ SW_BOOTLOADER_SEL
+ 0
+ 1
+ read-write
+
+
+
+
+ SPI_DMA_CHAN_SEL
+ 0x5A8
+ 0x20
+
+
+ SPI1_DMA_CHAN_SEL
+ 0
+ 2
+ read-write
+
+
+ SPI2_DMA_CHAN_SEL
+ 2
+ 2
+ read-write
+
+
+ SPI3_DMA_CHAN_SEL
+ 4
+ 2
+ read-write
+
+
+
+
+ PRO_VECBASE_CTRL
+ 0x5AC
+ 0x20
+
+
+ PRO_OUT_VECBASE_SEL
+ 0
+ 2
+ read-write
+
+
+
+
+ PRO_VECBASE_SET
+ 0x5B0
+ 0x20
+
+
+ PRO_OUT_VECBASE
+ 0
+ 22
+ read-write
+
+
+
+
+ APP_VECBASE_CTRL
+ 0x5B4
+ 0x20
+
+
+ APP_OUT_VECBASE_SEL
+ 0
+ 2
+ read-write
+
+
+
+
+ APP_VECBASE_SET
+ 0x5B8
+ 0x20
+
+
+ APP_OUT_VECBASE
+ 0
+ 22
+ read-write
+
+
+
+
+ DATE
+ 0xFFC
+ 0x20
+ 0x01605190
+
+
+ DATE
+ 0
+ 28
+ read-write
+
+
+
+
+
+
+ EFUSE
+ eFuse Controller
+ EFUSE
+ 0x3FF5A000
+
+ 0x0
+ 0x124
+ registers
+
+
+ EFUSE
+ 44
+
+
+
+ BLK0_RDATA0
+ 0x0
+ 0x20
+
+
+ RD_EFUSE_WR_DIS
+ read for efuse_wr_disable
+ 0
+ 16
+ read-only
+
+
+ RD_EFUSE_RD_DIS
+ read for efuse_rd_disable
+ 16
+ 4
+ read-only
+
+
+ RD_FLASH_CRYPT_CNT
+ read for flash_crypt_cnt
+ 20
+ 7
+ read-only
+
+
+
+
+ BLK0_RDATA1
+ 0x4
+ 0x20
+
+
+ RD_WIFI_MAC_CRC_LOW
+ read for low 32bit WIFI_MAC_Address
+ 0
+ 32
+ read-only
+
+
+
+
+ BLK0_RDATA2
+ 0x8
+ 0x20
+
+
+ RD_WIFI_MAC_CRC_HIGH
+ read for high 24bit WIFI_MAC_Address
+ 0
+ 24
+ read-only
+
+
+
+
+ BLK0_RDATA3
+ 0xC
+ 0x20
+
+
+ RD_CHIP_VER_DIS_APP_CPU
+ 0
+ 1
+ read-only
+
+
+ RD_CHIP_VER_DIS_BT
+ 1
+ 1
+ read-only
+
+
+ RD_CHIP_VER_PKG_4BIT
+ most significant bit of chip package
+ 2
+ 1
+ read-only
+
+
+ RD_CHIP_VER_DIS_CACHE
+ 3
+ 1
+ read-only
+
+
+ RD_SPI_PAD_CONFIG_HD
+ read for SPI_pad_config_hd
+ 4
+ 5
+ read-only
+
+
+ RD_CHIP_VER_PKG
+ least significant bits of chip package
+ 9
+ 3
+ read-write
+
+
+ RD_CHIP_CPU_FREQ_LOW
+ If set alongside EFUSE_RD_CHIP_CPU_FREQ_RATED, the ESP32's max CPU frequency is rated for 160MHz. 240MHz otherwise
+ 12
+ 1
+ read-write
+
+
+ RD_CHIP_CPU_FREQ_RATED
+ If set, the ESP32's maximum CPU frequency has been rated
+ 13
+ 1
+ read-write
+
+
+ RD_BLK3_PART_RESERVE
+ If set, this bit indicates that BLOCK3[143:96] is reserved for internal use
+ 14
+ 1
+ read-write
+
+
+ RD_CHIP_VER_REV1
+ bit is set to 1 for rev1 silicon
+ 15
+ 1
+ read-write
+
+
+
+
+ BLK0_RDATA4
+ 0x10
+ 0x20
+
+
+ RD_CK8M_FREQ
+ 0
+ 8
+ read-only
+
+
+ RD_ADC_VREF
+ True ADC reference voltage
+ 8
+ 5
+ read-write
+
+
+ RD_SDIO_DREFH
+ 8
+ 2
+ read-only
+
+
+ RD_SDIO_DREFM
+ 10
+ 2
+ read-only
+
+
+ RD_SDIO_DREFL
+ 12
+ 2
+ read-only
+
+
+ RD_XPD_SDIO
+ read for XPD_SDIO_REG
+ 14
+ 1
+ read-only
+
+
+ RD_SDIO_TIEH
+ read for SDIO_TIEH
+ 15
+ 1
+ read-only
+
+
+ RD_SDIO_FORCE
+ read for sdio_force
+ 16
+ 1
+ read-only
+
+
+
+
+ BLK0_RDATA5
+ 0x14
+ 0x20
+
+
+ RD_SPI_PAD_CONFIG_CLK
+ read for SPI_pad_config_clk
+ 0
+ 5
+ read-only
+
+
+ RD_SPI_PAD_CONFIG_Q
+ read for SPI_pad_config_q
+ 5
+ 5
+ read-only
+
+
+ RD_SPI_PAD_CONFIG_D
+ read for SPI_pad_config_d
+ 10
+ 5
+ read-only
+
+
+ RD_SPI_PAD_CONFIG_CS0
+ read for SPI_pad_config_cs0
+ 15
+ 5
+ read-only
+
+
+ RD_CHIP_VER_REV2
+ 20
+ 1
+ read-only
+
+
+ RD_VOL_LEVEL_HP_INV
+ This field stores the voltage level for CPU to run at 240 MHz, or for flash/PSRAM to run at 80 MHz.0x0: level 7; 0x1: level 6; 0x2: level 5; 0x3: level 4. (RO)
+ 22
+ 2
+ read-only
+
+
+ RD_WAFER_VERSION_MINOR
+ 24
+ 2
+ read-only
+
+
+ RD_FLASH_CRYPT_CONFIG
+ read for flash_crypt_config
+ 28
+ 4
+ read-only
+
+
+
+
+ BLK0_RDATA6
+ 0x18
+ 0x20
+
+
+ RD_CODING_SCHEME
+ read for coding_scheme
+ 0
+ 2
+ read-only
+
+
+ RD_CONSOLE_DEBUG_DISABLE
+ read for console_debug_disable
+ 2
+ 1
+ read-only
+
+
+ RD_DISABLE_SDIO_HOST
+ 3
+ 1
+ read-only
+
+
+ RD_ABS_DONE_0
+ read for abstract_done_0
+ 4
+ 1
+ read-only
+
+
+ RD_ABS_DONE_1
+ read for abstract_done_1
+ 5
+ 1
+ read-only
+
+
+ RD_DISABLE_JTAG
+ read for JTAG_disable
+ 6
+ 1
+ read-only
+
+
+ RD_DISABLE_DL_ENCRYPT
+ read for download_dis_encrypt
+ 7
+ 1
+ read-only
+
+
+ RD_DISABLE_DL_DECRYPT
+ read for download_dis_decrypt
+ 8
+ 1
+ read-only
+
+
+ RD_DISABLE_DL_CACHE
+ read for download_dis_cache
+ 9
+ 1
+ read-only
+
+
+ RD_KEY_STATUS
+ read for key_status
+ 10
+ 1
+ read-only
+
+
+
+
+ BLK0_WDATA0
+ 0x1C
+ 0x20
+
+
+ WR_DIS
+ program for efuse_wr_disable
+ 0
+ 16
+ read-write
+
+
+ RD_DIS
+ program for efuse_rd_disable
+ 16
+ 4
+ read-write
+
+
+ FLASH_CRYPT_CNT
+ program for flash_crypt_cnt
+ 20
+ 7
+ read-write
+
+
+
+
+ BLK0_WDATA1
+ 0x20
+ 0x20
+
+
+ WIFI_MAC_CRC_LOW
+ program for low 32bit WIFI_MAC_Address
+ 0
+ 32
+ read-write
+
+
+
+
+ BLK0_WDATA2
+ 0x24
+ 0x20
+
+
+ WIFI_MAC_CRC_HIGH
+ program for high 24bit WIFI_MAC_Address
+ 0
+ 24
+ read-write
+
+
+
+
+ BLK0_WDATA3
+ 0x28
+ 0x20
+
+
+ CHIP_VER_DIS_APP_CPU
+ 0
+ 1
+ read-write
+
+
+ CHIP_VER_DIS_BT
+ 1
+ 1
+ read-write
+
+
+ CHIP_VER_PKG_4BIT
+ most significant bit of chip package
+ 2
+ 1
+ read-only
+
+
+ CHIP_VER_DIS_CACHE
+ 3
+ 1
+ read-write
+
+
+ SPI_PAD_CONFIG_HD
+ program for SPI_pad_config_hd
+ 4
+ 5
+ read-write
+
+
+ CHIP_VER_PKG
+ least significant bits of chip package
+ 9
+ 3
+ read-write
+
+
+ CHIP_CPU_FREQ_LOW
+ If set alongside EFUSE_CHIP_CPU_FREQ_RATED, the ESP32's max CPU frequency is rated for 160MHz. 240MHz otherwise
+ 12
+ 1
+ read-write
+
+
+ CHIP_CPU_FREQ_RATED
+ If set, the ESP32's maximum CPU frequency has been rated
+ 13
+ 1
+ read-write
+
+
+ BLK3_PART_RESERVE
+ If set, this bit indicates that BLOCK3[143:96] is reserved for internal use
+ 14
+ 1
+ read-write
+
+
+ CHIP_VER_REV1
+ 15
+ 1
+ read-write
+
+
+
+
+ BLK0_WDATA4
+ 0x2C
+ 0x20
+
+
+ CK8M_FREQ
+ 0
+ 8
+ read-write
+
+
+ ADC_VREF
+ True ADC reference voltage
+ 8
+ 5
+ read-write
+
+
+ SDIO_DREFH
+ 8
+ 2
+ read-write
+
+
+ SDIO_DREFM
+ 10
+ 2
+ read-write
+
+
+ SDIO_DREFL
+ 12
+ 2
+ read-write
+
+
+ XPD_SDIO
+ program for XPD_SDIO_REG
+ 14
+ 1
+ read-write
+
+
+ SDIO_TIEH
+ program for SDIO_TIEH
+ 15
+ 1
+ read-write
+
+
+ SDIO_FORCE
+ program for sdio_force
+ 16
+ 1
+ read-write
+
+
+
+
+ BLK0_WDATA5
+ 0x30
+ 0x20
+
+
+ SPI_PAD_CONFIG_CLK
+ program for SPI_pad_config_clk
+ 0
+ 5
+ read-write
+
+
+ SPI_PAD_CONFIG_Q
+ program for SPI_pad_config_q
+ 5
+ 5
+ read-write
+
+
+ SPI_PAD_CONFIG_D
+ program for SPI_pad_config_d
+ 10
+ 5
+ read-write
+
+
+ SPI_PAD_CONFIG_CS0
+ program for SPI_pad_config_cs0
+ 15
+ 5
+ read-write
+
+
+ INST_CONFIG
+ 20
+ 8
+ read-write
+
+
+ VOL_LEVEL_HP_INV
+ This field stores the voltage level for CPU to run at 240 MHz, or for flash/PSRAM to run at 80 MHz.0x0: level 7; 0x1: level 6; 0x2: level 5; 0x3: level 4. (R/W)
+ 22
+ 2
+ read-write
+
+
+ DIG_VOL_L6
+ 24
+ 4
+ read-write
+
+
+ FLASH_CRYPT_CONFIG
+ program for flash_crypt_config
+ 28
+ 4
+ read-write
+
+
+
+
+ BLK0_WDATA6
+ 0x34
+ 0x20
+
+
+ CODING_SCHEME
+ program for coding_scheme
+ 0
+ 2
+ read-write
+
+
+ CONSOLE_DEBUG_DISABLE
+ program for console_debug_disable
+ 2
+ 1
+ read-write
+
+
+ DISABLE_SDIO_HOST
+ 3
+ 1
+ read-write
+
+
+ ABS_DONE_0
+ program for abstract_done_0
+ 4
+ 1
+ read-write
+
+
+ ABS_DONE_1
+ program for abstract_done_1
+ 5
+ 1
+ read-write
+
+
+ DISABLE_JTAG
+ program for JTAG_disable
+ 6
+ 1
+ read-write
+
+
+ DISABLE_DL_ENCRYPT
+ program for download_dis_encrypt
+ 7
+ 1
+ read-write
+
+
+ DISABLE_DL_DECRYPT
+ program for download_dis_decrypt
+ 8
+ 1
+ read-write
+
+
+ DISABLE_DL_CACHE
+ program for download_dis_cache
+ 9
+ 1
+ read-write
+
+
+ KEY_STATUS
+ program for key_status
+ 10
+ 1
+ read-write
+
+
+
+
+ BLK1_RDATA0
+ 0x38
+ 0x20
+
+
+ BLK1_DOUT0
+ read for BLOCK1
+ 0
+ 32
+ read-only
+
+
+
+
+ BLK1_RDATA1
+ 0x3C
+ 0x20
+
+
+ BLK1_DOUT1
+ read for BLOCK1
+ 0
+ 32
+ read-only
+
+
+
+
+ BLK1_RDATA2
+ 0x40
+ 0x20
+
+
+ BLK1_DOUT2
+ read for BLOCK1
+ 0
+ 32
+ read-only
+
+
+
+
+ BLK1_RDATA3
+ 0x44
+ 0x20
+
+
+ BLK1_DOUT3
+ read for BLOCK1
+ 0
+ 32
+ read-only
+
+
+
+
+ BLK1_RDATA4
+ 0x48
+ 0x20
+
+
+ BLK1_DOUT4
+ read for BLOCK1
+ 0
+ 32
+ read-only
+
+
+
+
+ BLK1_RDATA5
+ 0x4C
+ 0x20
+
+
+ BLK1_DOUT5
+ read for BLOCK1
+ 0
+ 32
+ read-only
+
+
+
+
+ BLK1_RDATA6
+ 0x50
+ 0x20
+
+
+ BLK1_DOUT6
+ read for BLOCK1
+ 0
+ 32
+ read-only
+
+
+
+
+ BLK1_RDATA7
+ 0x54
+ 0x20
+
+
+ BLK1_DOUT7
+ read for BLOCK1
+ 0
+ 32
+ read-only
+
+
+
+
+ BLK2_RDATA0
+ 0x58
+ 0x20
+
+
+ BLK2_DOUT0
+ read for BLOCK2
+ 0
+ 32
+ read-only
+
+
+
+
+ BLK2_RDATA1
+ 0x5C
+ 0x20
+
+
+ BLK2_DOUT1
+ read for BLOCK2
+ 0
+ 32
+ read-only
+
+
+
+
+ BLK2_RDATA2
+ 0x60
+ 0x20
+
+
+ BLK2_DOUT2
+ read for BLOCK2
+ 0
+ 32
+ read-only
+
+
+
+
+ BLK2_RDATA3
+ 0x64
+ 0x20
+
+
+ BLK2_DOUT3
+ read for BLOCK2
+ 0
+ 32
+ read-only
+
+
+
+
+ BLK2_RDATA4
+ 0x68
+ 0x20
+
+
+ BLK2_DOUT4
+ read for BLOCK2
+ 0
+ 32
+ read-only
+
+
+
+
+ BLK2_RDATA5
+ 0x6C
+ 0x20
+
+
+ BLK2_DOUT5
+ read for BLOCK2
+ 0
+ 32
+ read-only
+
+
+
+
+ BLK2_RDATA6
+ 0x70
+ 0x20
+
+
+ BLK2_DOUT6
+ read for BLOCK2
+ 0
+ 32
+ read-only
+
+
+
+
+ BLK2_RDATA7
+ 0x74
+ 0x20
+
+
+ BLK2_DOUT7
+ read for BLOCK2
+ 0
+ 32
+ read-only
+
+
+
+
+ BLK3_RDATA0
+ 0x78
+ 0x20
+
+
+ BLK3_DOUT0
+ read for BLOCK3
+ 0
+ 32
+ read-only
+
+
+
+
+ BLK3_RDATA1
+ 0x7C
+ 0x20
+
+
+ BLK3_DOUT1
+ read for BLOCK3
+ 0
+ 32
+ read-only
+
+
+
+
+ BLK3_RDATA2
+ 0x80
+ 0x20
+
+
+ BLK3_DOUT2
+ read for BLOCK3
+ 0
+ 32
+ read-only
+
+
+
+
+ BLK3_RDATA3
+ 0x84
+ 0x20
+
+
+ BLK3_DOUT3
+ read for BLOCK3
+ 0
+ 32
+ read-only
+
+
+ RD_ADC1_TP_LOW
+ ADC1 Two Point calibration low point. Only valid if EFUSE_RD_BLK3_PART_RESERVE
+ 0
+ 7
+ read-write
+
+
+ RD_ADC1_TP_HIGH
+ ADC1 Two Point calibration high point. Only valid if EFUSE_RD_BLK3_PART_RESERVE
+ 7
+ 9
+ read-write
+
+
+ RD_ADC2_TP_LOW
+ ADC2 Two Point calibration low point. Only valid if EFUSE_RD_BLK3_PART_RESERVE
+ 16
+ 7
+ read-write
+
+
+ RD_ADC2_TP_HIGH
+ ADC2 Two Point calibration high point. Only valid if EFUSE_RD_BLK3_PART_RESERVE
+ 23
+ 9
+ read-write
+
+
+
+
+ BLK3_RDATA4
+ 0x88
+ 0x20
+
+
+ BLK3_DOUT4
+ read for BLOCK3
+ 0
+ 32
+ read-only
+
+
+ RD_CAL_RESERVED
+ Reserved for future calibration use. Indicated by EFUSE_RD_BLK3_PART_RESERVE
+ 0
+ 16
+ read-write
+
+
+
+
+ BLK3_RDATA5
+ 0x8C
+ 0x20
+
+
+ BLK3_DOUT5
+ read for BLOCK3
+ 0
+ 32
+ read-only
+
+
+
+
+ BLK3_RDATA6
+ 0x90
+ 0x20
+
+
+ BLK3_DOUT6
+ read for BLOCK3
+ 0
+ 32
+ read-only
+
+
+
+
+ BLK3_RDATA7
+ 0x94
+ 0x20
+
+
+ BLK3_DOUT7
+ read for BLOCK3
+ 0
+ 32
+ read-only
+
+
+
+
+ BLK1_WDATA0
+ 0x98
+ 0x20
+
+
+ BLK1_DIN0
+ program for BLOCK1
+ 0
+ 32
+ read-write
+
+
+
+
+ BLK1_WDATA1
+ 0x9C
+ 0x20
+
+
+ BLK1_DIN1
+ program for BLOCK1
+ 0
+ 32
+ read-write
+
+
+
+
+ BLK1_WDATA2
+ 0xA0
+ 0x20
+
+
+ BLK1_DIN2
+ program for BLOCK1
+ 0
+ 32
+ read-write
+
+
+
+
+ BLK1_WDATA3
+ 0xA4
+ 0x20
+
+
+ BLK1_DIN3
+ program for BLOCK1
+ 0
+ 32
+ read-write
+
+
+
+
+ BLK1_WDATA4
+ 0xA8
+ 0x20
+
+
+ BLK1_DIN4
+ program for BLOCK1
+ 0
+ 32
+ read-write
+
+
+
+
+ BLK1_WDATA5
+ 0xAC
+ 0x20
+
+
+ BLK1_DIN5
+ program for BLOCK1
+ 0
+ 32
+ read-write
+
+
+
+
+ BLK1_WDATA6
+ 0xB0
+ 0x20
+
+
+ BLK1_DIN6
+ program for BLOCK1
+ 0
+ 32
+ read-write
+
+
+
+
+ BLK1_WDATA7
+ 0xB4
+ 0x20
+
+
+ BLK1_DIN7
+ program for BLOCK1
+ 0
+ 32
+ read-write
+
+
+
+
+ BLK2_WDATA0
+ 0xB8
+ 0x20
+
+
+ BLK2_DIN0
+ program for BLOCK2
+ 0
+ 32
+ read-write
+
+
+
+
+ BLK2_WDATA1
+ 0xBC
+ 0x20
+
+
+ BLK2_DIN1
+ program for BLOCK2
+ 0
+ 32
+ read-write
+
+
+
+
+ BLK2_WDATA2
+ 0xC0
+ 0x20
+
+
+ BLK2_DIN2
+ program for BLOCK2
+ 0
+ 32
+ read-write
+
+
+
+
+ BLK2_WDATA3
+ 0xC4
+ 0x20
+
+
+ BLK2_DIN3
+ program for BLOCK2
+ 0
+ 32
+ read-write
+
+
+
+
+ BLK2_WDATA4
+ 0xC8
+ 0x20
+
+
+ BLK2_DIN4
+ program for BLOCK2
+ 0
+ 32
+ read-write
+
+
+
+
+ BLK2_WDATA5
+ 0xCC
+ 0x20
+
+
+ BLK2_DIN5
+ program for BLOCK2
+ 0
+ 32
+ read-write
+
+
+
+
+ BLK2_WDATA6
+ 0xD0
+ 0x20
+
+
+ BLK2_DIN6
+ program for BLOCK2
+ 0
+ 32
+ read-write
+
+
+
+
+ BLK2_WDATA7
+ 0xD4
+ 0x20
+
+
+ BLK2_DIN7
+ program for BLOCK2
+ 0
+ 32
+ read-write
+
+
+
+
+ BLK3_WDATA0
+ 0xD8
+ 0x20
+
+
+ BLK3_DIN0
+ program for BLOCK3
+ 0
+ 32
+ read-write
+
+
+
+
+ BLK3_WDATA1
+ 0xDC
+ 0x20
+
+
+ BLK3_DIN1
+ program for BLOCK3
+ 0
+ 32
+ read-write
+
+
+
+
+ BLK3_WDATA2
+ 0xE0
+ 0x20
+
+
+ BLK3_DIN2
+ program for BLOCK3
+ 0
+ 32
+ read-write
+
+
+
+
+ BLK3_WDATA3
+ 0xE4
+ 0x20
+
+
+ BLK3_DIN3
+ program for BLOCK3
+ 0
+ 32
+ read-write
+
+
+ ADC1_TP_LOW
+ ADC1 Two Point calibration low point. Only valid if EFUSE_RD_BLK3_PART_RESERVE
+ 0
+ 7
+ read-write
+
+
+ ADC1_TP_HIGH
+ ADC1 Two Point calibration high point. Only valid if EFUSE_RD_BLK3_PART_RESERVE
+ 7
+ 9
+ read-write
+
+
+ ADC2_TP_LOW
+ ADC2 Two Point calibration low point. Only valid if EFUSE_RD_BLK3_PART_RESERVE
+ 16
+ 7
+ read-write
+
+
+ ADC2_TP_HIGH
+ ADC2 Two Point calibration high point. Only valid if EFUSE_RD_BLK3_PART_RESERVE
+ 23
+ 9
+ read-write
+
+
+
+
+ BLK3_WDATA4
+ 0xE8
+ 0x20
+
+
+ BLK3_DIN4
+ program for BLOCK3
+ 0
+ 32
+ read-write
+
+
+ CAL_RESERVED
+ Reserved for future calibration use. Indicated by EFUSE_BLK3_PART_RESERVE
+ 0
+ 16
+ read-write
+
+
+
+
+ BLK3_WDATA5
+ 0xEC
+ 0x20
+
+
+ BLK3_DIN5
+ program for BLOCK3
+ 0
+ 32
+ read-write
+
+
+
+
+ BLK3_WDATA6
+ 0xF0
+ 0x20
+
+
+ BLK3_DIN6
+ program for BLOCK3
+ 0
+ 32
+ read-write
+
+
+
+
+ BLK3_WDATA7
+ 0xF4
+ 0x20
+
+
+ BLK3_DIN7
+ program for BLOCK3
+ 0
+ 32
+ read-write
+
+
+
+
+ CLK
+ 0xF8
+ 0x20
+ 0x00004052
+
+
+ SEL0
+ efuse timing configure
+ 0
+ 8
+ read-write
+
+
+ SEL1
+ efuse timing configure
+ 8
+ 8
+ read-write
+
+
+ EN
+ 16
+ 1
+ read-write
+
+
+
+
+ CONF
+ 0xFC
+ 0x20
+ 0x00010000
+
+
+ OP_CODE
+ efuse operation code
+ 0
+ 16
+ read-write
+
+
+ FORCE_NO_WR_RD_DIS
+ 16
+ 1
+ read-write
+
+
+
+
+ STATUS
+ 0x100
+ 0x20
+
+
+ DEBUG
+ 0
+ 32
+ read-only
+
+
+
+
+ CMD
+ 0x104
+ 0x20
+
+
+ READ_CMD
+ command for read
+ 0
+ 1
+ read-write
+
+
+ PGM_CMD
+ command for program
+ 1
+ 1
+ read-write
+
+
+
+
+ INT_RAW
+ 0x108
+ 0x20
+
+
+ READ_DONE_INT_RAW
+ read done interrupt raw status
+ 0
+ 1
+ read-only
+
+
+ PGM_DONE_INT_RAW
+ program done interrupt raw status
+ 1
+ 1
+ read-only
+
+
+
+
+ INT_ST
+ 0x10C
+ 0x20
+
+
+ READ_DONE_INT_ST
+ read done interrupt status
+ 0
+ 1
+ read-only
+
+
+ PGM_DONE_INT_ST
+ program done interrupt status
+ 1
+ 1
+ read-only
+
+
+
+
+ INT_ENA
+ 0x110
+ 0x20
+
+
+ READ_DONE_INT_ENA
+ read done interrupt enable
+ 0
+ 1
+ read-write
+
+
+ PGM_DONE_INT_ENA
+ program done interrupt enable
+ 1
+ 1
+ read-write
+
+
+
+
+ INT_CLR
+ 0x114
+ 0x20
+
+
+ READ_DONE_INT_CLR
+ read done interrupt clear
+ 0
+ 1
+ write-only
+
+
+ PGM_DONE_INT_CLR
+ program done interrupt clear
+ 1
+ 1
+ write-only
+
+
+
+
+ DAC_CONF
+ 0x118
+ 0x20
+ 0x00000028
+
+
+ DAC_CLK_DIV
+ efuse timing configure
+ 0
+ 8
+ read-write
+
+
+ DAC_CLK_PAD_SEL
+ 8
+ 1
+ read-write
+
+
+
+
+ DEC_STATUS
+ 0x11C
+ 0x20
+
+
+ DEC_WARNINGS
+ the decode result of 3/4 coding scheme has warning
+ 0
+ 12
+ read-only
+
+
+
+
+ DATE
+ 0x1FC
+ 0x20
+ 0x16042600
+
+
+ DATE
+ 0
+ 32
+ read-write
+
+
+
+
+
+
+ FLASH_ENCRYPTION
+ Flash Encryption Peripheral
+ FLASH_ENCRYPTION
+ 0x3FF46000
+
+ 0x0
+ 0x2C
+ registers
+
+
+
+ 8
+ 0x4
+ BUFFER_%s
+ 0x0
+ 0x20
+
+
+ BUFFER
+ Data buffers for encryption.
+ 0
+ 8
+ write-only
+
+
+
+
+ START
+ 0x20
+ 0x20
+
+
+ FLASH_START
+ Set this bit to start encryption operation on data buffer.
+ 0
+ 8
+ write-only
+
+
+
+
+ ADDRESS
+ 0x24
+ 0x20
+
+
+ ADDRESS
+ The physical address on the off-chip flash must be 8-word boundary aligned.
+ 0
+ 8
+ write-only
+
+
+
+
+ DONE
+ 0x28
+ 0x20
+
+
+ FLASH_DONE
+ Set this bit when encryption operation is complete.
+ 0
+ 1
+ read-only
+
+
+
+
+
+
+ FRC_TIMER
+ Peripheral FRC_TIMER
+ FRC
+ 0x3FF47000
+
+ 0x0
+ 0x14
+ registers
+
+
+
+ TIMER_LOAD
+ 0x0
+ 0x20
+
+
+ VALUE
+ 0
+ 8
+ read-write
+
+
+
+
+ TIMER_COUNT
+ 0x4
+ 0x20
+
+
+ TIMER_COUNT
+ 0
+ 8
+ read-write
+
+
+
+
+ TIMER_CTRL
+ 0x8
+ 0x20
+
+
+ TIMER_PRESCALER
+ 1
+ 8
+ read-write
+
+
+
+
+ TIMER_INT
+ 0xC
+ 0x20
+
+
+ CLR
+ 0
+ 1
+ read-write
+
+
+
+
+ TIMER_ALARM
+ 0x10
+ 0x20
+
+
+ TIMER_ALARM
+ 0
+ 8
+ read-write
+
+
+
+
+
+
+ GPIO
+ General Purpose Input/Output
+ GPIO
+ 0x3FF44000
+
+ 0x0
+ 0x5CC
+ registers
+
+
+ GPIO
+ 22
+
+
+ GPIO_NMI
+ 23
+
+
+
+ BT_SELECT
+ 0x0
+ 0x20
+
+
+ BT_SEL
+ NA
+ 0
+ 32
+ read-write
+
+
+
+
+ OUT
+ 0x4
+ 0x20
+
+
+ DATA
+ GPIO0~31 output value
+ 0
+ 32
+ read-write
+
+
+
+
+ OUT_W1TS
+ 0x8
+ 0x20
+
+
+ OUT_DATA_W1TS
+ GPIO0~31 output value write 1 to set
+ 0
+ 32
+ read-write
+
+
+
+
+ OUT_W1TC
+ 0xC
+ 0x20
+
+
+ OUT_DATA_W1TC
+ GPIO0~31 output value write 1 to clear
+ 0
+ 32
+ read-write
+
+
+
+
+ OUT1
+ 0x10
+ 0x20
+
+
+ DATA
+ GPIO32~39 output value
+ 0
+ 8
+ read-write
+
+
+
+
+ OUT1_W1TS
+ 0x14
+ 0x20
+
+
+ OUT1_DATA_W1TS
+ GPIO32~39 output value write 1 to set
+ 0
+ 8
+ read-write
+
+
+
+
+ OUT1_W1TC
+ 0x18
+ 0x20
+
+
+ OUT1_DATA_W1TC
+ GPIO32~39 output value write 1 to clear
+ 0
+ 8
+ read-write
+
+
+
+
+ SDIO_SELECT
+ 0x1C
+ 0x20
+
+
+ SDIO_SEL
+ SDIO PADS on/off control from outside
+ 0
+ 8
+ read-write
+
+
+
+
+ ENABLE
+ 0x20
+ 0x20
+
+
+ DATA
+ GPIO0~31 output enable
+ 0
+ 32
+ read-write
+
+
+
+
+ ENABLE_W1TS
+ 0x24
+ 0x20
+
+
+ ENABLE_DATA_W1TS
+ GPIO0~31 output enable write 1 to set
+ 0
+ 32
+ read-write
+
+
+
+
+ ENABLE_W1TC
+ 0x28
+ 0x20
+
+
+ ENABLE_DATA_W1TC
+ GPIO0~31 output enable write 1 to clear
+ 0
+ 32
+ read-write
+
+
+
+
+ ENABLE1
+ 0x2C
+ 0x20
+
+
+ DATA
+ GPIO32~39 output enable
+ 0
+ 8
+ read-write
+
+
+
+
+ ENABLE1_W1TS
+ 0x30
+ 0x20
+
+
+ ENABLE1_DATA_W1TS
+ GPIO32~39 output enable write 1 to set
+ 0
+ 8
+ read-write
+
+
+
+
+ ENABLE1_W1TC
+ 0x34
+ 0x20
+
+
+ ENABLE1_DATA_W1TC
+ GPIO32~39 output enable write 1 to clear
+ 0
+ 8
+ read-write
+
+
+
+
+ STRAP
+ 0x38
+ 0x20
+
+
+ STRAPPING
+ {10'b0, MTDI, GPIO0, GPIO2, GPIO4, MTDO, GPIO5}
+ 0
+ 16
+ read-only
+
+
+
+
+ IN
+ 0x3C
+ 0x20
+
+
+ DATA_NEXT
+ GPIO0~31 input value
+ 0
+ 32
+ read-write
+
+
+
+
+ IN1
+ 0x40
+ 0x20
+
+
+ DATA_NEXT
+ GPIO32~39 input value
+ 0
+ 8
+ read-write
+
+
+
+
+ STATUS
+ 0x44
+ 0x20
+
+
+ INT
+ GPIO0~31 interrupt status
+ 0
+ 32
+ read-write
+
+
+
+
+ STATUS_W1TS
+ 0x48
+ 0x20
+
+
+ STATUS_INT_W1TS
+ GPIO0~31 interrupt status write 1 to set
+ 0
+ 32
+ read-write
+
+
+
+
+ STATUS_W1TC
+ 0x4C
+ 0x20
+
+
+ STATUS_INT_W1TC
+ GPIO0~31 interrupt status write 1 to clear
+ 0
+ 32
+ read-write
+
+
+
+
+ STATUS1
+ 0x50
+ 0x20
+
+
+ INT
+ GPIO32~39 interrupt status
+ 0
+ 8
+ read-write
+
+
+
+
+ STATUS1_W1TS
+ 0x54
+ 0x20
+
+
+ STATUS1_INT_W1TS
+ GPIO32~39 interrupt status write 1 to set
+ 0
+ 8
+ read-write
+
+
+
+
+ STATUS1_W1TC
+ 0x58
+ 0x20
+
+
+ STATUS1_INT_W1TC
+ GPIO32~39 interrupt status write 1 to clear
+ 0
+ 8
+ read-write
+
+
+
+
+ ACPU_INT
+ 0x60
+ 0x20
+
+
+ APPCPU_INT
+ GPIO0~31 APP CPU interrupt status
+ 0
+ 32
+ read-only
+
+
+
+
+ ACPU_NMI_INT
+ 0x64
+ 0x20
+
+
+ APPCPU_NMI_INT
+ GPIO0~31 APP CPU non-maskable interrupt status
+ 0
+ 32
+ read-only
+
+
+
+
+ PCPU_INT
+ 0x68
+ 0x20
+
+
+ PROCPU_INT
+ GPIO0~31 PRO CPU interrupt status
+ 0
+ 32
+ read-only
+
+
+
+
+ PCPU_NMI_INT
+ 0x6C
+ 0x20
+
+
+ PROCPU_NMI_INT
+ GPIO0~31 PRO CPU non-maskable interrupt status
+ 0
+ 32
+ read-only
+
+
+
+
+ CPUSDIO_INT
+ 0x70
+ 0x20
+
+
+ SDIO_INT
+ SDIO's extent GPIO0~31 interrupt
+ 0
+ 32
+ read-only
+
+
+
+
+ ACPU_INT1
+ 0x74
+ 0x20
+
+
+ APPCPU_INT_H
+ GPIO32~39 APP CPU interrupt status
+ 0
+ 8
+ read-only
+
+
+
+
+ ACPU_NMI_INT1
+ 0x78
+ 0x20
+
+
+ APPCPU_NMI_INT_H
+ GPIO32~39 APP CPU non-maskable interrupt status
+ 0
+ 8
+ read-only
+
+
+
+
+ PCPU_INT1
+ 0x7C
+ 0x20
+
+
+ PROCPU_INT_H
+ GPIO32~39 PRO CPU interrupt status
+ 0
+ 8
+ read-only
+
+
+
+
+ PCPU_NMI_INT1
+ 0x80
+ 0x20
+
+
+ PROCPU_NMI_INT_H
+ GPIO32~39 PRO CPU non-maskable interrupt status
+ 0
+ 8
+ read-only
+
+
+
+
+ CPUSDIO_INT1
+ 0x84
+ 0x20
+
+
+ SDIO_INT_H
+ SDIO's extent GPIO32~39 interrupt
+ 0
+ 8
+ read-only
+
+
+ PIN_PAD_DRIVER
+ 2
+ 1
+ read-write
+
+
+ PIN_INT_TYPE
+ 7
+ 3
+ read-write
+
+
+ PIN_WAKEUP_ENABLE
+ 10
+ 1
+ read-write
+
+
+ PIN_CONFIG
+ 11
+ 2
+ read-write
+
+
+ PIN_INT_ENA
+ 13
+ 5
+ read-write
+
+
+
+
+ 40
+ 0x4
+ 0-39
+ PIN%s
+ 0x88
+ 0x20
+
+
+ PAD_DRIVER
+ if set to 0: normal output if set to 1: open drain
+ 2
+ 1
+ read-write
+
+
+ INT_TYPE
+ if set to 0: GPIO interrupt disable if set to 1: rising edge trigger if set to 2: falling edge trigger if set to 3: any edge trigger if set to 4: low level trigger if set to 5: high level trigger
+ 7
+ 3
+ read-write
+
+
+ WAKEUP_ENABLE
+ GPIO wake up enable only available in light sleep
+ 10
+ 1
+ read-write
+
+
+ CONFIG
+ NA
+ 11
+ 2
+ read-write
+
+
+ INT_ENA
+ bit0: APP CPU interrupt enable bit1: APP CPU non-maskable interrupt enable bit3: PRO CPU interrupt enable bit4: PRO CPU non-maskable interrupt enable bit5: SDIO's extent interrupt enable
+ 13
+ 5
+ read-write
+
+
+
+
+ cali_conf
+ 0x128
+ 0x20
+
+
+ CALI_RTC_MAX
+ 0
+ 10
+ read-write
+
+
+ CALI_START
+ 31
+ 1
+ read-write
+
+
+
+
+ cali_data
+ 0x12C
+ 0x20
+
+
+ CALI_VALUE_SYNC2
+ 0
+ 20
+ read-only
+
+
+ CALI_RDY_REAL
+ 30
+ 1
+ read-only
+
+
+ CALI_RDY_SYNC2
+ 31
+ 1
+ read-only
+
+
+
+
+ 256
+ 0x4
+ 0-255
+ FUNC%s_IN_SEL_CFG
+ 0x130
+ 0x20
+
+
+ IN_SEL
+ select one of the 256 inputs
+ 0
+ 6
+ read-write
+
+
+ IN_INV_SEL
+ revert the value of the input if you want to revert please set the value to 1
+ 6
+ 1
+ read-write
+
+
+ SEL
+ if the slow signal bypass the io matrix or not if you want setting the value to 1
+ 7
+ 1
+ read-write
+
+
+
+
+ 40
+ 0x4
+ 0-39
+ FUNC%s_OUT_SEL_CFG
+ 0x530
+ 0x20
+
+
+ OUT_SEL
+ select one of the 256 output to 40 GPIO
+ 0
+ 9
+ read-write
+
+
+ INV_SEL
+ invert the output value if you want to revert the output value setting the value to 1
+ 9
+ 1
+ read-write
+
+
+ OEN_SEL
+ weather using the logical oen signal or not using the value setting by the register
+ 10
+ 1
+ read-write
+
+
+ OEN_INV_SEL
+ invert the output enable value if you want to revert the output enable value setting the value to 1
+ 11
+ 1
+ read-write
+
+
+
+
+
+
+ GPIO_SD
+ Sigma-Delta Modulation
+ GPIO_SIGMADELTA
+ 0x3FF44F00
+
+ 0x0
+ 0x2C
+ registers
+
+
+
+ SIGMADELTA0
+ 0x0
+ 0x20
+ 0x0000FF00
+
+
+ SD0_IN
+ 0
+ 8
+ read-write
+
+
+ SD0_PRESCALE
+ 8
+ 8
+ read-write
+
+
+
+
+ SIGMADELTA1
+ 0x4
+ 0x20
+ 0x0000FF00
+
+
+ SD1_IN
+ 0
+ 8
+ read-write
+
+
+ SD1_PRESCALE
+ 8
+ 8
+ read-write
+
+
+
+
+ SIGMADELTA2
+ 0x8
+ 0x20
+ 0x0000FF00
+
+
+ SD2_IN
+ 0
+ 8
+ read-write
+
+
+ SD2_PRESCALE
+ 8
+ 8
+ read-write
+
+
+
+
+ SIGMADELTA3
+ 0xC
+ 0x20
+ 0x0000FF00
+
+
+ SD3_IN
+ 0
+ 8
+ read-write
+
+
+ SD3_PRESCALE
+ 8
+ 8
+ read-write
+
+
+
+
+ SIGMADELTA4
+ 0x10
+ 0x20
+ 0x0000FF00
+
+
+ SD4_IN
+ 0
+ 8
+ read-write
+
+
+ SD4_PRESCALE
+ 8
+ 8
+ read-write
+
+
+
+
+ SIGMADELTA5
+ 0x14
+ 0x20
+ 0x0000FF00
+
+
+ SD5_IN
+ 0
+ 8
+ read-write
+
+
+ SD5_PRESCALE
+ 8
+ 8
+ read-write
+
+
+
+
+ SIGMADELTA6
+ 0x18
+ 0x20
+ 0x0000FF00
+
+
+ SD6_IN
+ 0
+ 8
+ read-write
+
+
+ SD6_PRESCALE
+ 8
+ 8
+ read-write
+
+
+
+
+ SIGMADELTA7
+ 0x1C
+ 0x20
+ 0x0000FF00
+
+
+ SD7_IN
+ 0
+ 8
+ read-write
+
+
+ SD7_PRESCALE
+ 8
+ 8
+ read-write
+
+
+
+
+ CG
+ 0x20
+ 0x20
+
+
+ SD_CLK_EN
+ 31
+ 1
+ read-write
+
+
+
+
+ MISC
+ 0x24
+ 0x20
+
+
+ SPI_SWAP
+ 31
+ 1
+ read-write
+
+
+
+
+ VERSION
+ 0x28
+ 0x20
+ 0x01506190
+
+
+ SD_DATE
+ 0
+ 28
+ read-write
+
+
+
+
+
+
+ HINF
+ Peripheral HINF
+ HINF
+ 0x3FF4B000
+
+ 0x0
+ 0x34
+ registers
+
+
+
+ CFG_DATA0
+ 0x0
+ 0x20
+ 0x22226666
+
+
+ USER_ID_FN1
+ 0
+ 16
+ read-write
+
+
+ DEVICE_ID_FN1
+ 16
+ 16
+ read-write
+
+
+
+
+ CFG_DATA1
+ 0x4
+ 0x20
+ 0x01110011
+
+
+ SDIO_ENABLE
+ 0
+ 1
+ read-write
+
+
+ SDIO_IOREADY1
+ 1
+ 1
+ read-write
+
+
+ HIGHSPEED_ENABLE
+ 2
+ 1
+ read-write
+
+
+ HIGHSPEED_MODE
+ 3
+ 1
+ read-only
+
+
+ SDIO_CD_ENABLE
+ 4
+ 1
+ read-write
+
+
+ SDIO_IOREADY2
+ 5
+ 1
+ read-write
+
+
+ SDIO_INT_MASK
+ 6
+ 1
+ read-write
+
+
+ IOENABLE2
+ 7
+ 1
+ read-only
+
+
+ CD_DISABLE
+ 8
+ 1
+ read-only
+
+
+ FUNC1_EPS
+ 9
+ 1
+ read-only
+
+
+ EMP
+ 10
+ 1
+ read-only
+
+
+ IOENABLE1
+ 11
+ 1
+ read-only
+
+
+ SDIO20_CONF0
+ 12
+ 4
+ read-write
+
+
+ SDIO_VER
+ 16
+ 12
+ read-write
+
+
+ FUNC2_EPS
+ 28
+ 1
+ read-only
+
+
+ SDIO20_CONF1
+ 29
+ 3
+ read-write
+
+
+
+
+ CFG_DATA7
+ 0x1C
+ 0x20
+ 0x00020000
+
+
+ PIN_STATE
+ 0
+ 8
+ read-write
+
+
+ CHIP_STATE
+ 8
+ 8
+ read-write
+
+
+ SDIO_RST
+ 16
+ 1
+ read-write
+
+
+ SDIO_IOREADY0
+ 17
+ 1
+ read-write
+
+
+
+
+ CIS_CONF0
+ 0x20
+ 0x20
+ 0xFFFFFFFF
+
+
+ CIS_CONF_W0
+ 0
+ 32
+ read-write
+
+
+
+
+ CIS_CONF1
+ 0x24
+ 0x20
+ 0xFFFFFFFF
+
+
+ CIS_CONF_W1
+ 0
+ 32
+ read-write
+
+
+
+
+ CIS_CONF2
+ 0x28
+ 0x20
+ 0xFFFFFFFF
+
+
+ CIS_CONF_W2
+ 0
+ 32
+ read-write
+
+
+
+
+ CIS_CONF3
+ 0x2C
+ 0x20
+ 0xFFFFFFFF
+
+
+ CIS_CONF_W3
+ 0
+ 32
+ read-write
+
+
+
+
+ CIS_CONF4
+ 0x30
+ 0x20
+ 0xFFFFFFFF
+
+
+ CIS_CONF_W4
+ 0
+ 32
+ read-write
+
+
+
+
+ CIS_CONF5
+ 0x34
+ 0x20
+ 0xFFFFFFFF
+
+
+ CIS_CONF_W5
+ 0
+ 32
+ read-write
+
+
+
+
+ CIS_CONF6
+ 0x38
+ 0x20
+ 0xFFFFFFFF
+
+
+ CIS_CONF_W6
+ 0
+ 32
+ read-write
+
+
+
+
+ CIS_CONF7
+ 0x3C
+ 0x20
+ 0xFFFFFFFF
+
+
+ CIS_CONF_W7
+ 0
+ 32
+ read-write
+
+
+
+
+ CFG_DATA16
+ 0x40
+ 0x20
+ 0x33336666
+
+
+ USER_ID_FN2
+ 0
+ 16
+ read-write
+
+
+ DEVICE_ID_FN2
+ 16
+ 16
+ read-write
+
+
+
+
+ DATE
+ 0xFC
+ 0x20
+ 0x15030200
+
+
+ SDIO_DATE
+ 0
+ 32
+ read-write
+
+
+
+
+
+
+ I2C0
+ I2C (Inter-Integrated Circuit) Controller
+ I2C
+ 0x3FF53000
+
+ 0x0
+ 0x9C
+ registers
+
+
+ I2C_EXT0
+ 49
+
+
+
+ SCL_LOW_PERIOD
+ 0x0
+ 0x20
+
+
+ SCL_LOW_PERIOD
+ This register is used to configure the low level width of SCL clock.
+ 0
+ 14
+ read-write
+
+
+
+
+ CTR
+ 0x4
+ 0x20
+ 0x00000003
+
+
+ SDA_FORCE_OUT
+ 1: normally ouput sda data 0: exchange the function of sda_o and sda_oe (sda_o is the original internal output sda signal sda_oe is the enable bit for the internal output sda signal)
+ 0
+ 1
+ read-write
+
+
+ SCL_FORCE_OUT
+ 1: normally ouput scl clock 0: exchange the function of scl_o and scl_oe (scl_o is the original internal output scl signal scl_oe is the enable bit for the internal output scl signal)
+ 1
+ 1
+ read-write
+
+
+ SAMPLE_SCL_LEVEL
+ Set this bit to sample data in SCL low level. clear this bit to sample data in SCL high level.
+ 2
+ 1
+ read-write
+
+
+ MS_MODE
+ Set this bit to configure the module as i2c master clear this bit to configure the module as i2c slave.
+ 4
+ 1
+ read-write
+
+
+ TRANS_START
+ Set this bit to start sending data in txfifo.
+ 5
+ 1
+ read-write
+
+
+ TX_LSB_FIRST
+ This bit is used to control the sending mode for data need to be send. 1: receive data from most significant bit 0: receive data from least significant bit
+ 6
+ 1
+ read-write
+
+
+ RX_LSB_FIRST
+ This bit is used to control the storage mode for received datas. 1: receive data from most significant bit 0: receive data from least significant bit
+ 7
+ 1
+ read-write
+
+
+ CLK_EN
+ This is the clock gating control bit for reading or writing registers.
+ 8
+ 1
+ read-write
+
+
+
+
+ SR
+ 0x8
+ 0x20
+
+
+ ACK_REC
+ This register stores the value of ACK bit.
+ 0
+ 1
+ read-only
+
+
+ SLAVE_RW
+ when in slave mode 1: master read slave 0: master write slave.
+ 1
+ 1
+ read-only
+
+
+ TIME_OUT
+ when I2C takes more than time_out_reg clocks to receive a data then this register changes to high level.
+ 2
+ 1
+ read-only
+
+
+ ARB_LOST
+ when I2C lost control of SDA line this register changes to high level.
+ 3
+ 1
+ read-only
+
+
+ BUS_BUSY
+ 1:I2C bus is busy transferring data. 0:I2C bus is in idle state.
+ 4
+ 1
+ read-only
+
+
+ SLAVE_ADDRESSED
+ when configured as i2c slave and the address send by master is equal to slave's address then this bit will be high level.
+ 5
+ 1
+ read-only
+
+
+ BYTE_TRANS
+ This register changes to high level when one byte is transferred.
+ 6
+ 1
+ read-only
+
+
+ RXFIFO_CNT
+ This register represent the amount of data need to send.
+ 8
+ 6
+ read-only
+
+
+ TXFIFO_CNT
+ This register stores the amount of received data in ram.
+ 18
+ 6
+ read-only
+
+
+ SCL_MAIN_STATE_LAST
+ This register stores the value of state machine for i2c module. 3'h0: SCL_MAIN_IDLE 3'h1: SCL_ADDRESS_SHIFT 3'h2: SCL_ACK_ADDRESS 3'h3: SCL_RX_DATA 3'h4 SCL_TX_DATA 3'h5:SCL_SEND_ACK 3'h6:SCL_WAIT_ACK
+ 24
+ 3
+ read-only
+
+
+ SCL_STATE_LAST
+ This register stores the value of state machine to produce SCL. 3'h0: SCL_IDLE 3'h1:SCL_START 3'h2:SCL_LOW_EDGE 3'h3: SCL_LOW 3'h4:SCL_HIGH_EDGE 3'h5:SCL_HIGH 3'h6:SCL_STOP
+ 28
+ 3
+ read-only
+
+
+
+
+ TO
+ 0xC
+ 0x20
+
+
+ TIME_OUT
+ This register is used to configure the max clock number of receiving a data.
+ 0
+ 20
+ read-write
+
+
+
+
+ SLAVE_ADDR
+ 0x10
+ 0x20
+
+
+ SLAVE_ADDR
+ when configured as i2c slave this register is used to configure slave's address.
+ 0
+ 15
+ read-write
+
+
+ ADDR_10BIT_EN
+ This register is used to enable slave 10bit address mode.
+ 31
+ 1
+ read-write
+
+
+
+
+ RXFIFO_ST
+ 0x14
+ 0x20
+
+
+ RXFIFO_START_ADDR
+ This is the offset address of the last receiving data as described in nonfifo_rx_thres_register.
+ 0
+ 5
+ read-only
+
+
+ RXFIFO_END_ADDR
+ This is the offset address of the first receiving data as described in nonfifo_rx_thres_register.
+ 5
+ 5
+ read-only
+
+
+ TXFIFO_START_ADDR
+ This is the offset address of the first sending data as described in nonfifo_tx_thres register.
+ 10
+ 5
+ read-only
+
+
+ TXFIFO_END_ADDR
+ This is the offset address of the last sending data as described in nonfifo_tx_thres register.
+ 15
+ 5
+ read-only
+
+
+
+
+ FIFO_CONF
+ 0x18
+ 0x20
+ 0x0155408B
+
+
+ RXFIFO_FULL_THRHD
+ 0
+ 5
+ read-write
+
+
+ TXFIFO_EMPTY_THRHD
+ Config txfifo empty threhd value when using apb fifo access
+ 5
+ 5
+ read-write
+
+
+ NONFIFO_EN
+ Set this bit to enble apb nonfifo access.
+ 10
+ 1
+ read-write
+
+
+ FIFO_ADDR_CFG_EN
+ When this bit is set to 1 then the byte after address represent the offset address of I2C Slave's ram.
+ 11
+ 1
+ read-write
+
+
+ RX_FIFO_RST
+ Set this bit to reset rx fifo when using apb fifo access.
+ 12
+ 1
+ read-write
+
+
+ TX_FIFO_RST
+ Set this bit to reset tx fifo when using apb fifo access.
+ 13
+ 1
+ read-write
+
+
+ NONFIFO_RX_THRES
+ when I2C receives more than nonfifo_rx_thres data it will produce rx_send_full_int_raw interrupt and update the current offset address of the receiving data.
+ 14
+ 6
+ read-write
+
+
+ NONFIFO_TX_THRES
+ when I2C sends more than nonfifo_tx_thres data it will produce tx_send_empty_int_raw interrupt and update the current offset address of the sending data.
+ 20
+ 6
+ read-write
+
+
+
+
+ DATA
+ 0x1C
+ 0x20
+
+
+ FIFO_RDATA
+ The register represent the byte data read from rxfifo when use apb fifo access
+ 0
+ 8
+ read-only
+
+
+
+
+ INT_RAW
+ 0x20
+ 0x20
+
+
+ RXFIFO_FULL_INT_RAW
+ The raw interrupt status bit for rxfifo full when use apb fifo access.
+ 0
+ 1
+ read-only
+
+
+ TXFIFO_EMPTY_INT_RAW
+ The raw interrupt status bit for txfifo empty when use apb fifo access.
+ 1
+ 1
+ read-only
+
+
+ RXFIFO_OVF_INT_RAW
+ The raw interrupt status bit for receiving data overflow when use apb fifo access.
+ 2
+ 1
+ read-only
+
+
+ END_DETECT_INT_RAW
+ The raw interrupt status bit for end_detect_int interrupt. when I2C deals with the END command it will produce end_detect_int interrupt.
+ 3
+ 1
+ read-only
+
+
+ SLAVE_TRAN_COMP_INT_RAW
+ The raw interrupt status bit for slave_tran_comp_int interrupt. when I2C Slave detectsthe STOP bit it will produce slave_tran_comp_int interrupt.
+ 4
+ 1
+ read-only
+
+
+ ARBITRATION_LOST_INT_RAW
+ The raw interrupt status bit for arbitration_lost_int interrupt.when I2C lost the usage right of I2C BUS it will produce arbitration_lost_int interrupt.
+ 5
+ 1
+ read-only
+
+
+ MASTER_TRAN_COMP_INT_RAW
+ The raw interrupt status bit for master_tra_comp_int interrupt. when I2C Master sends or receives a byte it will produce master_tran_comp_int interrupt.
+ 6
+ 1
+ read-only
+
+
+ TRANS_COMPLETE_INT_RAW
+ The raw interrupt status bit for trans_complete_int interrupt. when I2C Master finished STOP command it will produce trans_complete_int interrupt.
+ 7
+ 1
+ read-only
+
+
+ TIME_OUT_INT_RAW
+ The raw interrupt status bit for time_out_int interrupt. when I2C takes a lot of time to receive a data it will produce time_out_int interrupt.
+ 8
+ 1
+ read-only
+
+
+ TRANS_START_INT_RAW
+ The raw interrupt status bit for trans_start_int interrupt. when I2C sends the START bit it will produce trans_start_int interrupt.
+ 9
+ 1
+ read-only
+
+
+ ACK_ERR_INT_RAW
+ The raw interrupt status bit for ack_err_int interrupt. when I2C receives a wrong ACK bit it will produce ack_err_int interrupt..
+ 10
+ 1
+ read-only
+
+
+ RX_REC_FULL_INT_RAW
+ The raw interrupt status bit for rx_rec_full_int interrupt. when I2C receives more data than nonfifo_rx_thres it will produce rx_rec_full_int interrupt.
+ 11
+ 1
+ read-only
+
+
+ TX_SEND_EMPTY_INT_RAW
+ The raw interrupt status bit for tx_send_empty_int interrupt.when I2C sends more data than nonfifo_tx_thres it will produce tx_send_empty_int interrupt..
+ 12
+ 1
+ read-only
+
+
+
+
+ INT_CLR
+ 0x24
+ 0x20
+
+
+ RXFIFO_FULL_INT_CLR
+ Set this bit to clear the rxfifo_full_int interrupt.
+ 0
+ 1
+ write-only
+
+
+ TXFIFO_EMPTY_INT_CLR
+ Set this bit to clear the txfifo_empty_int interrupt.
+ 1
+ 1
+ write-only
+
+
+ RXFIFO_OVF_INT_CLR
+ Set this bit to clear the rxfifo_ovf_int interrupt.
+ 2
+ 1
+ write-only
+
+
+ END_DETECT_INT_CLR
+ Set this bit to clear the end_detect_int interrupt.
+ 3
+ 1
+ write-only
+
+
+ SLAVE_TRAN_COMP_INT_CLR
+ Set this bit to clear the slave_tran_comp_int interrupt.
+ 4
+ 1
+ write-only
+
+
+ ARBITRATION_LOST_INT_CLR
+ Set this bit to clear the arbitration_lost_int interrupt.
+ 5
+ 1
+ write-only
+
+
+ MASTER_TRAN_COMP_INT_CLR
+ Set this bit to clear the master_tran_comp interrupt.
+ 6
+ 1
+ write-only
+
+
+ TRANS_COMPLETE_INT_CLR
+ Set this bit to clear the trans_complete_int interrupt.
+ 7
+ 1
+ write-only
+
+
+ TIME_OUT_INT_CLR
+ Set this bit to clear the time_out_int interrupt.
+ 8
+ 1
+ write-only
+
+
+ TRANS_START_INT_CLR
+ Set this bit to clear the trans_start_int interrupt.
+ 9
+ 1
+ write-only
+
+
+ ACK_ERR_INT_CLR
+ Set this bit to clear the ack_err_int interrupt.
+ 10
+ 1
+ write-only
+
+
+ RX_REC_FULL_INT_CLR
+ Set this bit to clear the rx_rec_full_int interrupt.
+ 11
+ 1
+ write-only
+
+
+ TX_SEND_EMPTY_INT_CLR
+ Set this bit to clear the tx_send_empty_int interrupt.
+ 12
+ 1
+ write-only
+
+
+
+
+ INT_ENA
+ 0x28
+ 0x20
+
+
+ RXFIFO_FULL_INT_ENA
+ The enable bit for rxfifo_full_int interrupt.
+ 0
+ 1
+ read-write
+
+
+ TXFIFO_EMPTY_INT_ENA
+ The enable bit for txfifo_empty_int interrupt.
+ 1
+ 1
+ read-write
+
+
+ RXFIFO_OVF_INT_ENA
+ The enable bit for rxfifo_ovf_int interrupt.
+ 2
+ 1
+ read-write
+
+
+ END_DETECT_INT_ENA
+ The enable bit for end_detect_int interrupt.
+ 3
+ 1
+ read-write
+
+
+ SLAVE_TRAN_COMP_INT_ENA
+ The enable bit for slave_tran_comp_int interrupt.
+ 4
+ 1
+ read-write
+
+
+ ARBITRATION_LOST_INT_ENA
+ The enable bit for arbitration_lost_int interrupt.
+ 5
+ 1
+ read-write
+
+
+ MASTER_TRAN_COMP_INT_ENA
+ The enable bit for master_tran_comp_int interrupt.
+ 6
+ 1
+ read-write
+
+
+ TRANS_COMPLETE_INT_ENA
+ The enable bit for trans_complete_int interrupt.
+ 7
+ 1
+ read-write
+
+
+ TIME_OUT_INT_ENA
+ The enable bit for time_out_int interrupt.
+ 8
+ 1
+ read-write
+
+
+ TRANS_START_INT_ENA
+ The enable bit for trans_start_int interrupt.
+ 9
+ 1
+ read-write
+
+
+ ACK_ERR_INT_ENA
+ The enable bit for ack_err_int interrupt.
+ 10
+ 1
+ read-write
+
+
+ RX_REC_FULL_INT_ENA
+ The enable bit for rx_rec_full_int interrupt.
+ 11
+ 1
+ read-write
+
+
+ TX_SEND_EMPTY_INT_ENA
+ The enable bit for tx_send_empty_int interrupt.
+ 12
+ 1
+ read-write
+
+
+
+
+ INT_STATUS
+ 0x2C
+ 0x20
+
+
+ RXFIFO_FULL_INT_ST
+ The masked interrupt status for rxfifo_full_int interrupt.
+ 0
+ 1
+ read-only
+
+
+ TXFIFO_EMPTY_INT_ST
+ The masked interrupt status for txfifo_empty_int interrupt.
+ 1
+ 1
+ read-only
+
+
+ RXFIFO_OVF_INT_ST
+ The masked interrupt status for rxfifo_ovf_int interrupt.
+ 2
+ 1
+ read-only
+
+
+ END_DETECT_INT_ST
+ The masked interrupt status for end_detect_int interrupt.
+ 3
+ 1
+ read-only
+
+
+ SLAVE_TRAN_COMP_INT_ST
+ The masked interrupt status for slave_tran_comp_int interrupt.
+ 4
+ 1
+ read-only
+
+
+ ARBITRATION_LOST_INT_ST
+ The masked interrupt status for arbitration_lost_int interrupt.
+ 5
+ 1
+ read-only
+
+
+ MASTER_TRAN_COMP_INT_ST
+ The masked interrupt status for master_tran_comp_int interrupt.
+ 6
+ 1
+ read-only
+
+
+ TRANS_COMPLETE_INT_ST
+ The masked interrupt status for trans_complete_int interrupt.
+ 7
+ 1
+ read-only
+
+
+ TIME_OUT_INT_ST
+ The masked interrupt status for time_out_int interrupt.
+ 8
+ 1
+ read-only
+
+
+ TRANS_START_INT_ST
+ The masked interrupt status for trans_start_int interrupt.
+ 9
+ 1
+ read-only
+
+
+ ACK_ERR_INT_ST
+ The masked interrupt status for ack_err_int interrupt.
+ 10
+ 1
+ read-only
+
+
+ RX_REC_FULL_INT_ST
+ The masked interrupt status for rx_rec_full_int interrupt.
+ 11
+ 1
+ read-only
+
+
+ TX_SEND_EMPTY_INT_ST
+ The masked interrupt status for tx_send_empty_int interrupt.
+ 12
+ 1
+ read-only
+
+
+
+
+ SDA_HOLD
+ 0x30
+ 0x20
+
+
+ TIME
+ This register is used to configure the clock num I2C used to hold the data after the negedge of SCL.
+ 0
+ 10
+ read-write
+
+
+
+
+ SDA_SAMPLE
+ 0x34
+ 0x20
+
+
+ TIME
+ This register is used to configure the clock num I2C used to sample data on SDA after the posedge of SCL
+ 0
+ 10
+ read-write
+
+
+
+
+ SCL_HIGH_PERIOD
+ 0x38
+ 0x20
+
+
+ SCL_HIGH_PERIOD
+ This register is used to configure the clock num during SCL is low level.
+ 0
+ 14
+ read-write
+
+
+
+
+ SCL_START_HOLD
+ 0x40
+ 0x20
+ 0x00000008
+
+
+ TIME
+ This register is used to configure the clock num between the negedge of SDA and negedge of SCL for start mark.
+ 0
+ 10
+ read-write
+
+
+
+
+ SCL_RSTART_SETUP
+ 0x44
+ 0x20
+ 0x00000008
+
+
+ TIME
+ This register is used to configure the clock num between the posedge of SCL and the negedge of SDA for restart mark.
+ 0
+ 10
+ read-write
+
+
+
+
+ SCL_STOP_HOLD
+ 0x48
+ 0x20
+
+
+ TIME
+ This register is used to configure the clock num after the STOP bit's posedge.
+ 0
+ 14
+ read-write
+
+
+
+
+ SCL_STOP_SETUP
+ 0x4C
+ 0x20
+
+
+ TIME
+ This register is used to configure the clock num between the posedge of SCL and the posedge of SDA.
+ 0
+ 10
+ read-write
+
+
+
+
+ SCL_FILTER_CFG
+ 0x50
+ 0x20
+ 0x00000008
+
+
+ SCL_FILTER_THRES
+ When input SCL's pulse width is smaller than this register value I2C ignores this pulse.
+ 0
+ 3
+ read-write
+
+
+ SCL_FILTER_EN
+ This is the filter enable bit for SCL.
+ 3
+ 1
+ read-write
+
+
+
+
+ SDA_FILTER_CFG
+ 0x54
+ 0x20
+ 0x00000008
+
+
+ SDA_FILTER_THRES
+ When input SCL's pulse width is smaller than this register value I2C ignores this pulse.
+ 0
+ 3
+ read-write
+
+
+ SDA_FILTER_EN
+ This is the filter enable bit for SDA.
+ 3
+ 1
+ read-write
+
+
+
+
+ 16
+ 0x4
+ 0-15
+ COMD%s
+ 0x58
+ 0x20
+
+
+ COMMAND
+ This is the content of command0. It consists of three part. op_code is the command 0: RSTART 1: WRITE 2: READ 3: STOP . 4:END. Byte_num represent the number of data need to be send or data need to be received. ack_check_en ack_exp and ack value are used to control the ack bit.
+ 0
+ 14
+ read-write
+
+
+ COMMAND_DONE
+ When command0 is done in I2C Master mode this bit changes to high level.
+ 31
+ 1
+ read-write
+
+
+
+
+ DATE
+ 0xF8
+ 0x20
+ 0x16042000
+
+
+ DATE
+ 0
+ 32
+ read-write
+
+
+
+
+ FIFO_START_ADDR
+ 0x100
+ 0x20
+
+
+
+
+ I2C1
+ I2C (Inter-Integrated Circuit) Controller
+ 0x3FF67000
+
+ I2C_EXT1
+ 50
+
+
+
+ I2S0
+ I2S (Inter-IC Sound) Controller
+ I2S
+ 0x3FF4F000
+
+ 0x0
+ 0xB4
+ registers
+
+
+ I2S0
+ 32
+
+
+
+ CONF
+ 0x8
+ 0x20
+ 0x00030300
+
+
+ TX_RESET
+ 0
+ 1
+ read-write
+
+
+ RX_RESET
+ 1
+ 1
+ read-write
+
+
+ TX_FIFO_RESET
+ 2
+ 1
+ read-write
+
+
+ RX_FIFO_RESET
+ 3
+ 1
+ read-write
+
+
+ TX_START
+ 4
+ 1
+ read-write
+
+
+ RX_START
+ 5
+ 1
+ read-write
+
+
+ TX_SLAVE_MOD
+ 6
+ 1
+ read-write
+
+
+ RX_SLAVE_MOD
+ 7
+ 1
+ read-write
+
+
+ TX_RIGHT_FIRST
+ 8
+ 1
+ read-write
+
+
+ RX_RIGHT_FIRST
+ 9
+ 1
+ read-write
+
+
+ TX_MSB_SHIFT
+ 10
+ 1
+ read-write
+
+
+ RX_MSB_SHIFT
+ 11
+ 1
+ read-write
+
+
+ TX_SHORT_SYNC
+ 12
+ 1
+ read-write
+
+
+ RX_SHORT_SYNC
+ 13
+ 1
+ read-write
+
+
+ TX_MONO
+ 14
+ 1
+ read-write
+
+
+ RX_MONO
+ 15
+ 1
+ read-write
+
+
+ TX_MSB_RIGHT
+ 16
+ 1
+ read-write
+
+
+ RX_MSB_RIGHT
+ 17
+ 1
+ read-write
+
+
+ SIG_LOOPBACK
+ 18
+ 1
+ read-write
+
+
+
+
+ INT_RAW
+ 0xC
+ 0x20
+
+
+ RX_TAKE_DATA_INT_RAW
+ 0
+ 1
+ read-only
+
+
+ TX_PUT_DATA_INT_RAW
+ 1
+ 1
+ read-only
+
+
+ RX_WFULL_INT_RAW
+ 2
+ 1
+ read-only
+
+
+ RX_REMPTY_INT_RAW
+ 3
+ 1
+ read-only
+
+
+ TX_WFULL_INT_RAW
+ 4
+ 1
+ read-only
+
+
+ TX_REMPTY_INT_RAW
+ 5
+ 1
+ read-only
+
+
+ RX_HUNG_INT_RAW
+ 6
+ 1
+ read-only
+
+
+ TX_HUNG_INT_RAW
+ 7
+ 1
+ read-only
+
+
+ IN_DONE_INT_RAW
+ 8
+ 1
+ read-only
+
+
+ IN_SUC_EOF_INT_RAW
+ 9
+ 1
+ read-only
+
+
+ IN_ERR_EOF_INT_RAW
+ 10
+ 1
+ read-only
+
+
+ OUT_DONE_INT_RAW
+ 11
+ 1
+ read-only
+
+
+ OUT_EOF_INT_RAW
+ 12
+ 1
+ read-only
+
+
+ IN_DSCR_ERR_INT_RAW
+ 13
+ 1
+ read-only
+
+
+ OUT_DSCR_ERR_INT_RAW
+ 14
+ 1
+ read-only
+
+
+ IN_DSCR_EMPTY_INT_RAW
+ 15
+ 1
+ read-only
+
+
+ OUT_TOTAL_EOF_INT_RAW
+ 16
+ 1
+ read-only
+
+
+
+
+ INT_ST
+ 0x10
+ 0x20
+
+
+ RX_TAKE_DATA_INT_ST
+ 0
+ 1
+ read-only
+
+
+ TX_PUT_DATA_INT_ST
+ 1
+ 1
+ read-only
+
+
+ RX_WFULL_INT_ST
+ 2
+ 1
+ read-only
+
+
+ RX_REMPTY_INT_ST
+ 3
+ 1
+ read-only
+
+
+ TX_WFULL_INT_ST
+ 4
+ 1
+ read-only
+
+
+ TX_REMPTY_INT_ST
+ 5
+ 1
+ read-only
+
+
+ RX_HUNG_INT_ST
+ 6
+ 1
+ read-only
+
+
+ TX_HUNG_INT_ST
+ 7
+ 1
+ read-only
+
+
+ IN_DONE_INT_ST
+ 8
+ 1
+ read-only
+
+
+ IN_SUC_EOF_INT_ST
+ 9
+ 1
+ read-only
+
+
+ IN_ERR_EOF_INT_ST
+ 10
+ 1
+ read-only
+
+
+ OUT_DONE_INT_ST
+ 11
+ 1
+ read-only
+
+
+ OUT_EOF_INT_ST
+ 12
+ 1
+ read-only
+
+
+ IN_DSCR_ERR_INT_ST
+ 13
+ 1
+ read-only
+
+
+ OUT_DSCR_ERR_INT_ST
+ 14
+ 1
+ read-only
+
+
+ IN_DSCR_EMPTY_INT_ST
+ 15
+ 1
+ read-only
+
+
+ OUT_TOTAL_EOF_INT_ST
+ 16
+ 1
+ read-only
+
+
+
+
+ INT_ENA
+ 0x14
+ 0x20
+
+
+ RX_TAKE_DATA_INT_ENA
+ 0
+ 1
+ read-write
+
+
+ TX_PUT_DATA_INT_ENA
+ 1
+ 1
+ read-write
+
+
+ RX_WFULL_INT_ENA
+ 2
+ 1
+ read-write
+
+
+ RX_REMPTY_INT_ENA
+ 3
+ 1
+ read-write
+
+
+ TX_WFULL_INT_ENA
+ 4
+ 1
+ read-write
+
+
+ TX_REMPTY_INT_ENA
+ 5
+ 1
+ read-write
+
+
+ RX_HUNG_INT_ENA
+ 6
+ 1
+ read-write
+
+
+ TX_HUNG_INT_ENA
+ 7
+ 1
+ read-write
+
+
+ IN_DONE_INT_ENA
+ 8
+ 1
+ read-write
+
+
+ IN_SUC_EOF_INT_ENA
+ 9
+ 1
+ read-write
+
+
+ IN_ERR_EOF_INT_ENA
+ 10
+ 1
+ read-write
+
+
+ OUT_DONE_INT_ENA
+ 11
+ 1
+ read-write
+
+
+ OUT_EOF_INT_ENA
+ 12
+ 1
+ read-write
+
+
+ IN_DSCR_ERR_INT_ENA
+ 13
+ 1
+ read-write
+
+
+ OUT_DSCR_ERR_INT_ENA
+ 14
+ 1
+ read-write
+
+
+ IN_DSCR_EMPTY_INT_ENA
+ 15
+ 1
+ read-write
+
+
+ OUT_TOTAL_EOF_INT_ENA
+ 16
+ 1
+ read-write
+
+
+
+
+ INT_CLR
+ 0x18
+ 0x20
+
+
+ TAKE_DATA_INT_CLR
+ 0
+ 1
+ write-only
+
+
+ PUT_DATA_INT_CLR
+ 1
+ 1
+ write-only
+
+
+ RX_WFULL_INT_CLR
+ 2
+ 1
+ write-only
+
+
+ RX_REMPTY_INT_CLR
+ 3
+ 1
+ write-only
+
+
+ TX_WFULL_INT_CLR
+ 4
+ 1
+ write-only
+
+
+ TX_REMPTY_INT_CLR
+ 5
+ 1
+ write-only
+
+
+ RX_HUNG_INT_CLR
+ 6
+ 1
+ write-only
+
+
+ TX_HUNG_INT_CLR
+ 7
+ 1
+ write-only
+
+
+ IN_DONE_INT_CLR
+ 8
+ 1
+ write-only
+
+
+ IN_SUC_EOF_INT_CLR
+ 9
+ 1
+ write-only
+
+
+ IN_ERR_EOF_INT_CLR
+ 10
+ 1
+ write-only
+
+
+ OUT_DONE_INT_CLR
+ 11
+ 1
+ write-only
+
+
+ OUT_EOF_INT_CLR
+ 12
+ 1
+ write-only
+
+
+ IN_DSCR_ERR_INT_CLR
+ 13
+ 1
+ write-only
+
+
+ OUT_DSCR_ERR_INT_CLR
+ 14
+ 1
+ write-only
+
+
+ IN_DSCR_EMPTY_INT_CLR
+ 15
+ 1
+ write-only
+
+
+ OUT_TOTAL_EOF_INT_CLR
+ 16
+ 1
+ write-only
+
+
+
+
+ TIMING
+ 0x1C
+ 0x20
+
+
+ TX_BCK_IN_DELAY
+ 0
+ 2
+ read-write
+
+
+ TX_WS_IN_DELAY
+ 2
+ 2
+ read-write
+
+
+ RX_BCK_IN_DELAY
+ 4
+ 2
+ read-write
+
+
+ RX_WS_IN_DELAY
+ 6
+ 2
+ read-write
+
+
+ RX_SD_IN_DELAY
+ 8
+ 2
+ read-write
+
+
+ TX_BCK_OUT_DELAY
+ 10
+ 2
+ read-write
+
+
+ TX_WS_OUT_DELAY
+ 12
+ 2
+ read-write
+
+
+ TX_SD_OUT_DELAY
+ 14
+ 2
+ read-write
+
+
+ RX_WS_OUT_DELAY
+ 16
+ 2
+ read-write
+
+
+ RX_BCK_OUT_DELAY
+ 18
+ 2
+ read-write
+
+
+ TX_DSYNC_SW
+ 20
+ 1
+ read-write
+
+
+ RX_DSYNC_SW
+ 21
+ 1
+ read-write
+
+
+ DATA_ENABLE_DELAY
+ 22
+ 2
+ read-write
+
+
+ TX_BCK_IN_INV
+ 24
+ 1
+ read-write
+
+
+
+
+ FIFO_CONF
+ 0x20
+ 0x20
+ 0x00001820
+
+
+ RX_DATA_NUM
+ 0
+ 6
+ read-write
+
+
+ TX_DATA_NUM
+ 6
+ 6
+ read-write
+
+
+ DSCR_EN
+ 12
+ 1
+ read-write
+
+
+ TX_FIFO_MOD
+ 13
+ 3
+ read-write
+
+
+ RX_FIFO_MOD
+ 16
+ 3
+ read-write
+
+
+ TX_FIFO_MOD_FORCE_EN
+ 19
+ 1
+ read-write
+
+
+ RX_FIFO_MOD_FORCE_EN
+ 20
+ 1
+ read-write
+
+
+
+
+ RXEOF_NUM
+ 0x24
+ 0x20
+ 0x00000040
+
+
+ RX_EOF_NUM
+ 0
+ 32
+ read-write
+
+
+
+
+ CONF_SIGLE_DATA
+ 0x28
+ 0x20
+
+
+ SIGLE_DATA
+ 0
+ 32
+ read-write
+
+
+
+
+ CONF_CHAN
+ 0x2C
+ 0x20
+
+
+ TX_CHAN_MOD
+ 0
+ 3
+ read-write
+
+
+ RX_CHAN_MOD
+ 3
+ 2
+ read-write
+
+
+
+
+ OUT_LINK
+ 0x30
+ 0x20
+
+
+ OUTLINK_ADDR
+ 0
+ 20
+ read-write
+
+
+ OUTLINK_STOP
+ 28
+ 1
+ read-write
+
+
+ OUTLINK_START
+ 29
+ 1
+ read-write
+
+
+ OUTLINK_RESTART
+ 30
+ 1
+ read-write
+
+
+ OUTLINK_PARK
+ 31
+ 1
+ read-only
+
+
+
+
+ IN_LINK
+ 0x34
+ 0x20
+
+
+ INLINK_ADDR
+ 0
+ 20
+ read-write
+
+
+ INLINK_STOP
+ 28
+ 1
+ read-write
+
+
+ INLINK_START
+ 29
+ 1
+ read-write
+
+
+ INLINK_RESTART
+ 30
+ 1
+ read-write
+
+
+ INLINK_PARK
+ 31
+ 1
+ read-only
+
+
+
+
+ OUT_EOF_DES_ADDR
+ 0x38
+ 0x20
+
+
+ OUT_EOF_DES_ADDR
+ 0
+ 32
+ read-only
+
+
+
+
+ IN_EOF_DES_ADDR
+ 0x3C
+ 0x20
+
+
+ IN_SUC_EOF_DES_ADDR
+ 0
+ 32
+ read-only
+
+
+
+
+ OUT_EOF_BFR_DES_ADDR
+ 0x40
+ 0x20
+
+
+ OUT_EOF_BFR_DES_ADDR
+ 0
+ 32
+ read-only
+
+
+
+
+ AHB_TEST
+ 0x44
+ 0x20
+
+
+ AHB_TESTMODE
+ 0
+ 3
+ read-write
+
+
+ AHB_TESTADDR
+ 4
+ 2
+ read-write
+
+
+
+
+ INLINK_DSCR
+ 0x48
+ 0x20
+
+
+ INLINK_DSCR
+ 0
+ 32
+ read-only
+
+
+
+
+ INLINK_DSCR_BF0
+ 0x4C
+ 0x20
+
+
+ INLINK_DSCR_BF0
+ 0
+ 32
+ read-only
+
+
+
+
+ INLINK_DSCR_BF1
+ 0x50
+ 0x20
+
+
+ INLINK_DSCR_BF1
+ 0
+ 32
+ read-only
+
+
+
+
+ OUTLINK_DSCR
+ 0x54
+ 0x20
+
+
+ OUTLINK_DSCR
+ 0
+ 32
+ read-only
+
+
+
+
+ OUTLINK_DSCR_BF0
+ 0x58
+ 0x20
+
+
+ OUTLINK_DSCR_BF0
+ 0
+ 32
+ read-only
+
+
+
+
+ OUTLINK_DSCR_BF1
+ 0x5C
+ 0x20
+
+
+ OUTLINK_DSCR_BF1
+ 0
+ 32
+ read-only
+
+
+
+
+ LC_CONF
+ 0x60
+ 0x20
+ 0x00000100
+
+
+ IN_RST
+ 0
+ 1
+ read-write
+
+
+ OUT_RST
+ 1
+ 1
+ read-write
+
+
+ AHBM_FIFO_RST
+ 2
+ 1
+ read-write
+
+
+ AHBM_RST
+ 3
+ 1
+ read-write
+
+
+ OUT_LOOP_TEST
+ 4
+ 1
+ read-write
+
+
+ IN_LOOP_TEST
+ 5
+ 1
+ read-write
+
+
+ OUT_AUTO_WRBACK
+ 6
+ 1
+ read-write
+
+
+ OUT_NO_RESTART_CLR
+ 7
+ 1
+ read-write
+
+
+ OUT_EOF_MODE
+ 8
+ 1
+ read-write
+
+
+ OUTDSCR_BURST_EN
+ 9
+ 1
+ read-write
+
+
+ INDSCR_BURST_EN
+ 10
+ 1
+ read-write
+
+
+ OUT_DATA_BURST_EN
+ 11
+ 1
+ read-write
+
+
+ CHECK_OWNER
+ 12
+ 1
+ read-write
+
+
+ MEM_TRANS_EN
+ 13
+ 1
+ read-write
+
+
+
+
+ OUTFIFO_PUSH
+ 0x64
+ 0x20
+
+
+ OUTFIFO_WDATA
+ 0
+ 9
+ read-write
+
+
+ OUTFIFO_PUSH
+ 16
+ 1
+ read-write
+
+
+
+
+ INFIFO_POP
+ 0x68
+ 0x20
+
+
+ INFIFO_RDATA
+ 0
+ 12
+ read-only
+
+
+ INFIFO_POP
+ 16
+ 1
+ read-write
+
+
+
+
+ LC_STATE0
+ 0x6C
+ 0x20
+
+
+ LC_STATE0
+ 0
+ 32
+ read-only
+
+
+
+
+ LC_STATE1
+ 0x70
+ 0x20
+
+
+ LC_STATE1
+ 0
+ 32
+ read-only
+
+
+
+
+ LC_HUNG_CONF
+ 0x74
+ 0x20
+ 0x00000810
+
+
+ LC_FIFO_TIMEOUT
+ 0
+ 8
+ read-write
+
+
+ LC_FIFO_TIMEOUT_SHIFT
+ 8
+ 3
+ read-write
+
+
+ LC_FIFO_TIMEOUT_ENA
+ 11
+ 1
+ read-write
+
+
+
+
+ CVSD_CONF0
+ 0x80
+ 0x20
+ 0x80007FFF
+
+
+ CVSD_Y_MAX
+ 0
+ 16
+ read-write
+
+
+ CVSD_Y_MIN
+ 16
+ 16
+ read-write
+
+
+
+
+ CVSD_CONF1
+ 0x84
+ 0x20
+ 0x000A0500
+
+
+ CVSD_SIGMA_MAX
+ 0
+ 16
+ read-write
+
+
+ CVSD_SIGMA_MIN
+ 16
+ 16
+ read-write
+
+
+
+
+ CVSD_CONF2
+ 0x88
+ 0x20
+ 0x000502A4
+
+
+ CVSD_K
+ 0
+ 3
+ read-write
+
+
+ CVSD_J
+ 3
+ 3
+ read-write
+
+
+ CVSD_BETA
+ 6
+ 10
+ read-write
+
+
+ CVSD_H
+ 16
+ 3
+ read-write
+
+
+
+
+ PLC_CONF0
+ 0x8C
+ 0x20
+ 0x08A80339
+
+
+ GOOD_PACK_MAX
+ 0
+ 6
+ read-write
+
+
+ N_ERR_SEG
+ 6
+ 3
+ read-write
+
+
+ SHIFT_RATE
+ 9
+ 3
+ read-write
+
+
+ MAX_SLIDE_SAMPLE
+ 12
+ 8
+ read-write
+
+
+ PACK_LEN_8K
+ 20
+ 5
+ read-write
+
+
+ N_MIN_ERR
+ 25
+ 3
+ read-write
+
+
+
+
+ PLC_CONF1
+ 0x90
+ 0x20
+ 0xA0178A05
+
+
+ BAD_CEF_ATTEN_PARA
+ 0
+ 8
+ read-write
+
+
+ BAD_CEF_ATTEN_PARA_SHIFT
+ 8
+ 4
+ read-write
+
+
+ BAD_OLA_WIN2_PARA_SHIFT
+ 12
+ 4
+ read-write
+
+
+ BAD_OLA_WIN2_PARA
+ 16
+ 8
+ read-write
+
+
+ SLIDE_WIN_LEN
+ 24
+ 8
+ read-write
+
+
+
+
+ PLC_CONF2
+ 0x94
+ 0x20
+ 0x00000028
+
+
+ CVSD_SEG_MOD
+ 0
+ 2
+ read-write
+
+
+ MIN_PERIOD
+ 2
+ 5
+ read-write
+
+
+
+
+ ESCO_CONF0
+ 0x98
+ 0x20
+
+
+ ESCO_EN
+ 0
+ 1
+ read-write
+
+
+ ESCO_CHAN_MOD
+ 1
+ 1
+ read-write
+
+
+ ESCO_CVSD_DEC_PACK_ERR
+ 2
+ 1
+ read-write
+
+
+ ESCO_CVSD_PACK_LEN_8K
+ 3
+ 5
+ read-write
+
+
+ ESCO_CVSD_INF_EN
+ 8
+ 1
+ read-write
+
+
+ CVSD_DEC_START
+ 9
+ 1
+ read-write
+
+
+ CVSD_DEC_RESET
+ 10
+ 1
+ read-write
+
+
+ PLC_EN
+ 11
+ 1
+ read-write
+
+
+ PLC2DMA_EN
+ 12
+ 1
+ read-write
+
+
+
+
+ SCO_CONF0
+ 0x9C
+ 0x20
+
+
+ SCO_WITH_I2S_EN
+ 0
+ 1
+ read-write
+
+
+ SCO_NO_I2S_EN
+ 1
+ 1
+ read-write
+
+
+ CVSD_ENC_START
+ 2
+ 1
+ read-write
+
+
+ CVSD_ENC_RESET
+ 3
+ 1
+ read-write
+
+
+
+
+ CONF1
+ 0xA0
+ 0x20
+ 0x00000089
+
+
+ TX_PCM_CONF
+ 0
+ 3
+ read-write
+
+
+ TX_PCM_BYPASS
+ 3
+ 1
+ read-write
+
+
+ RX_PCM_CONF
+ 4
+ 3
+ read-write
+
+
+ RX_PCM_BYPASS
+ 7
+ 1
+ read-write
+
+
+ TX_STOP_EN
+ 8
+ 1
+ read-write
+
+
+ TX_ZEROS_RM_EN
+ 9
+ 1
+ read-write
+
+
+
+
+ PD_CONF
+ 0xA4
+ 0x20
+ 0x0000000A
+
+
+ FIFO_FORCE_PD
+ 0
+ 1
+ read-write
+
+
+ FIFO_FORCE_PU
+ 1
+ 1
+ read-write
+
+
+ PLC_MEM_FORCE_PD
+ 2
+ 1
+ read-write
+
+
+ PLC_MEM_FORCE_PU
+ 3
+ 1
+ read-write
+
+
+
+
+ CONF2
+ 0xA8
+ 0x20
+
+
+ CAMERA_EN
+ 0
+ 1
+ read-write
+
+
+ LCD_TX_WRX2_EN
+ 1
+ 1
+ read-write
+
+
+ LCD_TX_SDX2_EN
+ 2
+ 1
+ read-write
+
+
+ DATA_ENABLE_TEST_EN
+ 3
+ 1
+ read-write
+
+
+ DATA_ENABLE
+ 4
+ 1
+ read-write
+
+
+ LCD_EN
+ 5
+ 1
+ read-write
+
+
+ EXT_ADC_START_EN
+ 6
+ 1
+ read-write
+
+
+ INTER_VALID_EN
+ 7
+ 1
+ read-write
+
+
+
+
+ CLKM_CONF
+ 0xAC
+ 0x20
+ 0x00000004
+
+
+ CLKM_DIV_NUM
+ 0
+ 8
+ read-write
+
+
+ CLKM_DIV_B
+ 8
+ 6
+ read-write
+
+
+ CLKM_DIV_A
+ 14
+ 6
+ read-write
+
+
+ CLK_EN
+ 20
+ 1
+ read-write
+
+
+ CLKA_ENA
+ 21
+ 1
+ read-write
+
+
+
+
+ SAMPLE_RATE_CONF
+ 0xB0
+ 0x20
+ 0x00410186
+
+
+ TX_BCK_DIV_NUM
+ 0
+ 6
+ read-write
+
+
+ RX_BCK_DIV_NUM
+ 6
+ 6
+ read-write
+
+
+ TX_BITS_MOD
+ 12
+ 6
+ read-write
+
+
+ RX_BITS_MOD
+ 18
+ 6
+ read-write
+
+
+
+
+ PDM_CONF
+ 0xB4
+ 0x20
+ 0x01550020
+
+
+ TX_PDM_EN
+ 0
+ 1
+ read-write
+
+
+ RX_PDM_EN
+ 1
+ 1
+ read-write
+
+
+ PCM2PDM_CONV_EN
+ 2
+ 1
+ read-write
+
+
+ PDM2PCM_CONV_EN
+ 3
+ 1
+ read-write
+
+
+ TX_PDM_SINC_OSR2
+ 4
+ 4
+ read-write
+
+
+ TX_PDM_PRESCALE
+ 8
+ 8
+ read-write
+
+
+ TX_PDM_HP_IN_SHIFT
+ 16
+ 2
+ read-write
+
+
+ TX_PDM_LP_IN_SHIFT
+ 18
+ 2
+ read-write
+
+
+ TX_PDM_SINC_IN_SHIFT
+ 20
+ 2
+ read-write
+
+
+ TX_PDM_SIGMADELTA_IN_SHIFT
+ 22
+ 2
+ read-write
+
+
+ RX_PDM_SINC_DSR_16_EN
+ 24
+ 1
+ read-write
+
+
+ TX_PDM_HP_BYPASS
+ 25
+ 1
+ read-write
+
+
+
+
+ PDM_FREQ_CONF
+ 0xB8
+ 0x20
+ 0x000F01E0
+
+
+ TX_PDM_FS
+ 0
+ 10
+ read-write
+
+
+ TX_PDM_FP
+ 10
+ 10
+ read-write
+
+
+
+
+ STATE
+ 0xBC
+ 0x20
+ 0x00000007
+
+
+ TX_IDLE
+ 0
+ 1
+ read-only
+
+
+ TX_FIFO_RESET_BACK
+ 1
+ 1
+ read-only
+
+
+ RX_FIFO_RESET_BACK
+ 2
+ 1
+ read-only
+
+
+
+
+ DATE
+ 0xFC
+ 0x20
+ 0x01604201
+
+
+ I2SDATE
+ 0
+ 32
+ read-write
+
+
+
+
+
+
+ I2S1
+ I2S (Inter-IC Sound) Controller
+ 0x3FF6D000
+
+ I2S1
+ 33
+
+
+
+ IO_MUX
+ Input/Output Multiplexer
+ IO_MUX
+ 0x3FF49000
+
+ 0x0
+ 0x94
+ registers
+
+
+
+ PIN_CTRL
+ 0x0
+ 0x20
+
+
+ CLK1
+ If you want to output clock for I2S0 to: CLK_OUT1, then set PIN_CTRL[3:0] = 0x0; CLK_OUT2, then set PIN_CTRL[3:0] = 0x0 and PIN_CTRL[7:4] = 0x0; CLK_OUT3, then set PIN_CTRL[3:0] = 0x0 and PIN_CTRL[11:8] = 0x0. If you want to output clock for I2S1 to: CLK_OUT1, then set PIN_CTRL[3:0] = 0xF; CLK_OUT2, then set PIN_CTRL[3:0] = 0xF and PIN_CTRL[7:4] = 0x0; CLK_OUT3, then set PIN_CTRL[3:0] = 0xF and PIN_CTRL[11:8] = 0x0.
+ 0
+ 4
+ read-write
+
+
+ CLK2
+ If you want to output clock for I2S0 to: CLK_OUT1, then set PIN_CTRL[3:0] = 0x0; CLK_OUT2, then set PIN_CTRL[3:0] = 0x0 and PIN_CTRL[7:4] = 0x0; CLK_OUT3, then set PIN_CTRL[3:0] = 0x0 and PIN_CTRL[11:8] = 0x0. If you want to output clock for I2S1 to: CLK_OUT1, then set PIN_CTRL[3:0] = 0xF; CLK_OUT2, then set PIN_CTRL[3:0] = 0xF and PIN_CTRL[7:4] = 0x0; CLK_OUT3, then set PIN_CTRL[3:0] = 0xF and PIN_CTRL[11:8] = 0x0.
+ 4
+ 4
+ read-write
+
+
+ CLK3
+ If you want to output clock for I2S0 to: CLK_OUT1, then set PIN_CTRL[3:0] = 0x0; CLK_OUT2, then set PIN_CTRL[3:0] = 0x0 and PIN_CTRL[7:4] = 0x0; CLK_OUT3, then set PIN_CTRL[3:0] = 0x0 and PIN_CTRL[11:8] = 0x0. If you want to output clock for I2S1 to: CLK_OUT1, then set PIN_CTRL[3:0] = 0xF; CLK_OUT2, then set PIN_CTRL[3:0] = 0xF and PIN_CTRL[7:4] = 0x0; CLK_OUT3, then set PIN_CTRL[3:0] = 0xF and PIN_CTRL[11:8] = 0x0.
+ 8
+ 4
+ read-write
+
+
+
+
+ GPIO36
+ 0x4
+ 0x20
+
+
+ MCU_OE
+ Output enable of the pad in sleep mode. 1: enable output; 0: disable output.
+ 0
+ 1
+ read-write
+
+
+ SLP_SEL
+ Sleep mode selection of this pad. Set to 1 to put the pad in sleep mode.
+ 1
+ 1
+ read-write
+
+
+ MCU_WPD
+ Pull-down enable of the pad during sleep mode. 1: internal pull-down enabled; 0: internal pull-down disabled.
+ 2
+ 1
+ read-write
+
+
+ MCU_WPU
+ Pull-up enable of the pad during sleep mode. 1: internal pull-up enabled; 0: internal pull-up disabled.
+ 3
+ 1
+ read-write
+
+
+ MCU_IE
+ Input enable of the pad during sleep mode. 1: input enabled; 0: input disabled.
+ 4
+ 1
+ read-write
+
+
+ MCU_DRV
+ Select the drive strength of the pad during sleep mode. A higher value corresponds with a higher strength.
+ 5
+ 2
+ read-write
+
+
+ FUN_WPD
+ Pull-down enable of the pad. 1: internal pull-down enabled, 0: internal pull-down disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull-down circuitry, therefore, their FUN_WPD is always 0.
+ 7
+ 1
+ read-write
+
+
+ FUN_WPU
+ Pull-up enable of the pad. 1: internal pull-up enabled; 0: internal pull-up disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull- down circuitry, therefore, their FUN_WPU is always 0.
+ 8
+ 1
+ read-write
+
+
+ FUN_IE
+ Input enable of the pad. 1: input enabled; 0: input disabled.
+ 9
+ 1
+ read-write
+
+
+ FUN_DRV
+ Select the drive strength of the pad. A higher value corresponds with a higher strength. For GPIO34-39, FUN_DRV is always 0. For detailed drive strength, please see note 8 in Table ”Notes on ESP32 Pin Lists”, in ESP32 Datasheet.
+ 10
+ 2
+ read-write
+
+
+ MCU_SEL
+ Select the IO_MUX function for this signal. 0 selects Function 0, 1 selects Function 1, etc.
+ 12
+ 3
+ read-write
+
+
+
+
+ GPIO37
+ 0x8
+ 0x20
+
+
+ MCU_OE
+ Output enable of the pad in sleep mode. 1: enable output; 0: disable output.
+ 0
+ 1
+ read-write
+
+
+ SLP_SEL
+ Sleep mode selection of this pad. Set to 1 to put the pad in sleep mode.
+ 1
+ 1
+ read-write
+
+
+ MCU_WPD
+ Pull-down enable of the pad during sleep mode. 1: internal pull-down enabled; 0: internal pull-down disabled.
+ 2
+ 1
+ read-write
+
+
+ MCU_WPU
+ Pull-up enable of the pad during sleep mode. 1: internal pull-up enabled; 0: internal pull-up disabled.
+ 3
+ 1
+ read-write
+
+
+ MCU_IE
+ Input enable of the pad during sleep mode. 1: input enabled; 0: input disabled.
+ 4
+ 1
+ read-write
+
+
+ MCU_DRV
+ Select the drive strength of the pad during sleep mode. A higher value corresponds with a higher strength.
+ 5
+ 2
+ read-write
+
+
+ FUN_WPD
+ Pull-down enable of the pad. 1: internal pull-down enabled, 0: internal pull-down disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull-down circuitry, therefore, their FUN_WPD is always 0.
+ 7
+ 1
+ read-write
+
+
+ FUN_WPU
+ Pull-up enable of the pad. 1: internal pull-up enabled; 0: internal pull-up disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull- down circuitry, therefore, their FUN_WPU is always 0.
+ 8
+ 1
+ read-write
+
+
+ FUN_IE
+ Input enable of the pad. 1: input enabled; 0: input disabled.
+ 9
+ 1
+ read-write
+
+
+ FUN_DRV
+ Select the drive strength of the pad. A higher value corresponds with a higher strength. For GPIO34-39, FUN_DRV is always 0. For detailed drive strength, please see note 8 in Table ”Notes on ESP32 Pin Lists”, in ESP32 Datasheet.
+ 10
+ 2
+ read-write
+
+
+ MCU_SEL
+ Select the IO_MUX function for this signal. 0 selects Function 0, 1 selects Function 1, etc.
+ 12
+ 3
+ read-write
+
+
+
+
+ GPIO38
+ 0xC
+ 0x20
+
+
+ MCU_OE
+ Output enable of the pad in sleep mode. 1: enable output; 0: disable output.
+ 0
+ 1
+ read-write
+
+
+ SLP_SEL
+ Sleep mode selection of this pad. Set to 1 to put the pad in sleep mode.
+ 1
+ 1
+ read-write
+
+
+ MCU_WPD
+ Pull-down enable of the pad during sleep mode. 1: internal pull-down enabled; 0: internal pull-down disabled.
+ 2
+ 1
+ read-write
+
+
+ MCU_WPU
+ Pull-up enable of the pad during sleep mode. 1: internal pull-up enabled; 0: internal pull-up disabled.
+ 3
+ 1
+ read-write
+
+
+ MCU_IE
+ Input enable of the pad during sleep mode. 1: input enabled; 0: input disabled.
+ 4
+ 1
+ read-write
+
+
+ MCU_DRV
+ Select the drive strength of the pad during sleep mode. A higher value corresponds with a higher strength.
+ 5
+ 2
+ read-write
+
+
+ FUN_WPD
+ Pull-down enable of the pad. 1: internal pull-down enabled, 0: internal pull-down disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull-down circuitry, therefore, their FUN_WPD is always 0.
+ 7
+ 1
+ read-write
+
+
+ FUN_WPU
+ Pull-up enable of the pad. 1: internal pull-up enabled; 0: internal pull-up disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull- down circuitry, therefore, their FUN_WPU is always 0.
+ 8
+ 1
+ read-write
+
+
+ FUN_IE
+ Input enable of the pad. 1: input enabled; 0: input disabled.
+ 9
+ 1
+ read-write
+
+
+ FUN_DRV
+ Select the drive strength of the pad. A higher value corresponds with a higher strength. For GPIO34-39, FUN_DRV is always 0. For detailed drive strength, please see note 8 in Table ”Notes on ESP32 Pin Lists”, in ESP32 Datasheet.
+ 10
+ 2
+ read-write
+
+
+ MCU_SEL
+ Select the IO_MUX function for this signal. 0 selects Function 0, 1 selects Function 1, etc.
+ 12
+ 3
+ read-write
+
+
+
+
+ GPIO39
+ 0x10
+ 0x20
+
+
+ MCU_OE
+ Output enable of the pad in sleep mode. 1: enable output; 0: disable output.
+ 0
+ 1
+ read-write
+
+
+ SLP_SEL
+ Sleep mode selection of this pad. Set to 1 to put the pad in sleep mode.
+ 1
+ 1
+ read-write
+
+
+ MCU_WPD
+ Pull-down enable of the pad during sleep mode. 1: internal pull-down enabled; 0: internal pull-down disabled.
+ 2
+ 1
+ read-write
+
+
+ MCU_WPU
+ Pull-up enable of the pad during sleep mode. 1: internal pull-up enabled; 0: internal pull-up disabled.
+ 3
+ 1
+ read-write
+
+
+ MCU_IE
+ Input enable of the pad during sleep mode. 1: input enabled; 0: input disabled.
+ 4
+ 1
+ read-write
+
+
+ MCU_DRV
+ Select the drive strength of the pad during sleep mode. A higher value corresponds with a higher strength.
+ 5
+ 2
+ read-write
+
+
+ FUN_WPD
+ Pull-down enable of the pad. 1: internal pull-down enabled, 0: internal pull-down disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull-down circuitry, therefore, their FUN_WPD is always 0.
+ 7
+ 1
+ read-write
+
+
+ FUN_WPU
+ Pull-up enable of the pad. 1: internal pull-up enabled; 0: internal pull-up disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull- down circuitry, therefore, their FUN_WPU is always 0.
+ 8
+ 1
+ read-write
+
+
+ FUN_IE
+ Input enable of the pad. 1: input enabled; 0: input disabled.
+ 9
+ 1
+ read-write
+
+
+ FUN_DRV
+ Select the drive strength of the pad. A higher value corresponds with a higher strength. For GPIO34-39, FUN_DRV is always 0. For detailed drive strength, please see note 8 in Table ”Notes on ESP32 Pin Lists”, in ESP32 Datasheet.
+ 10
+ 2
+ read-write
+
+
+ MCU_SEL
+ Select the IO_MUX function for this signal. 0 selects Function 0, 1 selects Function 1, etc.
+ 12
+ 3
+ read-write
+
+
+
+
+ GPIO34
+ 0x14
+ 0x20
+
+
+ MCU_OE
+ Output enable of the pad in sleep mode. 1: enable output; 0: disable output.
+ 0
+ 1
+ read-write
+
+
+ SLP_SEL
+ Sleep mode selection of this pad. Set to 1 to put the pad in sleep mode.
+ 1
+ 1
+ read-write
+
+
+ MCU_WPD
+ Pull-down enable of the pad during sleep mode. 1: internal pull-down enabled; 0: internal pull-down disabled.
+ 2
+ 1
+ read-write
+
+
+ MCU_WPU
+ Pull-up enable of the pad during sleep mode. 1: internal pull-up enabled; 0: internal pull-up disabled.
+ 3
+ 1
+ read-write
+
+
+ MCU_IE
+ Input enable of the pad during sleep mode. 1: input enabled; 0: input disabled.
+ 4
+ 1
+ read-write
+
+
+ MCU_DRV
+ Select the drive strength of the pad during sleep mode. A higher value corresponds with a higher strength.
+ 5
+ 2
+ read-write
+
+
+ FUN_WPD
+ Pull-down enable of the pad. 1: internal pull-down enabled, 0: internal pull-down disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull-down circuitry, therefore, their FUN_WPD is always 0.
+ 7
+ 1
+ read-write
+
+
+ FUN_WPU
+ Pull-up enable of the pad. 1: internal pull-up enabled; 0: internal pull-up disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull- down circuitry, therefore, their FUN_WPU is always 0.
+ 8
+ 1
+ read-write
+
+
+ FUN_IE
+ Input enable of the pad. 1: input enabled; 0: input disabled.
+ 9
+ 1
+ read-write
+
+
+ FUN_DRV
+ Select the drive strength of the pad. A higher value corresponds with a higher strength. For GPIO34-39, FUN_DRV is always 0. For detailed drive strength, please see note 8 in Table ”Notes on ESP32 Pin Lists”, in ESP32 Datasheet.
+ 10
+ 2
+ read-write
+
+
+ MCU_SEL
+ Select the IO_MUX function for this signal. 0 selects Function 0, 1 selects Function 1, etc.
+ 12
+ 3
+ read-write
+
+
+
+
+ GPIO35
+ 0x18
+ 0x20
+
+
+ MCU_OE
+ Output enable of the pad in sleep mode. 1: enable output; 0: disable output.
+ 0
+ 1
+ read-write
+
+
+ SLP_SEL
+ Sleep mode selection of this pad. Set to 1 to put the pad in sleep mode.
+ 1
+ 1
+ read-write
+
+
+ MCU_WPD
+ Pull-down enable of the pad during sleep mode. 1: internal pull-down enabled; 0: internal pull-down disabled.
+ 2
+ 1
+ read-write
+
+
+ MCU_WPU
+ Pull-up enable of the pad during sleep mode. 1: internal pull-up enabled; 0: internal pull-up disabled.
+ 3
+ 1
+ read-write
+
+
+ MCU_IE
+ Input enable of the pad during sleep mode. 1: input enabled; 0: input disabled.
+ 4
+ 1
+ read-write
+
+
+ MCU_DRV
+ Select the drive strength of the pad during sleep mode. A higher value corresponds with a higher strength.
+ 5
+ 2
+ read-write
+
+
+ FUN_WPD
+ Pull-down enable of the pad. 1: internal pull-down enabled, 0: internal pull-down disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull-down circuitry, therefore, their FUN_WPD is always 0.
+ 7
+ 1
+ read-write
+
+
+ FUN_WPU
+ Pull-up enable of the pad. 1: internal pull-up enabled; 0: internal pull-up disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull- down circuitry, therefore, their FUN_WPU is always 0.
+ 8
+ 1
+ read-write
+
+
+ FUN_IE
+ Input enable of the pad. 1: input enabled; 0: input disabled.
+ 9
+ 1
+ read-write
+
+
+ FUN_DRV
+ Select the drive strength of the pad. A higher value corresponds with a higher strength. For GPIO34-39, FUN_DRV is always 0. For detailed drive strength, please see note 8 in Table ”Notes on ESP32 Pin Lists”, in ESP32 Datasheet.
+ 10
+ 2
+ read-write
+
+
+ MCU_SEL
+ Select the IO_MUX function for this signal. 0 selects Function 0, 1 selects Function 1, etc.
+ 12
+ 3
+ read-write
+
+
+
+
+ GPIO32
+ 0x1C
+ 0x20
+
+
+ MCU_OE
+ Output enable of the pad in sleep mode. 1: enable output; 0: disable output.
+ 0
+ 1
+ read-write
+
+
+ SLP_SEL
+ Sleep mode selection of this pad. Set to 1 to put the pad in sleep mode.
+ 1
+ 1
+ read-write
+
+
+ MCU_WPD
+ Pull-down enable of the pad during sleep mode. 1: internal pull-down enabled; 0: internal pull-down disabled.
+ 2
+ 1
+ read-write
+
+
+ MCU_WPU
+ Pull-up enable of the pad during sleep mode. 1: internal pull-up enabled; 0: internal pull-up disabled.
+ 3
+ 1
+ read-write
+
+
+ MCU_IE
+ Input enable of the pad during sleep mode. 1: input enabled; 0: input disabled.
+ 4
+ 1
+ read-write
+
+
+ MCU_DRV
+ Select the drive strength of the pad during sleep mode. A higher value corresponds with a higher strength.
+ 5
+ 2
+ read-write
+
+
+ FUN_WPD
+ Pull-down enable of the pad. 1: internal pull-down enabled, 0: internal pull-down disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull-down circuitry, therefore, their FUN_WPD is always 0.
+ 7
+ 1
+ read-write
+
+
+ FUN_WPU
+ Pull-up enable of the pad. 1: internal pull-up enabled; 0: internal pull-up disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull- down circuitry, therefore, their FUN_WPU is always 0.
+ 8
+ 1
+ read-write
+
+
+ FUN_IE
+ Input enable of the pad. 1: input enabled; 0: input disabled.
+ 9
+ 1
+ read-write
+
+
+ FUN_DRV
+ Select the drive strength of the pad. A higher value corresponds with a higher strength. For GPIO34-39, FUN_DRV is always 0. For detailed drive strength, please see note 8 in Table ”Notes on ESP32 Pin Lists”, in ESP32 Datasheet.
+ 10
+ 2
+ read-write
+
+
+ MCU_SEL
+ Select the IO_MUX function for this signal. 0 selects Function 0, 1 selects Function 1, etc.
+ 12
+ 3
+ read-write
+
+
+
+
+ GPIO33
+ 0x20
+ 0x20
+
+
+ MCU_OE
+ Output enable of the pad in sleep mode. 1: enable output; 0: disable output.
+ 0
+ 1
+ read-write
+
+
+ SLP_SEL
+ Sleep mode selection of this pad. Set to 1 to put the pad in sleep mode.
+ 1
+ 1
+ read-write
+
+
+ MCU_WPD
+ Pull-down enable of the pad during sleep mode. 1: internal pull-down enabled; 0: internal pull-down disabled.
+ 2
+ 1
+ read-write
+
+
+ MCU_WPU
+ Pull-up enable of the pad during sleep mode. 1: internal pull-up enabled; 0: internal pull-up disabled.
+ 3
+ 1
+ read-write
+
+
+ MCU_IE
+ Input enable of the pad during sleep mode. 1: input enabled; 0: input disabled.
+ 4
+ 1
+ read-write
+
+
+ MCU_DRV
+ Select the drive strength of the pad during sleep mode. A higher value corresponds with a higher strength.
+ 5
+ 2
+ read-write
+
+
+ FUN_WPD
+ Pull-down enable of the pad. 1: internal pull-down enabled, 0: internal pull-down disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull-down circuitry, therefore, their FUN_WPD is always 0.
+ 7
+ 1
+ read-write
+
+
+ FUN_WPU
+ Pull-up enable of the pad. 1: internal pull-up enabled; 0: internal pull-up disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull- down circuitry, therefore, their FUN_WPU is always 0.
+ 8
+ 1
+ read-write
+
+
+ FUN_IE
+ Input enable of the pad. 1: input enabled; 0: input disabled.
+ 9
+ 1
+ read-write
+
+
+ FUN_DRV
+ Select the drive strength of the pad. A higher value corresponds with a higher strength. For GPIO34-39, FUN_DRV is always 0. For detailed drive strength, please see note 8 in Table ”Notes on ESP32 Pin Lists”, in ESP32 Datasheet.
+ 10
+ 2
+ read-write
+
+
+ MCU_SEL
+ Select the IO_MUX function for this signal. 0 selects Function 0, 1 selects Function 1, etc.
+ 12
+ 3
+ read-write
+
+
+
+
+ GPIO25
+ 0x24
+ 0x20
+
+
+ MCU_OE
+ Output enable of the pad in sleep mode. 1: enable output; 0: disable output.
+ 0
+ 1
+ read-write
+
+
+ SLP_SEL
+ Sleep mode selection of this pad. Set to 1 to put the pad in sleep mode.
+ 1
+ 1
+ read-write
+
+
+ MCU_WPD
+ Pull-down enable of the pad during sleep mode. 1: internal pull-down enabled; 0: internal pull-down disabled.
+ 2
+ 1
+ read-write
+
+
+ MCU_WPU
+ Pull-up enable of the pad during sleep mode. 1: internal pull-up enabled; 0: internal pull-up disabled.
+ 3
+ 1
+ read-write
+
+
+ MCU_IE
+ Input enable of the pad during sleep mode. 1: input enabled; 0: input disabled.
+ 4
+ 1
+ read-write
+
+
+ MCU_DRV
+ Select the drive strength of the pad during sleep mode. A higher value corresponds with a higher strength.
+ 5
+ 2
+ read-write
+
+
+ FUN_WPD
+ Pull-down enable of the pad. 1: internal pull-down enabled, 0: internal pull-down disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull-down circuitry, therefore, their FUN_WPD is always 0.
+ 7
+ 1
+ read-write
+
+
+ FUN_WPU
+ Pull-up enable of the pad. 1: internal pull-up enabled; 0: internal pull-up disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull- down circuitry, therefore, their FUN_WPU is always 0.
+ 8
+ 1
+ read-write
+
+
+ FUN_IE
+ Input enable of the pad. 1: input enabled; 0: input disabled.
+ 9
+ 1
+ read-write
+
+
+ FUN_DRV
+ Select the drive strength of the pad. A higher value corresponds with a higher strength. For GPIO34-39, FUN_DRV is always 0. For detailed drive strength, please see note 8 in Table ”Notes on ESP32 Pin Lists”, in ESP32 Datasheet.
+ 10
+ 2
+ read-write
+
+
+ MCU_SEL
+ Select the IO_MUX function for this signal. 0 selects Function 0, 1 selects Function 1, etc.
+ 12
+ 3
+ read-write
+
+
+
+
+ GPIO26
+ 0x28
+ 0x20
+
+
+ MCU_OE
+ Output enable of the pad in sleep mode. 1: enable output; 0: disable output.
+ 0
+ 1
+ read-write
+
+
+ SLP_SEL
+ Sleep mode selection of this pad. Set to 1 to put the pad in sleep mode.
+ 1
+ 1
+ read-write
+
+
+ MCU_WPD
+ Pull-down enable of the pad during sleep mode. 1: internal pull-down enabled; 0: internal pull-down disabled.
+ 2
+ 1
+ read-write
+
+
+ MCU_WPU
+ Pull-up enable of the pad during sleep mode. 1: internal pull-up enabled; 0: internal pull-up disabled.
+ 3
+ 1
+ read-write
+
+
+ MCU_IE
+ Input enable of the pad during sleep mode. 1: input enabled; 0: input disabled.
+ 4
+ 1
+ read-write
+
+
+ MCU_DRV
+ Select the drive strength of the pad during sleep mode. A higher value corresponds with a higher strength.
+ 5
+ 2
+ read-write
+
+
+ FUN_WPD
+ Pull-down enable of the pad. 1: internal pull-down enabled, 0: internal pull-down disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull-down circuitry, therefore, their FUN_WPD is always 0.
+ 7
+ 1
+ read-write
+
+
+ FUN_WPU
+ Pull-up enable of the pad. 1: internal pull-up enabled; 0: internal pull-up disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull- down circuitry, therefore, their FUN_WPU is always 0.
+ 8
+ 1
+ read-write
+
+
+ FUN_IE
+ Input enable of the pad. 1: input enabled; 0: input disabled.
+ 9
+ 1
+ read-write
+
+
+ FUN_DRV
+ Select the drive strength of the pad. A higher value corresponds with a higher strength. For GPIO34-39, FUN_DRV is always 0. For detailed drive strength, please see note 8 in Table ”Notes on ESP32 Pin Lists”, in ESP32 Datasheet.
+ 10
+ 2
+ read-write
+
+
+ MCU_SEL
+ Select the IO_MUX function for this signal. 0 selects Function 0, 1 selects Function 1, etc.
+ 12
+ 3
+ read-write
+
+
+
+
+ GPIO27
+ 0x2C
+ 0x20
+
+
+ MCU_OE
+ Output enable of the pad in sleep mode. 1: enable output; 0: disable output.
+ 0
+ 1
+ read-write
+
+
+ SLP_SEL
+ Sleep mode selection of this pad. Set to 1 to put the pad in sleep mode.
+ 1
+ 1
+ read-write
+
+
+ MCU_WPD
+ Pull-down enable of the pad during sleep mode. 1: internal pull-down enabled; 0: internal pull-down disabled.
+ 2
+ 1
+ read-write
+
+
+ MCU_WPU
+ Pull-up enable of the pad during sleep mode. 1: internal pull-up enabled; 0: internal pull-up disabled.
+ 3
+ 1
+ read-write
+
+
+ MCU_IE
+ Input enable of the pad during sleep mode. 1: input enabled; 0: input disabled.
+ 4
+ 1
+ read-write
+
+
+ MCU_DRV
+ Select the drive strength of the pad during sleep mode. A higher value corresponds with a higher strength.
+ 5
+ 2
+ read-write
+
+
+ FUN_WPD
+ Pull-down enable of the pad. 1: internal pull-down enabled, 0: internal pull-down disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull-down circuitry, therefore, their FUN_WPD is always 0.
+ 7
+ 1
+ read-write
+
+
+ FUN_WPU
+ Pull-up enable of the pad. 1: internal pull-up enabled; 0: internal pull-up disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull- down circuitry, therefore, their FUN_WPU is always 0.
+ 8
+ 1
+ read-write
+
+
+ FUN_IE
+ Input enable of the pad. 1: input enabled; 0: input disabled.
+ 9
+ 1
+ read-write
+
+
+ FUN_DRV
+ Select the drive strength of the pad. A higher value corresponds with a higher strength. For GPIO34-39, FUN_DRV is always 0. For detailed drive strength, please see note 8 in Table ”Notes on ESP32 Pin Lists”, in ESP32 Datasheet.
+ 10
+ 2
+ read-write
+
+
+ MCU_SEL
+ Select the IO_MUX function for this signal. 0 selects Function 0, 1 selects Function 1, etc.
+ 12
+ 3
+ read-write
+
+
+
+
+ GPIO14
+ 0x30
+ 0x20
+
+
+ MCU_OE
+ Output enable of the pad in sleep mode. 1: enable output; 0: disable output.
+ 0
+ 1
+ read-write
+
+
+ SLP_SEL
+ Sleep mode selection of this pad. Set to 1 to put the pad in sleep mode.
+ 1
+ 1
+ read-write
+
+
+ MCU_WPD
+ Pull-down enable of the pad during sleep mode. 1: internal pull-down enabled; 0: internal pull-down disabled.
+ 2
+ 1
+ read-write
+
+
+ MCU_WPU
+ Pull-up enable of the pad during sleep mode. 1: internal pull-up enabled; 0: internal pull-up disabled.
+ 3
+ 1
+ read-write
+
+
+ MCU_IE
+ Input enable of the pad during sleep mode. 1: input enabled; 0: input disabled.
+ 4
+ 1
+ read-write
+
+
+ MCU_DRV
+ Select the drive strength of the pad during sleep mode. A higher value corresponds with a higher strength.
+ 5
+ 2
+ read-write
+
+
+ FUN_WPD
+ Pull-down enable of the pad. 1: internal pull-down enabled, 0: internal pull-down disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull-down circuitry, therefore, their FUN_WPD is always 0.
+ 7
+ 1
+ read-write
+
+
+ FUN_WPU
+ Pull-up enable of the pad. 1: internal pull-up enabled; 0: internal pull-up disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull- down circuitry, therefore, their FUN_WPU is always 0.
+ 8
+ 1
+ read-write
+
+
+ FUN_IE
+ Input enable of the pad. 1: input enabled; 0: input disabled.
+ 9
+ 1
+ read-write
+
+
+ FUN_DRV
+ Select the drive strength of the pad. A higher value corresponds with a higher strength. For GPIO34-39, FUN_DRV is always 0. For detailed drive strength, please see note 8 in Table ”Notes on ESP32 Pin Lists”, in ESP32 Datasheet.
+ 10
+ 2
+ read-write
+
+
+ MCU_SEL
+ Select the IO_MUX function for this signal. 0 selects Function 0, 1 selects Function 1, etc.
+ 12
+ 3
+ read-write
+
+
+
+
+ GPIO12
+ 0x34
+ 0x20
+
+
+ MCU_OE
+ Output enable of the pad in sleep mode. 1: enable output; 0: disable output.
+ 0
+ 1
+ read-write
+
+
+ SLP_SEL
+ Sleep mode selection of this pad. Set to 1 to put the pad in sleep mode.
+ 1
+ 1
+ read-write
+
+
+ MCU_WPD
+ Pull-down enable of the pad during sleep mode. 1: internal pull-down enabled; 0: internal pull-down disabled.
+ 2
+ 1
+ read-write
+
+
+ MCU_WPU
+ Pull-up enable of the pad during sleep mode. 1: internal pull-up enabled; 0: internal pull-up disabled.
+ 3
+ 1
+ read-write
+
+
+ MCU_IE
+ Input enable of the pad during sleep mode. 1: input enabled; 0: input disabled.
+ 4
+ 1
+ read-write
+
+
+ MCU_DRV
+ Select the drive strength of the pad during sleep mode. A higher value corresponds with a higher strength.
+ 5
+ 2
+ read-write
+
+
+ FUN_WPD
+ Pull-down enable of the pad. 1: internal pull-down enabled, 0: internal pull-down disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull-down circuitry, therefore, their FUN_WPD is always 0.
+ 7
+ 1
+ read-write
+
+
+ FUN_WPU
+ Pull-up enable of the pad. 1: internal pull-up enabled; 0: internal pull-up disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull- down circuitry, therefore, their FUN_WPU is always 0.
+ 8
+ 1
+ read-write
+
+
+ FUN_IE
+ Input enable of the pad. 1: input enabled; 0: input disabled.
+ 9
+ 1
+ read-write
+
+
+ FUN_DRV
+ Select the drive strength of the pad. A higher value corresponds with a higher strength. For GPIO34-39, FUN_DRV is always 0. For detailed drive strength, please see note 8 in Table ”Notes on ESP32 Pin Lists”, in ESP32 Datasheet.
+ 10
+ 2
+ read-write
+
+
+ MCU_SEL
+ Select the IO_MUX function for this signal. 0 selects Function 0, 1 selects Function 1, etc.
+ 12
+ 3
+ read-write
+
+
+
+
+ GPIO13
+ 0x38
+ 0x20
+
+
+ MCU_OE
+ Output enable of the pad in sleep mode. 1: enable output; 0: disable output.
+ 0
+ 1
+ read-write
+
+
+ SLP_SEL
+ Sleep mode selection of this pad. Set to 1 to put the pad in sleep mode.
+ 1
+ 1
+ read-write
+
+
+ MCU_WPD
+ Pull-down enable of the pad during sleep mode. 1: internal pull-down enabled; 0: internal pull-down disabled.
+ 2
+ 1
+ read-write
+
+
+ MCU_WPU
+ Pull-up enable of the pad during sleep mode. 1: internal pull-up enabled; 0: internal pull-up disabled.
+ 3
+ 1
+ read-write
+
+
+ MCU_IE
+ Input enable of the pad during sleep mode. 1: input enabled; 0: input disabled.
+ 4
+ 1
+ read-write
+
+
+ MCU_DRV
+ Select the drive strength of the pad during sleep mode. A higher value corresponds with a higher strength.
+ 5
+ 2
+ read-write
+
+
+ FUN_WPD
+ Pull-down enable of the pad. 1: internal pull-down enabled, 0: internal pull-down disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull-down circuitry, therefore, their FUN_WPD is always 0.
+ 7
+ 1
+ read-write
+
+
+ FUN_WPU
+ Pull-up enable of the pad. 1: internal pull-up enabled; 0: internal pull-up disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull- down circuitry, therefore, their FUN_WPU is always 0.
+ 8
+ 1
+ read-write
+
+
+ FUN_IE
+ Input enable of the pad. 1: input enabled; 0: input disabled.
+ 9
+ 1
+ read-write
+
+
+ FUN_DRV
+ Select the drive strength of the pad. A higher value corresponds with a higher strength. For GPIO34-39, FUN_DRV is always 0. For detailed drive strength, please see note 8 in Table ”Notes on ESP32 Pin Lists”, in ESP32 Datasheet.
+ 10
+ 2
+ read-write
+
+
+ MCU_SEL
+ Select the IO_MUX function for this signal. 0 selects Function 0, 1 selects Function 1, etc.
+ 12
+ 3
+ read-write
+
+
+
+
+ GPIO15
+ 0x3C
+ 0x20
+
+
+ MCU_OE
+ Output enable of the pad in sleep mode. 1: enable output; 0: disable output.
+ 0
+ 1
+ read-write
+
+
+ SLP_SEL
+ Sleep mode selection of this pad. Set to 1 to put the pad in sleep mode.
+ 1
+ 1
+ read-write
+
+
+ MCU_WPD
+ Pull-down enable of the pad during sleep mode. 1: internal pull-down enabled; 0: internal pull-down disabled.
+ 2
+ 1
+ read-write
+
+
+ MCU_WPU
+ Pull-up enable of the pad during sleep mode. 1: internal pull-up enabled; 0: internal pull-up disabled.
+ 3
+ 1
+ read-write
+
+
+ MCU_IE
+ Input enable of the pad during sleep mode. 1: input enabled; 0: input disabled.
+ 4
+ 1
+ read-write
+
+
+ MCU_DRV
+ Select the drive strength of the pad during sleep mode. A higher value corresponds with a higher strength.
+ 5
+ 2
+ read-write
+
+
+ FUN_WPD
+ Pull-down enable of the pad. 1: internal pull-down enabled, 0: internal pull-down disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull-down circuitry, therefore, their FUN_WPD is always 0.
+ 7
+ 1
+ read-write
+
+
+ FUN_WPU
+ Pull-up enable of the pad. 1: internal pull-up enabled; 0: internal pull-up disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull- down circuitry, therefore, their FUN_WPU is always 0.
+ 8
+ 1
+ read-write
+
+
+ FUN_IE
+ Input enable of the pad. 1: input enabled; 0: input disabled.
+ 9
+ 1
+ read-write
+
+
+ FUN_DRV
+ Select the drive strength of the pad. A higher value corresponds with a higher strength. For GPIO34-39, FUN_DRV is always 0. For detailed drive strength, please see note 8 in Table ”Notes on ESP32 Pin Lists”, in ESP32 Datasheet.
+ 10
+ 2
+ read-write
+
+
+ MCU_SEL
+ Select the IO_MUX function for this signal. 0 selects Function 0, 1 selects Function 1, etc.
+ 12
+ 3
+ read-write
+
+
+
+
+ GPIO2
+ 0x40
+ 0x20
+
+
+ MCU_OE
+ Output enable of the pad in sleep mode. 1: enable output; 0: disable output.
+ 0
+ 1
+ read-write
+
+
+ SLP_SEL
+ Sleep mode selection of this pad. Set to 1 to put the pad in sleep mode.
+ 1
+ 1
+ read-write
+
+
+ MCU_WPD
+ Pull-down enable of the pad during sleep mode. 1: internal pull-down enabled; 0: internal pull-down disabled.
+ 2
+ 1
+ read-write
+
+
+ MCU_WPU
+ Pull-up enable of the pad during sleep mode. 1: internal pull-up enabled; 0: internal pull-up disabled.
+ 3
+ 1
+ read-write
+
+
+ MCU_IE
+ Input enable of the pad during sleep mode. 1: input enabled; 0: input disabled.
+ 4
+ 1
+ read-write
+
+
+ MCU_DRV
+ Select the drive strength of the pad during sleep mode. A higher value corresponds with a higher strength.
+ 5
+ 2
+ read-write
+
+
+ FUN_WPD
+ Pull-down enable of the pad. 1: internal pull-down enabled, 0: internal pull-down disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull-down circuitry, therefore, their FUN_WPD is always 0.
+ 7
+ 1
+ read-write
+
+
+ FUN_WPU
+ Pull-up enable of the pad. 1: internal pull-up enabled; 0: internal pull-up disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull- down circuitry, therefore, their FUN_WPU is always 0.
+ 8
+ 1
+ read-write
+
+
+ FUN_IE
+ Input enable of the pad. 1: input enabled; 0: input disabled.
+ 9
+ 1
+ read-write
+
+
+ FUN_DRV
+ Select the drive strength of the pad. A higher value corresponds with a higher strength. For GPIO34-39, FUN_DRV is always 0. For detailed drive strength, please see note 8 in Table ”Notes on ESP32 Pin Lists”, in ESP32 Datasheet.
+ 10
+ 2
+ read-write
+
+
+ MCU_SEL
+ Select the IO_MUX function for this signal. 0 selects Function 0, 1 selects Function 1, etc.
+ 12
+ 3
+ read-write
+
+
+
+
+ GPIO0
+ 0x44
+ 0x20
+
+
+ MCU_OE
+ Output enable of the pad in sleep mode. 1: enable output; 0: disable output.
+ 0
+ 1
+ read-write
+
+
+ SLP_SEL
+ Sleep mode selection of this pad. Set to 1 to put the pad in sleep mode.
+ 1
+ 1
+ read-write
+
+
+ MCU_WPD
+ Pull-down enable of the pad during sleep mode. 1: internal pull-down enabled; 0: internal pull-down disabled.
+ 2
+ 1
+ read-write
+
+
+ MCU_WPU
+ Pull-up enable of the pad during sleep mode. 1: internal pull-up enabled; 0: internal pull-up disabled.
+ 3
+ 1
+ read-write
+
+
+ MCU_IE
+ Input enable of the pad during sleep mode. 1: input enabled; 0: input disabled.
+ 4
+ 1
+ read-write
+
+
+ MCU_DRV
+ Select the drive strength of the pad during sleep mode. A higher value corresponds with a higher strength.
+ 5
+ 2
+ read-write
+
+
+ FUN_WPD
+ Pull-down enable of the pad. 1: internal pull-down enabled, 0: internal pull-down disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull-down circuitry, therefore, their FUN_WPD is always 0.
+ 7
+ 1
+ read-write
+
+
+ FUN_WPU
+ Pull-up enable of the pad. 1: internal pull-up enabled; 0: internal pull-up disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull- down circuitry, therefore, their FUN_WPU is always 0.
+ 8
+ 1
+ read-write
+
+
+ FUN_IE
+ Input enable of the pad. 1: input enabled; 0: input disabled.
+ 9
+ 1
+ read-write
+
+
+ FUN_DRV
+ Select the drive strength of the pad. A higher value corresponds with a higher strength. For GPIO34-39, FUN_DRV is always 0. For detailed drive strength, please see note 8 in Table ”Notes on ESP32 Pin Lists”, in ESP32 Datasheet.
+ 10
+ 2
+ read-write
+
+
+ MCU_SEL
+ Select the IO_MUX function for this signal. 0 selects Function 0, 1 selects Function 1, etc.
+ 12
+ 3
+ read-write
+
+
+
+
+ GPIO4
+ 0x48
+ 0x20
+
+
+ MCU_OE
+ Output enable of the pad in sleep mode. 1: enable output; 0: disable output.
+ 0
+ 1
+ read-write
+
+
+ SLP_SEL
+ Sleep mode selection of this pad. Set to 1 to put the pad in sleep mode.
+ 1
+ 1
+ read-write
+
+
+ MCU_WPD
+ Pull-down enable of the pad during sleep mode. 1: internal pull-down enabled; 0: internal pull-down disabled.
+ 2
+ 1
+ read-write
+
+
+ MCU_WPU
+ Pull-up enable of the pad during sleep mode. 1: internal pull-up enabled; 0: internal pull-up disabled.
+ 3
+ 1
+ read-write
+
+
+ MCU_IE
+ Input enable of the pad during sleep mode. 1: input enabled; 0: input disabled.
+ 4
+ 1
+ read-write
+
+
+ MCU_DRV
+ Select the drive strength of the pad during sleep mode. A higher value corresponds with a higher strength.
+ 5
+ 2
+ read-write
+
+
+ FUN_WPD
+ Pull-down enable of the pad. 1: internal pull-down enabled, 0: internal pull-down disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull-down circuitry, therefore, their FUN_WPD is always 0.
+ 7
+ 1
+ read-write
+
+
+ FUN_WPU
+ Pull-up enable of the pad. 1: internal pull-up enabled; 0: internal pull-up disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull- down circuitry, therefore, their FUN_WPU is always 0.
+ 8
+ 1
+ read-write
+
+
+ FUN_IE
+ Input enable of the pad. 1: input enabled; 0: input disabled.
+ 9
+ 1
+ read-write
+
+
+ FUN_DRV
+ Select the drive strength of the pad. A higher value corresponds with a higher strength. For GPIO34-39, FUN_DRV is always 0. For detailed drive strength, please see note 8 in Table ”Notes on ESP32 Pin Lists”, in ESP32 Datasheet.
+ 10
+ 2
+ read-write
+
+
+ MCU_SEL
+ Select the IO_MUX function for this signal. 0 selects Function 0, 1 selects Function 1, etc.
+ 12
+ 3
+ read-write
+
+
+
+
+ GPIO16
+ 0x4C
+ 0x20
+
+
+ MCU_OE
+ Output enable of the pad in sleep mode. 1: enable output; 0: disable output.
+ 0
+ 1
+ read-write
+
+
+ SLP_SEL
+ Sleep mode selection of this pad. Set to 1 to put the pad in sleep mode.
+ 1
+ 1
+ read-write
+
+
+ MCU_WPD
+ Pull-down enable of the pad during sleep mode. 1: internal pull-down enabled; 0: internal pull-down disabled.
+ 2
+ 1
+ read-write
+
+
+ MCU_WPU
+ Pull-up enable of the pad during sleep mode. 1: internal pull-up enabled; 0: internal pull-up disabled.
+ 3
+ 1
+ read-write
+
+
+ MCU_IE
+ Input enable of the pad during sleep mode. 1: input enabled; 0: input disabled.
+ 4
+ 1
+ read-write
+
+
+ MCU_DRV
+ Select the drive strength of the pad during sleep mode. A higher value corresponds with a higher strength.
+ 5
+ 2
+ read-write
+
+
+ FUN_WPD
+ Pull-down enable of the pad. 1: internal pull-down enabled, 0: internal pull-down disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull-down circuitry, therefore, their FUN_WPD is always 0.
+ 7
+ 1
+ read-write
+
+
+ FUN_WPU
+ Pull-up enable of the pad. 1: internal pull-up enabled; 0: internal pull-up disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull- down circuitry, therefore, their FUN_WPU is always 0.
+ 8
+ 1
+ read-write
+
+
+ FUN_IE
+ Input enable of the pad. 1: input enabled; 0: input disabled.
+ 9
+ 1
+ read-write
+
+
+ FUN_DRV
+ Select the drive strength of the pad. A higher value corresponds with a higher strength. For GPIO34-39, FUN_DRV is always 0. For detailed drive strength, please see note 8 in Table ”Notes on ESP32 Pin Lists”, in ESP32 Datasheet.
+ 10
+ 2
+ read-write
+
+
+ MCU_SEL
+ Select the IO_MUX function for this signal. 0 selects Function 0, 1 selects Function 1, etc.
+ 12
+ 3
+ read-write
+
+
+
+
+ GPIO17
+ 0x50
+ 0x20
+
+
+ MCU_OE
+ Output enable of the pad in sleep mode. 1: enable output; 0: disable output.
+ 0
+ 1
+ read-write
+
+
+ SLP_SEL
+ Sleep mode selection of this pad. Set to 1 to put the pad in sleep mode.
+ 1
+ 1
+ read-write
+
+
+ MCU_WPD
+ Pull-down enable of the pad during sleep mode. 1: internal pull-down enabled; 0: internal pull-down disabled.
+ 2
+ 1
+ read-write
+
+
+ MCU_WPU
+ Pull-up enable of the pad during sleep mode. 1: internal pull-up enabled; 0: internal pull-up disabled.
+ 3
+ 1
+ read-write
+
+
+ MCU_IE
+ Input enable of the pad during sleep mode. 1: input enabled; 0: input disabled.
+ 4
+ 1
+ read-write
+
+
+ MCU_DRV
+ Select the drive strength of the pad during sleep mode. A higher value corresponds with a higher strength.
+ 5
+ 2
+ read-write
+
+
+ FUN_WPD
+ Pull-down enable of the pad. 1: internal pull-down enabled, 0: internal pull-down disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull-down circuitry, therefore, their FUN_WPD is always 0.
+ 7
+ 1
+ read-write
+
+
+ FUN_WPU
+ Pull-up enable of the pad. 1: internal pull-up enabled; 0: internal pull-up disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull- down circuitry, therefore, their FUN_WPU is always 0.
+ 8
+ 1
+ read-write
+
+
+ FUN_IE
+ Input enable of the pad. 1: input enabled; 0: input disabled.
+ 9
+ 1
+ read-write
+
+
+ FUN_DRV
+ Select the drive strength of the pad. A higher value corresponds with a higher strength. For GPIO34-39, FUN_DRV is always 0. For detailed drive strength, please see note 8 in Table ”Notes on ESP32 Pin Lists”, in ESP32 Datasheet.
+ 10
+ 2
+ read-write
+
+
+ MCU_SEL
+ Select the IO_MUX function for this signal. 0 selects Function 0, 1 selects Function 1, etc.
+ 12
+ 3
+ read-write
+
+
+
+
+ GPIO9
+ 0x54
+ 0x20
+
+
+ MCU_OE
+ Output enable of the pad in sleep mode. 1: enable output; 0: disable output.
+ 0
+ 1
+ read-write
+
+
+ SLP_SEL
+ Sleep mode selection of this pad. Set to 1 to put the pad in sleep mode.
+ 1
+ 1
+ read-write
+
+
+ MCU_WPD
+ Pull-down enable of the pad during sleep mode. 1: internal pull-down enabled; 0: internal pull-down disabled.
+ 2
+ 1
+ read-write
+
+
+ MCU_WPU
+ Pull-up enable of the pad during sleep mode. 1: internal pull-up enabled; 0: internal pull-up disabled.
+ 3
+ 1
+ read-write
+
+
+ MCU_IE
+ Input enable of the pad during sleep mode. 1: input enabled; 0: input disabled.
+ 4
+ 1
+ read-write
+
+
+ MCU_DRV
+ Select the drive strength of the pad during sleep mode. A higher value corresponds with a higher strength.
+ 5
+ 2
+ read-write
+
+
+ FUN_WPD
+ Pull-down enable of the pad. 1: internal pull-down enabled, 0: internal pull-down disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull-down circuitry, therefore, their FUN_WPD is always 0.
+ 7
+ 1
+ read-write
+
+
+ FUN_WPU
+ Pull-up enable of the pad. 1: internal pull-up enabled; 0: internal pull-up disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull- down circuitry, therefore, their FUN_WPU is always 0.
+ 8
+ 1
+ read-write
+
+
+ FUN_IE
+ Input enable of the pad. 1: input enabled; 0: input disabled.
+ 9
+ 1
+ read-write
+
+
+ FUN_DRV
+ Select the drive strength of the pad. A higher value corresponds with a higher strength. For GPIO34-39, FUN_DRV is always 0. For detailed drive strength, please see note 8 in Table ”Notes on ESP32 Pin Lists”, in ESP32 Datasheet.
+ 10
+ 2
+ read-write
+
+
+ MCU_SEL
+ Select the IO_MUX function for this signal. 0 selects Function 0, 1 selects Function 1, etc.
+ 12
+ 3
+ read-write
+
+
+
+
+ GPIO10
+ 0x58
+ 0x20
+
+
+ MCU_OE
+ Output enable of the pad in sleep mode. 1: enable output; 0: disable output.
+ 0
+ 1
+ read-write
+
+
+ SLP_SEL
+ Sleep mode selection of this pad. Set to 1 to put the pad in sleep mode.
+ 1
+ 1
+ read-write
+
+
+ MCU_WPD
+ Pull-down enable of the pad during sleep mode. 1: internal pull-down enabled; 0: internal pull-down disabled.
+ 2
+ 1
+ read-write
+
+
+ MCU_WPU
+ Pull-up enable of the pad during sleep mode. 1: internal pull-up enabled; 0: internal pull-up disabled.
+ 3
+ 1
+ read-write
+
+
+ MCU_IE
+ Input enable of the pad during sleep mode. 1: input enabled; 0: input disabled.
+ 4
+ 1
+ read-write
+
+
+ MCU_DRV
+ Select the drive strength of the pad during sleep mode. A higher value corresponds with a higher strength.
+ 5
+ 2
+ read-write
+
+
+ FUN_WPD
+ Pull-down enable of the pad. 1: internal pull-down enabled, 0: internal pull-down disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull-down circuitry, therefore, their FUN_WPD is always 0.
+ 7
+ 1
+ read-write
+
+
+ FUN_WPU
+ Pull-up enable of the pad. 1: internal pull-up enabled; 0: internal pull-up disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull- down circuitry, therefore, their FUN_WPU is always 0.
+ 8
+ 1
+ read-write
+
+
+ FUN_IE
+ Input enable of the pad. 1: input enabled; 0: input disabled.
+ 9
+ 1
+ read-write
+
+
+ FUN_DRV
+ Select the drive strength of the pad. A higher value corresponds with a higher strength. For GPIO34-39, FUN_DRV is always 0. For detailed drive strength, please see note 8 in Table ”Notes on ESP32 Pin Lists”, in ESP32 Datasheet.
+ 10
+ 2
+ read-write
+
+
+ MCU_SEL
+ Select the IO_MUX function for this signal. 0 selects Function 0, 1 selects Function 1, etc.
+ 12
+ 3
+ read-write
+
+
+
+
+ GPIO11
+ 0x5C
+ 0x20
+
+
+ MCU_OE
+ Output enable of the pad in sleep mode. 1: enable output; 0: disable output.
+ 0
+ 1
+ read-write
+
+
+ SLP_SEL
+ Sleep mode selection of this pad. Set to 1 to put the pad in sleep mode.
+ 1
+ 1
+ read-write
+
+
+ MCU_WPD
+ Pull-down enable of the pad during sleep mode. 1: internal pull-down enabled; 0: internal pull-down disabled.
+ 2
+ 1
+ read-write
+
+
+ MCU_WPU
+ Pull-up enable of the pad during sleep mode. 1: internal pull-up enabled; 0: internal pull-up disabled.
+ 3
+ 1
+ read-write
+
+
+ MCU_IE
+ Input enable of the pad during sleep mode. 1: input enabled; 0: input disabled.
+ 4
+ 1
+ read-write
+
+
+ MCU_DRV
+ Select the drive strength of the pad during sleep mode. A higher value corresponds with a higher strength.
+ 5
+ 2
+ read-write
+
+
+ FUN_WPD
+ Pull-down enable of the pad. 1: internal pull-down enabled, 0: internal pull-down disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull-down circuitry, therefore, their FUN_WPD is always 0.
+ 7
+ 1
+ read-write
+
+
+ FUN_WPU
+ Pull-up enable of the pad. 1: internal pull-up enabled; 0: internal pull-up disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull- down circuitry, therefore, their FUN_WPU is always 0.
+ 8
+ 1
+ read-write
+
+
+ FUN_IE
+ Input enable of the pad. 1: input enabled; 0: input disabled.
+ 9
+ 1
+ read-write
+
+
+ FUN_DRV
+ Select the drive strength of the pad. A higher value corresponds with a higher strength. For GPIO34-39, FUN_DRV is always 0. For detailed drive strength, please see note 8 in Table ”Notes on ESP32 Pin Lists”, in ESP32 Datasheet.
+ 10
+ 2
+ read-write
+
+
+ MCU_SEL
+ Select the IO_MUX function for this signal. 0 selects Function 0, 1 selects Function 1, etc.
+ 12
+ 3
+ read-write
+
+
+
+
+ GPIO6
+ 0x60
+ 0x20
+
+
+ MCU_OE
+ Output enable of the pad in sleep mode. 1: enable output; 0: disable output.
+ 0
+ 1
+ read-write
+
+
+ SLP_SEL
+ Sleep mode selection of this pad. Set to 1 to put the pad in sleep mode.
+ 1
+ 1
+ read-write
+
+
+ MCU_WPD
+ Pull-down enable of the pad during sleep mode. 1: internal pull-down enabled; 0: internal pull-down disabled.
+ 2
+ 1
+ read-write
+
+
+ MCU_WPU
+ Pull-up enable of the pad during sleep mode. 1: internal pull-up enabled; 0: internal pull-up disabled.
+ 3
+ 1
+ read-write
+
+
+ MCU_IE
+ Input enable of the pad during sleep mode. 1: input enabled; 0: input disabled.
+ 4
+ 1
+ read-write
+
+
+ MCU_DRV
+ Select the drive strength of the pad during sleep mode. A higher value corresponds with a higher strength.
+ 5
+ 2
+ read-write
+
+
+ FUN_WPD
+ Pull-down enable of the pad. 1: internal pull-down enabled, 0: internal pull-down disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull-down circuitry, therefore, their FUN_WPD is always 0.
+ 7
+ 1
+ read-write
+
+
+ FUN_WPU
+ Pull-up enable of the pad. 1: internal pull-up enabled; 0: internal pull-up disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull- down circuitry, therefore, their FUN_WPU is always 0.
+ 8
+ 1
+ read-write
+
+
+ FUN_IE
+ Input enable of the pad. 1: input enabled; 0: input disabled.
+ 9
+ 1
+ read-write
+
+
+ FUN_DRV
+ Select the drive strength of the pad. A higher value corresponds with a higher strength. For GPIO34-39, FUN_DRV is always 0. For detailed drive strength, please see note 8 in Table ”Notes on ESP32 Pin Lists”, in ESP32 Datasheet.
+ 10
+ 2
+ read-write
+
+
+ MCU_SEL
+ Select the IO_MUX function for this signal. 0 selects Function 0, 1 selects Function 1, etc.
+ 12
+ 3
+ read-write
+
+
+
+
+ GPIO7
+ 0x64
+ 0x20
+
+
+ MCU_OE
+ Output enable of the pad in sleep mode. 1: enable output; 0: disable output.
+ 0
+ 1
+ read-write
+
+
+ SLP_SEL
+ Sleep mode selection of this pad. Set to 1 to put the pad in sleep mode.
+ 1
+ 1
+ read-write
+
+
+ MCU_WPD
+ Pull-down enable of the pad during sleep mode. 1: internal pull-down enabled; 0: internal pull-down disabled.
+ 2
+ 1
+ read-write
+
+
+ MCU_WPU
+ Pull-up enable of the pad during sleep mode. 1: internal pull-up enabled; 0: internal pull-up disabled.
+ 3
+ 1
+ read-write
+
+
+ MCU_IE
+ Input enable of the pad during sleep mode. 1: input enabled; 0: input disabled.
+ 4
+ 1
+ read-write
+
+
+ MCU_DRV
+ Select the drive strength of the pad during sleep mode. A higher value corresponds with a higher strength.
+ 5
+ 2
+ read-write
+
+
+ FUN_WPD
+ Pull-down enable of the pad. 1: internal pull-down enabled, 0: internal pull-down disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull-down circuitry, therefore, their FUN_WPD is always 0.
+ 7
+ 1
+ read-write
+
+
+ FUN_WPU
+ Pull-up enable of the pad. 1: internal pull-up enabled; 0: internal pull-up disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull- down circuitry, therefore, their FUN_WPU is always 0.
+ 8
+ 1
+ read-write
+
+
+ FUN_IE
+ Input enable of the pad. 1: input enabled; 0: input disabled.
+ 9
+ 1
+ read-write
+
+
+ FUN_DRV
+ Select the drive strength of the pad. A higher value corresponds with a higher strength. For GPIO34-39, FUN_DRV is always 0. For detailed drive strength, please see note 8 in Table ”Notes on ESP32 Pin Lists”, in ESP32 Datasheet.
+ 10
+ 2
+ read-write
+
+
+ MCU_SEL
+ Select the IO_MUX function for this signal. 0 selects Function 0, 1 selects Function 1, etc.
+ 12
+ 3
+ read-write
+
+
+
+
+ GPIO8
+ 0x68
+ 0x20
+
+
+ MCU_OE
+ Output enable of the pad in sleep mode. 1: enable output; 0: disable output.
+ 0
+ 1
+ read-write
+
+
+ SLP_SEL
+ Sleep mode selection of this pad. Set to 1 to put the pad in sleep mode.
+ 1
+ 1
+ read-write
+
+
+ MCU_WPD
+ Pull-down enable of the pad during sleep mode. 1: internal pull-down enabled; 0: internal pull-down disabled.
+ 2
+ 1
+ read-write
+
+
+ MCU_WPU
+ Pull-up enable of the pad during sleep mode. 1: internal pull-up enabled; 0: internal pull-up disabled.
+ 3
+ 1
+ read-write
+
+
+ MCU_IE
+ Input enable of the pad during sleep mode. 1: input enabled; 0: input disabled.
+ 4
+ 1
+ read-write
+
+
+ MCU_DRV
+ Select the drive strength of the pad during sleep mode. A higher value corresponds with a higher strength.
+ 5
+ 2
+ read-write
+
+
+ FUN_WPD
+ Pull-down enable of the pad. 1: internal pull-down enabled, 0: internal pull-down disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull-down circuitry, therefore, their FUN_WPD is always 0.
+ 7
+ 1
+ read-write
+
+
+ FUN_WPU
+ Pull-up enable of the pad. 1: internal pull-up enabled; 0: internal pull-up disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull- down circuitry, therefore, their FUN_WPU is always 0.
+ 8
+ 1
+ read-write
+
+
+ FUN_IE
+ Input enable of the pad. 1: input enabled; 0: input disabled.
+ 9
+ 1
+ read-write
+
+
+ FUN_DRV
+ Select the drive strength of the pad. A higher value corresponds with a higher strength. For GPIO34-39, FUN_DRV is always 0. For detailed drive strength, please see note 8 in Table ”Notes on ESP32 Pin Lists”, in ESP32 Datasheet.
+ 10
+ 2
+ read-write
+
+
+ MCU_SEL
+ Select the IO_MUX function for this signal. 0 selects Function 0, 1 selects Function 1, etc.
+ 12
+ 3
+ read-write
+
+
+
+
+ GPIO5
+ 0x6C
+ 0x20
+
+
+ MCU_OE
+ Output enable of the pad in sleep mode. 1: enable output; 0: disable output.
+ 0
+ 1
+ read-write
+
+
+ SLP_SEL
+ Sleep mode selection of this pad. Set to 1 to put the pad in sleep mode.
+ 1
+ 1
+ read-write
+
+
+ MCU_WPD
+ Pull-down enable of the pad during sleep mode. 1: internal pull-down enabled; 0: internal pull-down disabled.
+ 2
+ 1
+ read-write
+
+
+ MCU_WPU
+ Pull-up enable of the pad during sleep mode. 1: internal pull-up enabled; 0: internal pull-up disabled.
+ 3
+ 1
+ read-write
+
+
+ MCU_IE
+ Input enable of the pad during sleep mode. 1: input enabled; 0: input disabled.
+ 4
+ 1
+ read-write
+
+
+ MCU_DRV
+ Select the drive strength of the pad during sleep mode. A higher value corresponds with a higher strength.
+ 5
+ 2
+ read-write
+
+
+ FUN_WPD
+ Pull-down enable of the pad. 1: internal pull-down enabled, 0: internal pull-down disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull-down circuitry, therefore, their FUN_WPD is always 0.
+ 7
+ 1
+ read-write
+
+
+ FUN_WPU
+ Pull-up enable of the pad. 1: internal pull-up enabled; 0: internal pull-up disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull- down circuitry, therefore, their FUN_WPU is always 0.
+ 8
+ 1
+ read-write
+
+
+ FUN_IE
+ Input enable of the pad. 1: input enabled; 0: input disabled.
+ 9
+ 1
+ read-write
+
+
+ FUN_DRV
+ Select the drive strength of the pad. A higher value corresponds with a higher strength. For GPIO34-39, FUN_DRV is always 0. For detailed drive strength, please see note 8 in Table ”Notes on ESP32 Pin Lists”, in ESP32 Datasheet.
+ 10
+ 2
+ read-write
+
+
+ MCU_SEL
+ Select the IO_MUX function for this signal. 0 selects Function 0, 1 selects Function 1, etc.
+ 12
+ 3
+ read-write
+
+
+
+
+ GPIO18
+ 0x70
+ 0x20
+
+
+ MCU_OE
+ Output enable of the pad in sleep mode. 1: enable output; 0: disable output.
+ 0
+ 1
+ read-write
+
+
+ SLP_SEL
+ Sleep mode selection of this pad. Set to 1 to put the pad in sleep mode.
+ 1
+ 1
+ read-write
+
+
+ MCU_WPD
+ Pull-down enable of the pad during sleep mode. 1: internal pull-down enabled; 0: internal pull-down disabled.
+ 2
+ 1
+ read-write
+
+
+ MCU_WPU
+ Pull-up enable of the pad during sleep mode. 1: internal pull-up enabled; 0: internal pull-up disabled.
+ 3
+ 1
+ read-write
+
+
+ MCU_IE
+ Input enable of the pad during sleep mode. 1: input enabled; 0: input disabled.
+ 4
+ 1
+ read-write
+
+
+ MCU_DRV
+ Select the drive strength of the pad during sleep mode. A higher value corresponds with a higher strength.
+ 5
+ 2
+ read-write
+
+
+ FUN_WPD
+ Pull-down enable of the pad. 1: internal pull-down enabled, 0: internal pull-down disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull-down circuitry, therefore, their FUN_WPD is always 0.
+ 7
+ 1
+ read-write
+
+
+ FUN_WPU
+ Pull-up enable of the pad. 1: internal pull-up enabled; 0: internal pull-up disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull- down circuitry, therefore, their FUN_WPU is always 0.
+ 8
+ 1
+ read-write
+
+
+ FUN_IE
+ Input enable of the pad. 1: input enabled; 0: input disabled.
+ 9
+ 1
+ read-write
+
+
+ FUN_DRV
+ Select the drive strength of the pad. A higher value corresponds with a higher strength. For GPIO34-39, FUN_DRV is always 0. For detailed drive strength, please see note 8 in Table ”Notes on ESP32 Pin Lists”, in ESP32 Datasheet.
+ 10
+ 2
+ read-write
+
+
+ MCU_SEL
+ Select the IO_MUX function for this signal. 0 selects Function 0, 1 selects Function 1, etc.
+ 12
+ 3
+ read-write
+
+
+
+
+ GPIO19
+ 0x74
+ 0x20
+
+
+ MCU_OE
+ Output enable of the pad in sleep mode. 1: enable output; 0: disable output.
+ 0
+ 1
+ read-write
+
+
+ SLP_SEL
+ Sleep mode selection of this pad. Set to 1 to put the pad in sleep mode.
+ 1
+ 1
+ read-write
+
+
+ MCU_WPD
+ Pull-down enable of the pad during sleep mode. 1: internal pull-down enabled; 0: internal pull-down disabled.
+ 2
+ 1
+ read-write
+
+
+ MCU_WPU
+ Pull-up enable of the pad during sleep mode. 1: internal pull-up enabled; 0: internal pull-up disabled.
+ 3
+ 1
+ read-write
+
+
+ MCU_IE
+ Input enable of the pad during sleep mode. 1: input enabled; 0: input disabled.
+ 4
+ 1
+ read-write
+
+
+ MCU_DRV
+ Select the drive strength of the pad during sleep mode. A higher value corresponds with a higher strength.
+ 5
+ 2
+ read-write
+
+
+ FUN_WPD
+ Pull-down enable of the pad. 1: internal pull-down enabled, 0: internal pull-down disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull-down circuitry, therefore, their FUN_WPD is always 0.
+ 7
+ 1
+ read-write
+
+
+ FUN_WPU
+ Pull-up enable of the pad. 1: internal pull-up enabled; 0: internal pull-up disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull- down circuitry, therefore, their FUN_WPU is always 0.
+ 8
+ 1
+ read-write
+
+
+ FUN_IE
+ Input enable of the pad. 1: input enabled; 0: input disabled.
+ 9
+ 1
+ read-write
+
+
+ FUN_DRV
+ Select the drive strength of the pad. A higher value corresponds with a higher strength. For GPIO34-39, FUN_DRV is always 0. For detailed drive strength, please see note 8 in Table ”Notes on ESP32 Pin Lists”, in ESP32 Datasheet.
+ 10
+ 2
+ read-write
+
+
+ MCU_SEL
+ Select the IO_MUX function for this signal. 0 selects Function 0, 1 selects Function 1, etc.
+ 12
+ 3
+ read-write
+
+
+
+
+ GPIO20
+ 0x78
+ 0x20
+
+
+ MCU_OE
+ Output enable of the pad in sleep mode. 1: enable output; 0: disable output.
+ 0
+ 1
+ read-write
+
+
+ SLP_SEL
+ Sleep mode selection of this pad. Set to 1 to put the pad in sleep mode.
+ 1
+ 1
+ read-write
+
+
+ MCU_WPD
+ Pull-down enable of the pad during sleep mode. 1: internal pull-down enabled; 0: internal pull-down disabled.
+ 2
+ 1
+ read-write
+
+
+ MCU_WPU
+ Pull-up enable of the pad during sleep mode. 1: internal pull-up enabled; 0: internal pull-up disabled.
+ 3
+ 1
+ read-write
+
+
+ MCU_IE
+ Input enable of the pad during sleep mode. 1: input enabled; 0: input disabled.
+ 4
+ 1
+ read-write
+
+
+ MCU_DRV
+ Select the drive strength of the pad during sleep mode. A higher value corresponds with a higher strength.
+ 5
+ 2
+ read-write
+
+
+ FUN_WPD
+ Pull-down enable of the pad. 1: internal pull-down enabled, 0: internal pull-down disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull-down circuitry, therefore, their FUN_WPD is always 0.
+ 7
+ 1
+ read-write
+
+
+ FUN_WPU
+ Pull-up enable of the pad. 1: internal pull-up enabled; 0: internal pull-up disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull- down circuitry, therefore, their FUN_WPU is always 0.
+ 8
+ 1
+ read-write
+
+
+ FUN_IE
+ Input enable of the pad. 1: input enabled; 0: input disabled.
+ 9
+ 1
+ read-write
+
+
+ FUN_DRV
+ Select the drive strength of the pad. A higher value corresponds with a higher strength. For GPIO34-39, FUN_DRV is always 0. For detailed drive strength, please see note 8 in Table ”Notes on ESP32 Pin Lists”, in ESP32 Datasheet.
+ 10
+ 2
+ read-write
+
+
+ MCU_SEL
+ Select the IO_MUX function for this signal. 0 selects Function 0, 1 selects Function 1, etc.
+ 12
+ 3
+ read-write
+
+
+
+
+ GPIO21
+ 0x7C
+ 0x20
+
+
+ MCU_OE
+ Output enable of the pad in sleep mode. 1: enable output; 0: disable output.
+ 0
+ 1
+ read-write
+
+
+ SLP_SEL
+ Sleep mode selection of this pad. Set to 1 to put the pad in sleep mode.
+ 1
+ 1
+ read-write
+
+
+ MCU_WPD
+ Pull-down enable of the pad during sleep mode. 1: internal pull-down enabled; 0: internal pull-down disabled.
+ 2
+ 1
+ read-write
+
+
+ MCU_WPU
+ Pull-up enable of the pad during sleep mode. 1: internal pull-up enabled; 0: internal pull-up disabled.
+ 3
+ 1
+ read-write
+
+
+ MCU_IE
+ Input enable of the pad during sleep mode. 1: input enabled; 0: input disabled.
+ 4
+ 1
+ read-write
+
+
+ MCU_DRV
+ Select the drive strength of the pad during sleep mode. A higher value corresponds with a higher strength.
+ 5
+ 2
+ read-write
+
+
+ FUN_WPD
+ Pull-down enable of the pad. 1: internal pull-down enabled, 0: internal pull-down disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull-down circuitry, therefore, their FUN_WPD is always 0.
+ 7
+ 1
+ read-write
+
+
+ FUN_WPU
+ Pull-up enable of the pad. 1: internal pull-up enabled; 0: internal pull-up disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull- down circuitry, therefore, their FUN_WPU is always 0.
+ 8
+ 1
+ read-write
+
+
+ FUN_IE
+ Input enable of the pad. 1: input enabled; 0: input disabled.
+ 9
+ 1
+ read-write
+
+
+ FUN_DRV
+ Select the drive strength of the pad. A higher value corresponds with a higher strength. For GPIO34-39, FUN_DRV is always 0. For detailed drive strength, please see note 8 in Table ”Notes on ESP32 Pin Lists”, in ESP32 Datasheet.
+ 10
+ 2
+ read-write
+
+
+ MCU_SEL
+ Select the IO_MUX function for this signal. 0 selects Function 0, 1 selects Function 1, etc.
+ 12
+ 3
+ read-write
+
+
+
+
+ GPIO22
+ 0x80
+ 0x20
+
+
+ MCU_OE
+ Output enable of the pad in sleep mode. 1: enable output; 0: disable output.
+ 0
+ 1
+ read-write
+
+
+ SLP_SEL
+ Sleep mode selection of this pad. Set to 1 to put the pad in sleep mode.
+ 1
+ 1
+ read-write
+
+
+ MCU_WPD
+ Pull-down enable of the pad during sleep mode. 1: internal pull-down enabled; 0: internal pull-down disabled.
+ 2
+ 1
+ read-write
+
+
+ MCU_WPU
+ Pull-up enable of the pad during sleep mode. 1: internal pull-up enabled; 0: internal pull-up disabled.
+ 3
+ 1
+ read-write
+
+
+ MCU_IE
+ Input enable of the pad during sleep mode. 1: input enabled; 0: input disabled.
+ 4
+ 1
+ read-write
+
+
+ MCU_DRV
+ Select the drive strength of the pad during sleep mode. A higher value corresponds with a higher strength.
+ 5
+ 2
+ read-write
+
+
+ FUN_WPD
+ Pull-down enable of the pad. 1: internal pull-down enabled, 0: internal pull-down disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull-down circuitry, therefore, their FUN_WPD is always 0.
+ 7
+ 1
+ read-write
+
+
+ FUN_WPU
+ Pull-up enable of the pad. 1: internal pull-up enabled; 0: internal pull-up disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull- down circuitry, therefore, their FUN_WPU is always 0.
+ 8
+ 1
+ read-write
+
+
+ FUN_IE
+ Input enable of the pad. 1: input enabled; 0: input disabled.
+ 9
+ 1
+ read-write
+
+
+ FUN_DRV
+ Select the drive strength of the pad. A higher value corresponds with a higher strength. For GPIO34-39, FUN_DRV is always 0. For detailed drive strength, please see note 8 in Table ”Notes on ESP32 Pin Lists”, in ESP32 Datasheet.
+ 10
+ 2
+ read-write
+
+
+ MCU_SEL
+ Select the IO_MUX function for this signal. 0 selects Function 0, 1 selects Function 1, etc.
+ 12
+ 3
+ read-write
+
+
+
+
+ GPIO3
+ 0x84
+ 0x20
+
+
+ MCU_OE
+ Output enable of the pad in sleep mode. 1: enable output; 0: disable output.
+ 0
+ 1
+ read-write
+
+
+ SLP_SEL
+ Sleep mode selection of this pad. Set to 1 to put the pad in sleep mode.
+ 1
+ 1
+ read-write
+
+
+ MCU_WPD
+ Pull-down enable of the pad during sleep mode. 1: internal pull-down enabled; 0: internal pull-down disabled.
+ 2
+ 1
+ read-write
+
+
+ MCU_WPU
+ Pull-up enable of the pad during sleep mode. 1: internal pull-up enabled; 0: internal pull-up disabled.
+ 3
+ 1
+ read-write
+
+
+ MCU_IE
+ Input enable of the pad during sleep mode. 1: input enabled; 0: input disabled.
+ 4
+ 1
+ read-write
+
+
+ MCU_DRV
+ Select the drive strength of the pad during sleep mode. A higher value corresponds with a higher strength.
+ 5
+ 2
+ read-write
+
+
+ FUN_WPD
+ Pull-down enable of the pad. 1: internal pull-down enabled, 0: internal pull-down disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull-down circuitry, therefore, their FUN_WPD is always 0.
+ 7
+ 1
+ read-write
+
+
+ FUN_WPU
+ Pull-up enable of the pad. 1: internal pull-up enabled; 0: internal pull-up disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull- down circuitry, therefore, their FUN_WPU is always 0.
+ 8
+ 1
+ read-write
+
+
+ FUN_IE
+ Input enable of the pad. 1: input enabled; 0: input disabled.
+ 9
+ 1
+ read-write
+
+
+ FUN_DRV
+ Select the drive strength of the pad. A higher value corresponds with a higher strength. For GPIO34-39, FUN_DRV is always 0. For detailed drive strength, please see note 8 in Table ”Notes on ESP32 Pin Lists”, in ESP32 Datasheet.
+ 10
+ 2
+ read-write
+
+
+ MCU_SEL
+ Select the IO_MUX function for this signal. 0 selects Function 0, 1 selects Function 1, etc.
+ 12
+ 3
+ read-write
+
+
+
+
+ GPIO1
+ 0x88
+ 0x20
+
+
+ MCU_OE
+ Output enable of the pad in sleep mode. 1: enable output; 0: disable output.
+ 0
+ 1
+ read-write
+
+
+ SLP_SEL
+ Sleep mode selection of this pad. Set to 1 to put the pad in sleep mode.
+ 1
+ 1
+ read-write
+
+
+ MCU_WPD
+ Pull-down enable of the pad during sleep mode. 1: internal pull-down enabled; 0: internal pull-down disabled.
+ 2
+ 1
+ read-write
+
+
+ MCU_WPU
+ Pull-up enable of the pad during sleep mode. 1: internal pull-up enabled; 0: internal pull-up disabled.
+ 3
+ 1
+ read-write
+
+
+ MCU_IE
+ Input enable of the pad during sleep mode. 1: input enabled; 0: input disabled.
+ 4
+ 1
+ read-write
+
+
+ MCU_DRV
+ Select the drive strength of the pad during sleep mode. A higher value corresponds with a higher strength.
+ 5
+ 2
+ read-write
+
+
+ FUN_WPD
+ Pull-down enable of the pad. 1: internal pull-down enabled, 0: internal pull-down disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull-down circuitry, therefore, their FUN_WPD is always 0.
+ 7
+ 1
+ read-write
+
+
+ FUN_WPU
+ Pull-up enable of the pad. 1: internal pull-up enabled; 0: internal pull-up disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull- down circuitry, therefore, their FUN_WPU is always 0.
+ 8
+ 1
+ read-write
+
+
+ FUN_IE
+ Input enable of the pad. 1: input enabled; 0: input disabled.
+ 9
+ 1
+ read-write
+
+
+ FUN_DRV
+ Select the drive strength of the pad. A higher value corresponds with a higher strength. For GPIO34-39, FUN_DRV is always 0. For detailed drive strength, please see note 8 in Table ”Notes on ESP32 Pin Lists”, in ESP32 Datasheet.
+ 10
+ 2
+ read-write
+
+
+ MCU_SEL
+ Select the IO_MUX function for this signal. 0 selects Function 0, 1 selects Function 1, etc.
+ 12
+ 3
+ read-write
+
+
+
+
+ GPIO23
+ 0x8C
+ 0x20
+
+
+ MCU_OE
+ Output enable of the pad in sleep mode. 1: enable output; 0: disable output.
+ 0
+ 1
+ read-write
+
+
+ SLP_SEL
+ Sleep mode selection of this pad. Set to 1 to put the pad in sleep mode.
+ 1
+ 1
+ read-write
+
+
+ MCU_WPD
+ Pull-down enable of the pad during sleep mode. 1: internal pull-down enabled; 0: internal pull-down disabled.
+ 2
+ 1
+ read-write
+
+
+ MCU_WPU
+ Pull-up enable of the pad during sleep mode. 1: internal pull-up enabled; 0: internal pull-up disabled.
+ 3
+ 1
+ read-write
+
+
+ MCU_IE
+ Input enable of the pad during sleep mode. 1: input enabled; 0: input disabled.
+ 4
+ 1
+ read-write
+
+
+ MCU_DRV
+ Select the drive strength of the pad during sleep mode. A higher value corresponds with a higher strength.
+ 5
+ 2
+ read-write
+
+
+ FUN_WPD
+ Pull-down enable of the pad. 1: internal pull-down enabled, 0: internal pull-down disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull-down circuitry, therefore, their FUN_WPD is always 0.
+ 7
+ 1
+ read-write
+
+
+ FUN_WPU
+ Pull-up enable of the pad. 1: internal pull-up enabled; 0: internal pull-up disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull- down circuitry, therefore, their FUN_WPU is always 0.
+ 8
+ 1
+ read-write
+
+
+ FUN_IE
+ Input enable of the pad. 1: input enabled; 0: input disabled.
+ 9
+ 1
+ read-write
+
+
+ FUN_DRV
+ Select the drive strength of the pad. A higher value corresponds with a higher strength. For GPIO34-39, FUN_DRV is always 0. For detailed drive strength, please see note 8 in Table ”Notes on ESP32 Pin Lists”, in ESP32 Datasheet.
+ 10
+ 2
+ read-write
+
+
+ MCU_SEL
+ Select the IO_MUX function for this signal. 0 selects Function 0, 1 selects Function 1, etc.
+ 12
+ 3
+ read-write
+
+
+
+
+ GPIO24
+ 0x90
+ 0x20
+
+
+ MCU_OE
+ Output enable of the pad in sleep mode. 1: enable output; 0: disable output.
+ 0
+ 1
+ read-write
+
+
+ SLP_SEL
+ Sleep mode selection of this pad. Set to 1 to put the pad in sleep mode.
+ 1
+ 1
+ read-write
+
+
+ MCU_WPD
+ Pull-down enable of the pad during sleep mode. 1: internal pull-down enabled; 0: internal pull-down disabled.
+ 2
+ 1
+ read-write
+
+
+ MCU_WPU
+ Pull-up enable of the pad during sleep mode. 1: internal pull-up enabled; 0: internal pull-up disabled.
+ 3
+ 1
+ read-write
+
+
+ MCU_IE
+ Input enable of the pad during sleep mode. 1: input enabled; 0: input disabled.
+ 4
+ 1
+ read-write
+
+
+ MCU_DRV
+ Select the drive strength of the pad during sleep mode. A higher value corresponds with a higher strength.
+ 5
+ 2
+ read-write
+
+
+ FUN_WPD
+ Pull-down enable of the pad. 1: internal pull-down enabled, 0: internal pull-down disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull-down circuitry, therefore, their FUN_WPD is always 0.
+ 7
+ 1
+ read-write
+
+
+ FUN_WPU
+ Pull-up enable of the pad. 1: internal pull-up enabled; 0: internal pull-up disabled. GPIO pins 34-39 are input-only. These pins do not feature an output driver or internal pull- up/pull- down circuitry, therefore, their FUN_WPU is always 0.
+ 8
+ 1
+ read-write
+
+
+ FUN_IE
+ Input enable of the pad. 1: input enabled; 0: input disabled.
+ 9
+ 1
+ read-write
+
+
+ FUN_DRV
+ Select the drive strength of the pad. A higher value corresponds with a higher strength. For GPIO34-39, FUN_DRV is always 0. For detailed drive strength, please see note 8 in Table ”Notes on ESP32 Pin Lists”, in ESP32 Datasheet.
+ 10
+ 2
+ read-write
+
+
+ MCU_SEL
+ Select the IO_MUX function for this signal. 0 selects Function 0, 1 selects Function 1, etc.
+ 12
+ 3
+ read-write
+
+
+
+
+
+
+ LEDC
+ LED Control PWM (Pulse Width Modulation)
+ LEDC
+ 0x3FF59000
+
+ 0x0
+ 0x198
+ registers
+
+
+ LEDC
+ 43
+
+
+ TIMER1
+ 56
+
+
+ TIMER2
+ 57
+
+
+
+ 8
+ 0x14
+ 0-7
+ HSCH%s_CONF0
+ 0x0
+ 0x20
+
+
+ TIMER_SEL
+ There are four high speed timers the two bits are used to select one of them for high speed channel0. 2'b00: seletc hstimer0. 2'b01: select hstimer1. 2'b10: select hstimer2. 2'b11: select hstimer3.
+ 0
+ 2
+ read-write
+
+
+ SIG_OUT_EN
+ This is the output enable control bit for high speed channel0
+ 2
+ 1
+ read-write
+
+
+ IDLE_LV
+ This bit is used to control the output value when high speed channel0 is off.
+ 3
+ 1
+ read-write
+
+
+
+
+ 8
+ 0x14
+ 0-7
+ HSCH%s_HPOINT
+ 0x4
+ 0x20
+
+
+ HPOINT
+ The output value changes to high when htimerx(x=[0 3]) selected by high speed channel0 has reached reg_hpoint_hsch0[19:0]
+ 0
+ 20
+ read-write
+
+
+
+
+ 8
+ 0x14
+ 0-7
+ HSCH%s_DUTY
+ 0x8
+ 0x20
+
+
+ DUTY
+ This register represents the current duty of the output signal for high speed channel0.
+ 0
+ 25
+ read-write
+
+
+
+
+ 8
+ 0x14
+ 0-7
+ HSCH%s_CONF1
+ 0xC
+ 0x20
+ 0x40000000
+
+
+ DUTY_SCALE
+ This register controls the increase or decrease step scale for high speed channel0.
+ 0
+ 10
+ read-write
+
+
+ DUTY_CYCLE
+ This register is used to increase or decrease the duty every reg_duty_cycle_hsch0 cycles for high speed channel0.
+ 10
+ 10
+ read-write
+
+
+ DUTY_NUM
+ This register is used to control the num of increased or decreased times for high speed channel0.
+ 20
+ 10
+ read-write
+
+
+ DUTY_INC
+ This register is used to increase the duty of output signal or decrease the duty of output signal for high speed channel0.
+ 30
+ 1
+ read-write
+
+
+ DUTY_START
+ When reg_duty_num_hsch0 reg_duty_cycle_hsch0 and reg_duty_scale_hsch0 has been configured. these register won't take effect until set reg_duty_start_hsch0. this bit is automatically cleared by hardware.
+ 31
+ 1
+ read-write
+
+
+
+
+ 8
+ 0x14
+ 0-7
+ HSCH%s_DUTY_R
+ 0x10
+ 0x20
+
+
+ DUTY_R
+ This register represents the current duty cycle of the output signal for high-speed channel %s
+ 0
+ 25
+ read-only
+
+
+
+
+ 8
+ 0x14
+ 0-7
+ LSCH%s_CONF0
+ 0xA0
+ 0x20
+
+
+ TIMER_SEL
+ There are four low speed timers the two bits are used to select one of them for low speed channel0. 2'b00: seletc lstimer0. 2'b01: select lstimer1. 2'b10: select lstimer2. 2'b11: select lstimer3.
+ 0
+ 2
+ read-write
+
+
+ SIG_OUT_EN
+ This is the output enable control bit for low speed channel0.
+ 2
+ 1
+ read-write
+
+
+ IDLE_LV
+ This bit is used to control the output value when low speed channel0 is off.
+ 3
+ 1
+ read-write
+
+
+ PARA_UP
+ This bit is used to update register LEDC_LSCH0_HPOINT and LEDC_LSCH0_DUTY for low speed channel0.
+ 4
+ 1
+ read-write
+
+
+
+
+ 8
+ 0x14
+ 0-7
+ LSCH%s_HPOINT
+ 0xA4
+ 0x20
+
+
+ HPOINT
+ The output value changes to high when lstimerx(x=[0 3]) selected by low speed channel0 has reached reg_hpoint_lsch0[19:0]
+ 0
+ 20
+ read-write
+
+
+
+
+ 8
+ 0x14
+ 0-7
+ LSCH%s_DUTY
+ 0xA8
+ 0x20
+ read-write
+
+
+ DUTY
+ This register represents the current duty of the output signal for low speed channel0.
+ 0
+ 25
+ read-write
+
+
+
+
+ 8
+ 0x14
+ 0-7
+ LSCH%s_CONF1
+ 0xAC
+ 0x20
+ 0x40000000
+
+
+ DUTY_SCALE
+ This register controls the increase or decrease step scale for low speed channel0.
+ 0
+ 10
+ read-write
+
+
+ DUTY_CYCLE
+ This register is used to increase or decrease the duty every reg_duty_cycle_lsch0 cycles for low speed channel0.
+ 10
+ 10
+ read-write
+
+
+ DUTY_NUM
+ This register is used to control the num of increased or decreased times for low speed channel6.
+ 20
+ 10
+ read-write
+
+
+ DUTY_INC
+ This register is used to increase the duty of output signal or decrease the duty of output signal for low speed channel6.
+ 30
+ 1
+ read-write
+
+
+ DUTY_START
+ When reg_duty_num_hsch1 reg_duty_cycle_hsch1 and reg_duty_scale_hsch1 has been configured. these register won't take effect until set reg_duty_start_hsch1. this bit is automatically cleared by hardware.
+ 31
+ 1
+ read-write
+
+
+
+
+ 8
+ 0x14
+ 0-7
+ LSCH%s_DUTY_R
+ 0xB0
+ 0x20
+
+
+ DUTY_R
+ This register represents the current duty cycle of the output signal for low-speed channel %s
+ 0
+ 25
+ read-only
+
+
+
+
+ 4
+ 0x8
+ 0-3
+ HSTIMER%s_CONF
+ 0x140
+ 0x20
+ 0x01000000
+
+
+ DUTY_RES
+ This register controls the range of the counter in high speed timer0. the counter range is [0 2**reg_hstimer0_lim] the max bit width for counter is 20.
+ 0
+ 5
+ read-write
+
+
+ DIV_NUM
+ This register is used to configure parameter for divider in high speed timer0 the least significant eight bits represent the decimal part.
+ 5
+ 18
+ read-write
+
+
+ PAUSE
+ This bit is used to pause the counter in high speed timer0
+ 23
+ 1
+ read-write
+
+
+ RST
+ This bit is used to reset high speed timer0 the counter will be 0 after reset.
+ 24
+ 1
+ read-write
+
+
+ TICK_SEL
+ This bit is used to choose apb_clk or ref_tick for high speed timer0. 1'b1:apb_clk 0:ref_tick
+ 25
+ 1
+ read-write
+
+
+ LIM
+ 31
+ 5
+ read-write
+
+
+
+
+ 4
+ 0x8
+ 0-3
+ HSTIMER%s_VALUE
+ 0x144
+ 0x20
+
+
+ CNT
+ software can read this register to get the current counter value in high speed timer0
+ 0
+ 20
+ read-only
+
+
+
+
+ 4
+ 0x8
+ 0-3
+ LSTIMER%s_CONF
+ 0x160
+ 0x20
+ 0x01000000
+
+
+ DUTY_RES
+ This register controls the range of the counter in low speed timer0. the counter range is [0 2**reg_lstimer0_lim] the max bit width for counter is 20.
+ 0
+ 5
+ read-write
+
+
+ DIV_NUM
+ This register is used to configure parameter for divider in low speed timer0 the least significant eight bits represent the decimal part.
+ 5
+ 18
+ read-write
+
+
+ PAUSE
+ This bit is used to pause the counter in low speed timer0.
+ 23
+ 1
+ read-write
+
+
+ RST
+ This bit is used to reset low speed timer0 the counter will be 0 after reset.
+ 24
+ 1
+ read-write
+
+
+ TICK_SEL
+ This bit is used to choose slow_clk or ref_tick for low speed timer0. 1'b1:slow_clk 0:ref_tick
+ 25
+ 1
+ read-write
+
+
+ PARA_UP
+ Set this bit to update reg_div_num_lstime0 and reg_lstimer0_lim.
+ 26
+ 1
+ read-write
+
+
+ LIM
+ 31
+ 5
+ read-write
+
+
+
+
+ 4
+ 0x8
+ 0-3
+ LSTIMER%s_VALUE
+ 0x164
+ 0x20
+
+
+ CNT
+ software can read this register to get the current counter value in low speed timer0.
+ 0
+ 20
+ read-only
+
+
+
+
+ INT_RAW
+ 0x180
+ 0x20
+
+
+ HSTIMER0_OVF_INT_RAW
+ The interrupt raw bit for high speed channel0 counter overflow.
+ 0
+ 1
+ read-only
+
+
+ HSTIMER1_OVF_INT_RAW
+ The interrupt raw bit for high speed channel1 counter overflow.
+ 1
+ 1
+ read-only
+
+
+ HSTIMER2_OVF_INT_RAW
+ The interrupt raw bit for high speed channel2 counter overflow.
+ 2
+ 1
+ read-only
+
+
+ HSTIMER3_OVF_INT_RAW
+ The interrupt raw bit for high speed channel3 counter overflow.
+ 3
+ 1
+ read-only
+
+
+ LSTIMER0_OVF_INT_RAW
+ The interrupt raw bit for low speed channel0 counter overflow.
+ 4
+ 1
+ read-only
+
+
+ LSTIMER1_OVF_INT_RAW
+ The interrupt raw bit for low speed channel1 counter overflow.
+ 5
+ 1
+ read-only
+
+
+ LSTIMER2_OVF_INT_RAW
+ The interrupt raw bit for low speed channel2 counter overflow.
+ 6
+ 1
+ read-only
+
+
+ LSTIMER3_OVF_INT_RAW
+ The interrupt raw bit for low speed channel3 counter overflow.
+ 7
+ 1
+ read-only
+
+
+ DUTY_CHNG_END_HSCH0_INT_RAW
+ The interrupt raw bit for high speed channel 0 duty change done.
+ 8
+ 1
+ read-only
+
+
+ DUTY_CHNG_END_HSCH1_INT_RAW
+ The interrupt raw bit for high speed channel 1 duty change done.
+ 9
+ 1
+ read-only
+
+
+ DUTY_CHNG_END_HSCH2_INT_RAW
+ The interrupt raw bit for high speed channel 2 duty change done.
+ 10
+ 1
+ read-only
+
+
+ DUTY_CHNG_END_HSCH3_INT_RAW
+ The interrupt raw bit for high speed channel 3 duty change done.
+ 11
+ 1
+ read-only
+
+
+ DUTY_CHNG_END_HSCH4_INT_RAW
+ The interrupt raw bit for high speed channel 4 duty change done.
+ 12
+ 1
+ read-only
+
+
+ DUTY_CHNG_END_HSCH5_INT_RAW
+ The interrupt raw bit for high speed channel 5 duty change done.
+ 13
+ 1
+ read-only
+
+
+ DUTY_CHNG_END_HSCH6_INT_RAW
+ The interrupt raw bit for high speed channel 6 duty change done.
+ 14
+ 1
+ read-only
+
+
+ DUTY_CHNG_END_HSCH7_INT_RAW
+ The interrupt raw bit for high speed channel 7 duty change done.
+ 15
+ 1
+ read-only
+
+
+ DUTY_CHNG_END_LSCH0_INT_RAW
+ The interrupt raw bit for low speed channel 0 duty change done.
+ 16
+ 1
+ read-only
+
+
+ DUTY_CHNG_END_LSCH1_INT_RAW
+ The interrupt raw bit for low speed channel 1 duty change done.
+ 17
+ 1
+ read-only
+
+
+ DUTY_CHNG_END_LSCH2_INT_RAW
+ The interrupt raw bit for low speed channel 2 duty change done.
+ 18
+ 1
+ read-only
+
+
+ DUTY_CHNG_END_LSCH3_INT_RAW
+ The interrupt raw bit for low speed channel 3 duty change done.
+ 19
+ 1
+ read-only
+
+
+ DUTY_CHNG_END_LSCH4_INT_RAW
+ The interrupt raw bit for low speed channel 4 duty change done.
+ 20
+ 1
+ read-only
+
+
+ DUTY_CHNG_END_LSCH5_INT_RAW
+ The interrupt raw bit for low speed channel 5 duty change done.
+ 21
+ 1
+ read-only
+
+
+ DUTY_CHNG_END_LSCH6_INT_RAW
+ The interrupt raw bit for low speed channel 6 duty change done.
+ 22
+ 1
+ read-only
+
+
+ DUTY_CHNG_END_LSCH7_INT_RAW
+ The interrupt raw bit for low speed channel 7 duty change done.
+ 23
+ 1
+ read-only
+
+
+
+
+ INT_ST
+ 0x184
+ 0x20
+
+
+ HSTIMER0_OVF_INT_ST
+ The interrupt status bit for high speed channel0 counter overflow event.
+ 0
+ 1
+ read-only
+
+
+ HSTIMER1_OVF_INT_ST
+ The interrupt status bit for high speed channel1 counter overflow event.
+ 1
+ 1
+ read-only
+
+
+ HSTIMER2_OVF_INT_ST
+ The interrupt status bit for high speed channel2 counter overflow event.
+ 2
+ 1
+ read-only
+
+
+ HSTIMER3_OVF_INT_ST
+ The interrupt status bit for high speed channel3 counter overflow event.
+ 3
+ 1
+ read-only
+
+
+ LSTIMER0_OVF_INT_ST
+ The interrupt status bit for low speed channel0 counter overflow event.
+ 4
+ 1
+ read-only
+
+
+ LSTIMER1_OVF_INT_ST
+ The interrupt status bit for low speed channel1 counter overflow event.
+ 5
+ 1
+ read-only
+
+
+ LSTIMER2_OVF_INT_ST
+ The interrupt status bit for low speed channel2 counter overflow event.
+ 6
+ 1
+ read-only
+
+
+ LSTIMER3_OVF_INT_ST
+ The interrupt status bit for low speed channel3 counter overflow event.
+ 7
+ 1
+ read-only
+
+
+ DUTY_CHNG_END_HSCH0_INT_ST
+ The interrupt status bit for high speed channel 0 duty change done event.
+ 8
+ 1
+ read-only
+
+
+ DUTY_CHNG_END_HSCH1_INT_ST
+ The interrupt status bit for high speed channel 1 duty change done event.
+ 9
+ 1
+ read-only
+
+
+ DUTY_CHNG_END_HSCH2_INT_ST
+ The interrupt status bit for high speed channel 2 duty change done event.
+ 10
+ 1
+ read-only
+
+
+ DUTY_CHNG_END_HSCH3_INT_ST
+ The interrupt status bit for high speed channel 3 duty change done event.
+ 11
+ 1
+ read-only
+
+
+ DUTY_CHNG_END_HSCH4_INT_ST
+ The interrupt status bit for high speed channel 4 duty change done event.
+ 12
+ 1
+ read-only
+
+
+ DUTY_CHNG_END_HSCH5_INT_ST
+ The interrupt status bit for high speed channel 5 duty change done event.
+ 13
+ 1
+ read-only
+
+
+ DUTY_CHNG_END_HSCH6_INT_ST
+ The interrupt status bit for high speed channel 6 duty change done event.
+ 14
+ 1
+ read-only
+
+
+ DUTY_CHNG_END_HSCH7_INT_ST
+ The interrupt status bit for high speed channel 7 duty change done event.
+ 15
+ 1
+ read-only
+
+
+ DUTY_CHNG_END_LSCH0_INT_ST
+ The interrupt status bit for low speed channel 0 duty change done event.
+ 16
+ 1
+ read-only
+
+
+ DUTY_CHNG_END_LSCH1_INT_ST
+ The interrupt status bit for low speed channel 1 duty change done event.
+ 17
+ 1
+ read-only
+
+
+ DUTY_CHNG_END_LSCH2_INT_ST
+ The interrupt status bit for low speed channel 2 duty change done event.
+ 18
+ 1
+ read-only
+
+
+ DUTY_CHNG_END_LSCH3_INT_ST
+ The interrupt status bit for low speed channel 3 duty change done event.
+ 19
+ 1
+ read-only
+
+
+ DUTY_CHNG_END_LSCH4_INT_ST
+ The interrupt status bit for low speed channel 4 duty change done event.
+ 20
+ 1
+ read-only
+
+
+ DUTY_CHNG_END_LSCH5_INT_ST
+ The interrupt status bit for low speed channel 5 duty change done event.
+ 21
+ 1
+ read-only
+
+
+ DUTY_CHNG_END_LSCH6_INT_ST
+ The interrupt status bit for low speed channel 6 duty change done event.
+ 22
+ 1
+ read-only
+
+
+ DUTY_CHNG_END_LSCH7_INT_ST
+ The interrupt status bit for low speed channel 7 duty change done event
+ 23
+ 1
+ read-only
+
+
+
+
+ INT_ENA
+ 0x188
+ 0x20
+
+
+ HSTIMER0_OVF_INT_ENA
+ The interrupt enable bit for high speed channel0 counter overflow interrupt.
+ 0
+ 1
+ read-write
+
+
+ HSTIMER1_OVF_INT_ENA
+ The interrupt enable bit for high speed channel1 counter overflow interrupt.
+ 1
+ 1
+ read-write
+
+
+ HSTIMER2_OVF_INT_ENA
+ The interrupt enable bit for high speed channel2 counter overflow interrupt.
+ 2
+ 1
+ read-write
+
+
+ HSTIMER3_OVF_INT_ENA
+ The interrupt enable bit for high speed channel3 counter overflow interrupt.
+ 3
+ 1
+ read-write
+
+
+ LSTIMER0_OVF_INT_ENA
+ The interrupt enable bit for low speed channel0 counter overflow interrupt.
+ 4
+ 1
+ read-write
+
+
+ LSTIMER1_OVF_INT_ENA
+ The interrupt enable bit for low speed channel1 counter overflow interrupt.
+ 5
+ 1
+ read-write
+
+
+ LSTIMER2_OVF_INT_ENA
+ The interrupt enable bit for low speed channel2 counter overflow interrupt.
+ 6
+ 1
+ read-write
+
+
+ LSTIMER3_OVF_INT_ENA
+ The interrupt enable bit for low speed channel3 counter overflow interrupt.
+ 7
+ 1
+ read-write
+
+
+ DUTY_CHNG_END_HSCH0_INT_ENA
+ The interrupt enable bit for high speed channel 0 duty change done interrupt.
+ 8
+ 1
+ read-write
+
+
+ DUTY_CHNG_END_HSCH1_INT_ENA
+ The interrupt enable bit for high speed channel 1 duty change done interrupt.
+ 9
+ 1
+ read-write
+
+
+ DUTY_CHNG_END_HSCH2_INT_ENA
+ The interrupt enable bit for high speed channel 2 duty change done interrupt.
+ 10
+ 1
+ read-write
+
+
+ DUTY_CHNG_END_HSCH3_INT_ENA
+ The interrupt enable bit for high speed channel 3 duty change done interrupt.
+ 11
+ 1
+ read-write
+
+
+ DUTY_CHNG_END_HSCH4_INT_ENA
+ The interrupt enable bit for high speed channel 4 duty change done interrupt.
+ 12
+ 1
+ read-write
+
+
+ DUTY_CHNG_END_HSCH5_INT_ENA
+ The interrupt enable bit for high speed channel 5 duty change done interrupt.
+ 13
+ 1
+ read-write
+
+
+ DUTY_CHNG_END_HSCH6_INT_ENA
+ The interrupt enable bit for high speed channel 6 duty change done interrupt.
+ 14
+ 1
+ read-write
+
+
+ DUTY_CHNG_END_HSCH7_INT_ENA
+ The interrupt enable bit for high speed channel 7 duty change done interrupt.
+ 15
+ 1
+ read-write
+
+
+ DUTY_CHNG_END_LSCH0_INT_ENA
+ The interrupt enable bit for low speed channel 0 duty change done interrupt.
+ 16
+ 1
+ read-write
+
+
+ DUTY_CHNG_END_LSCH1_INT_ENA
+ The interrupt enable bit for low speed channel 1 duty change done interrupt.
+ 17
+ 1
+ read-write
+
+
+ DUTY_CHNG_END_LSCH2_INT_ENA
+ The interrupt enable bit for low speed channel 2 duty change done interrupt.
+ 18
+ 1
+ read-write
+
+
+ DUTY_CHNG_END_LSCH3_INT_ENA
+ The interrupt enable bit for low speed channel 3 duty change done interrupt.
+ 19
+ 1
+ read-write
+
+
+ DUTY_CHNG_END_LSCH4_INT_ENA
+ The interrupt enable bit for low speed channel 4 duty change done interrupt.
+ 20
+ 1
+ read-write
+
+
+ DUTY_CHNG_END_LSCH5_INT_ENA
+ The interrupt enable bit for low speed channel 5 duty change done interrupt.
+ 21
+ 1
+ read-write
+
+
+ DUTY_CHNG_END_LSCH6_INT_ENA
+ The interrupt enable bit for low speed channel 6 duty change done interrupt.
+ 22
+ 1
+ read-write
+
+
+ DUTY_CHNG_END_LSCH7_INT_ENA
+ The interrupt enable bit for low speed channel 7 duty change done interrupt.
+ 23
+ 1
+ read-write
+
+
+
+
+ INT_CLR
+ 0x18C
+ 0x20
+
+
+ HSTIMER0_OVF_INT_CLR
+ Set this bit to clear high speed channel0 counter overflow interrupt.
+ 0
+ 1
+ write-only
+
+
+ HSTIMER1_OVF_INT_CLR
+ Set this bit to clear high speed channel1 counter overflow interrupt.
+ 1
+ 1
+ write-only
+
+
+ HSTIMER2_OVF_INT_CLR
+ Set this bit to clear high speed channel2 counter overflow interrupt.
+ 2
+ 1
+ write-only
+
+
+ HSTIMER3_OVF_INT_CLR
+ Set this bit to clear high speed channel3 counter overflow interrupt.
+ 3
+ 1
+ write-only
+
+
+ LSTIMER0_OVF_INT_CLR
+ Set this bit to clear low speed channel0 counter overflow interrupt.
+ 4
+ 1
+ write-only
+
+
+ LSTIMER1_OVF_INT_CLR
+ Set this bit to clear low speed channel1 counter overflow interrupt.
+ 5
+ 1
+ write-only
+
+
+ LSTIMER2_OVF_INT_CLR
+ Set this bit to clear low speed channel2 counter overflow interrupt.
+ 6
+ 1
+ write-only
+
+
+ LSTIMER3_OVF_INT_CLR
+ Set this bit to clear low speed channel3 counter overflow interrupt.
+ 7
+ 1
+ write-only
+
+
+ DUTY_CHNG_END_HSCH0_INT_CLR
+ Set this bit to clear high speed channel 0 duty change done interrupt.
+ 8
+ 1
+ write-only
+
+
+ DUTY_CHNG_END_HSCH1_INT_CLR
+ Set this bit to clear high speed channel 1 duty change done interrupt.
+ 9
+ 1
+ write-only
+
+
+ DUTY_CHNG_END_HSCH2_INT_CLR
+ Set this bit to clear high speed channel 2 duty change done interrupt.
+ 10
+ 1
+ write-only
+
+
+ DUTY_CHNG_END_HSCH3_INT_CLR
+ Set this bit to clear high speed channel 3 duty change done interrupt.
+ 11
+ 1
+ write-only
+
+
+ DUTY_CHNG_END_HSCH4_INT_CLR
+ Set this bit to clear high speed channel 4 duty change done interrupt.
+ 12
+ 1
+ write-only
+
+
+ DUTY_CHNG_END_HSCH5_INT_CLR
+ Set this bit to clear high speed channel 5 duty change done interrupt.
+ 13
+ 1
+ write-only
+
+
+ DUTY_CHNG_END_HSCH6_INT_CLR
+ Set this bit to clear high speed channel 6 duty change done interrupt.
+ 14
+ 1
+ write-only
+
+
+ DUTY_CHNG_END_HSCH7_INT_CLR
+ Set this bit to clear high speed channel 7 duty change done interrupt.
+ 15
+ 1
+ write-only
+
+
+ DUTY_CHNG_END_LSCH0_INT_CLR
+ Set this bit to clear low speed channel 0 duty change done interrupt.
+ 16
+ 1
+ write-only
+
+
+ DUTY_CHNG_END_LSCH1_INT_CLR
+ Set this bit to clear low speed channel 1 duty change done interrupt.
+ 17
+ 1
+ write-only
+
+
+ DUTY_CHNG_END_LSCH2_INT_CLR
+ Set this bit to clear low speed channel 2 duty change done interrupt.
+ 18
+ 1
+ write-only
+
+
+ DUTY_CHNG_END_LSCH3_INT_CLR
+ Set this bit to clear low speed channel 3 duty change done interrupt.
+ 19
+ 1
+ write-only
+
+
+ DUTY_CHNG_END_LSCH4_INT_CLR
+ Set this bit to clear low speed channel 4 duty change done interrupt.
+ 20
+ 1
+ write-only
+
+
+ DUTY_CHNG_END_LSCH5_INT_CLR
+ Set this bit to clear low speed channel 5 duty change done interrupt.
+ 21
+ 1
+ write-only
+
+
+ DUTY_CHNG_END_LSCH6_INT_CLR
+ Set this bit to clear low speed channel 6 duty change done interrupt.
+ 22
+ 1
+ write-only
+
+
+ DUTY_CHNG_END_LSCH7_INT_CLR
+ Set this bit to clear low speed channel 7 duty change done interrupt.
+ 23
+ 1
+ write-only
+
+
+
+
+ CONF
+ 0x190
+ 0x20
+
+
+ APB_CLK_SEL
+ This bit is used to set the frequency of slow_clk. 1'b1:80mhz 1'b0:8mhz
+ 0
+ 1
+ read-write
+
+
+
+
+ DATE
+ 0x1FC
+ 0x20
+ 0x16031700
+
+
+ DATE
+ This register represents the version .
+ 0
+ 32
+ read-write
+
+
+
+
+
+
+ PWM0
+ Motor Control Pulse-Width Modulation
+ MCPWM
+ 0x3FF5E000
+
+ 0x0
+ 0x128
+ registers
+
+
+ PWM0
+ 39
+
+
+
+ CLK_CFG
+ 0x0
+ 0x20
+
+
+ CLK_PRESCALE
+ 0
+ 8
+ read-write
+
+
+
+
+ TIMER0_CFG0
+ 0x4
+ 0x20
+ 0x0000FF00
+
+
+ TIMER0_PRESCALE
+ 0
+ 8
+ read-write
+
+
+ TIMER0_PERIOD
+ 8
+ 16
+ read-write
+
+
+ TIMER0_PERIOD_UPMETHOD
+ 24
+ 2
+ read-write
+
+
+
+
+ TIMER0_CFG1
+ 0x8
+ 0x20
+
+
+ TIMER0_START
+ 0
+ 3
+ read-write
+
+
+ TIMER0_MOD
+ 3
+ 2
+ read-write
+
+
+
+
+ TIMER0_SYNC
+ 0xC
+ 0x20
+
+
+ TIMER0_SYNCI_EN
+ 0
+ 1
+ read-write
+
+
+ SW
+ 1
+ 1
+ read-write
+
+
+ TIMER0_SYNCO_SEL
+ 2
+ 2
+ read-write
+
+
+ TIMER0_PHASE
+ 4
+ 16
+ read-write
+
+
+ TIMER0_PHASE_DIRECTION
+ 20
+ 1
+ read-write
+
+
+
+
+ TIMER0_STATUS
+ 0x10
+ 0x20
+
+
+ TIMER0_VALUE
+ 0
+ 16
+ read-only
+
+
+ TIMER0_DIRECTION
+ 16
+ 1
+ read-only
+
+
+
+
+ TIMER1_CFG0
+ 0x14
+ 0x20
+ 0x0000FF00
+
+
+ TIMER1_PRESCALE
+ 0
+ 8
+ read-write
+
+
+ TIMER1_PERIOD
+ 8
+ 16
+ read-write
+
+
+ TIMER1_PERIOD_UPMETHOD
+ 24
+ 2
+ read-write
+
+
+
+
+ TIMER1_CFG1
+ 0x18
+ 0x20
+
+
+ TIMER1_START
+ 0
+ 3
+ read-write
+
+
+ TIMER1_MOD
+ 3
+ 2
+ read-write
+
+
+
+
+ TIMER1_SYNC
+ 0x1C
+ 0x20
+
+
+ TIMER1_SYNCI_EN
+ 0
+ 1
+ read-write
+
+
+ SW
+ 1
+ 1
+ read-write
+
+
+ TIMER1_SYNCO_SEL
+ 2
+ 2
+ read-write
+
+
+ TIMER1_PHASE
+ 4
+ 16
+ read-write
+
+
+ TIMER1_PHASE_DIRECTION
+ 20
+ 1
+ read-write
+
+
+
+
+ TIMER1_STATUS
+ 0x20
+ 0x20
+
+
+ TIMER1_VALUE
+ 0
+ 16
+ read-only
+
+
+ TIMER1_DIRECTION
+ 16
+ 1
+ read-only
+
+
+
+
+ TIMER2_CFG0
+ 0x24
+ 0x20
+ 0x0000FF00
+
+
+ TIMER2_PRESCALE
+ 0
+ 8
+ read-write
+
+
+ TIMER2_PERIOD
+ 8
+ 16
+ read-write
+
+
+ TIMER2_PERIOD_UPMETHOD
+ 24
+ 2
+ read-write
+
+
+
+
+ TIMER2_CFG1
+ 0x28
+ 0x20
+
+
+ TIMER2_START
+ 0
+ 3
+ read-write
+
+
+ TIMER2_MOD
+ 3
+ 2
+ read-write
+
+
+
+
+ TIMER2_SYNC
+ 0x2C
+ 0x20
+
+
+ TIMER2_SYNCI_EN
+ 0
+ 1
+ read-write
+
+
+ SW
+ 1
+ 1
+ read-write
+
+
+ TIMER2_SYNCO_SEL
+ 2
+ 2
+ read-write
+
+
+ TIMER2_PHASE
+ 4
+ 16
+ read-write
+
+
+ TIMER2_PHASE_DIRECTION
+ 20
+ 1
+ read-write
+
+
+
+
+ TIMER2_STATUS
+ 0x30
+ 0x20
+
+
+ TIMER2_VALUE
+ 0
+ 16
+ read-only
+
+
+ TIMER2_DIRECTION
+ 16
+ 1
+ read-only
+
+
+
+
+ TIMER_SYNCI_CFG
+ 0x34
+ 0x20
+
+
+ TIMER0_SYNCISEL
+ 0
+ 3
+ read-write
+
+
+ TIMER1_SYNCISEL
+ 3
+ 3
+ read-write
+
+
+ TIMER2_SYNCISEL
+ 6
+ 3
+ read-write
+
+
+ EXTERNAL_SYNCI0_INVERT
+ 9
+ 1
+ read-write
+
+
+ EXTERNAL_SYNCI1_INVERT
+ 10
+ 1
+ read-write
+
+
+ EXTERNAL_SYNCI2_INVERT
+ 11
+ 1
+ read-write
+
+
+
+
+ OPERATOR_TIMERSEL
+ 0x38
+ 0x20
+
+
+ OPERATOR0_TIMERSEL
+ 0
+ 2
+ read-write
+
+
+ OPERATOR1_TIMERSEL
+ 2
+ 2
+ read-write
+
+
+ OPERATOR2_TIMERSEL
+ 4
+ 2
+ read-write
+
+
+
+
+ GEN0_STMP_CFG
+ 0x3C
+ 0x20
+
+
+ GEN0_A_UPMETHOD
+ 0
+ 4
+ read-write
+
+
+ GEN0_B_UPMETHOD
+ 4
+ 4
+ read-write
+
+
+ GEN0_A_SHDW_FULL
+ 8
+ 1
+ read-write
+
+
+ GEN0_B_SHDW_FULL
+ 9
+ 1
+ read-write
+
+
+
+
+ GEN0_TSTMP_A
+ 0x40
+ 0x20
+
+
+ GEN0_A
+ 0
+ 16
+ read-write
+
+
+
+
+ GEN0_TSTMP_B
+ 0x44
+ 0x20
+
+
+ GEN0_B
+ 0
+ 16
+ read-write
+
+
+
+
+ GEN0_CFG0
+ 0x48
+ 0x20
+
+
+ GEN0_CFG_UPMETHOD
+ 0
+ 4
+ read-write
+
+
+ GEN0_T0_SEL
+ 4
+ 3
+ read-write
+
+
+ GEN0_T1_SEL
+ 7
+ 3
+ read-write
+
+
+
+
+ GEN0_FORCE
+ 0x4C
+ 0x20
+ 0x00000020
+
+
+ GEN0_CNTUFORCE_UPMETHOD
+ 0
+ 6
+ read-write
+
+
+ GEN0_A_CNTUFORCE_MODE
+ 6
+ 2
+ read-write
+
+
+ GEN0_B_CNTUFORCE_MODE
+ 8
+ 2
+ read-write
+
+
+ GEN0_A_NCIFORCE
+ 10
+ 1
+ read-write
+
+
+ GEN0_A_NCIFORCE_MODE
+ 11
+ 2
+ read-write
+
+
+ GEN0_B_NCIFORCE
+ 13
+ 1
+ read-write
+
+
+ GEN0_B_NCIFORCE_MODE
+ 14
+ 2
+ read-write
+
+
+
+
+ GEN0_A
+ 0x50
+ 0x20
+
+
+ UTEZ
+ 0
+ 2
+ read-write
+
+
+ UTEP
+ 2
+ 2
+ read-write
+
+
+ UTEA
+ 4
+ 2
+ read-write
+
+
+ UTEB
+ 6
+ 2
+ read-write
+
+
+ UT0
+ 8
+ 2
+ read-write
+
+
+ UT1
+ 10
+ 2
+ read-write
+
+
+ DTEZ
+ 12
+ 2
+ read-write
+
+
+ DTEP
+ 14
+ 2
+ read-write
+
+
+ DTEA
+ 16
+ 2
+ read-write
+
+
+ DTEB
+ 18
+ 2
+ read-write
+
+
+ DT0
+ 20
+ 2
+ read-write
+
+
+ DT1
+ 22
+ 2
+ read-write
+
+
+
+
+ GEN0_B
+ 0x54
+ 0x20
+
+
+ UTEZ
+ 0
+ 2
+ read-write
+
+
+ UTEP
+ 2
+ 2
+ read-write
+
+
+ UTEA
+ 4
+ 2
+ read-write
+
+
+ UTEB
+ 6
+ 2
+ read-write
+
+
+ UT0
+ 8
+ 2
+ read-write
+
+
+ UT1
+ 10
+ 2
+ read-write
+
+
+ DTEZ
+ 12
+ 2
+ read-write
+
+
+ DTEP
+ 14
+ 2
+ read-write
+
+
+ DTEA
+ 16
+ 2
+ read-write
+
+
+ DTEB
+ 18
+ 2
+ read-write
+
+
+ DT0
+ 20
+ 2
+ read-write
+
+
+ DT1
+ 22
+ 2
+ read-write
+
+
+
+
+ DT0_CFG
+ 0x58
+ 0x20
+ 0x00018000
+
+
+ DT0_FED_UPMETHOD
+ 0
+ 4
+ read-write
+
+
+ DT0_RED_UPMETHOD
+ 4
+ 4
+ read-write
+
+
+ DT0_DEB_MODE
+ 8
+ 1
+ read-write
+
+
+ DT0_A_OUTSWAP
+ 9
+ 1
+ read-write
+
+
+ DT0_B_OUTSWAP
+ 10
+ 1
+ read-write
+
+
+ DT0_RED_INSEL
+ 11
+ 1
+ read-write
+
+
+ DT0_FED_INSEL
+ 12
+ 1
+ read-write
+
+
+ DT0_RED_OUTINVERT
+ 13
+ 1
+ read-write
+
+
+ DT0_FED_OUTINVERT
+ 14
+ 1
+ read-write
+
+
+ DT0_A_OUTBYPASS
+ 15
+ 1
+ read-write
+
+
+ DT0_B_OUTBYPASS
+ 16
+ 1
+ read-write
+
+
+ DT0_CLK_SEL
+ 17
+ 1
+ read-write
+
+
+
+
+ DT0_FED_CFG
+ 0x5C
+ 0x20
+
+
+ DT0_FED
+ 0
+ 16
+ read-write
+
+
+
+
+ DT0_RED_CFG
+ 0x60
+ 0x20
+
+
+ DT0_RED
+ 0
+ 16
+ read-write
+
+
+
+
+ CARRIER0_CFG
+ 0x64
+ 0x20
+
+
+ CARRIER0_EN
+ 0
+ 1
+ read-write
+
+
+ CARRIER0_PRESCALE
+ 1
+ 4
+ read-write
+
+
+ CARRIER0_DUTY
+ 5
+ 3
+ read-write
+
+
+ CARRIER0_OSHTWTH
+ 8
+ 4
+ read-write
+
+
+ CARRIER0_OUT_INVERT
+ 12
+ 1
+ read-write
+
+
+ CARRIER0_IN_INVERT
+ 13
+ 1
+ read-write
+
+
+
+
+ FH0_CFG0
+ 0x68
+ 0x20
+
+
+ FH0_SW_CBC
+ 0
+ 1
+ read-write
+
+
+ FH0_F2_CBC
+ 1
+ 1
+ read-write
+
+
+ FH0_F1_CBC
+ 2
+ 1
+ read-write
+
+
+ FH0_F0_CBC
+ 3
+ 1
+ read-write
+
+
+ FH0_SW_OST
+ 4
+ 1
+ read-write
+
+
+ FH0_F2_OST
+ 5
+ 1
+ read-write
+
+
+ FH0_F1_OST
+ 6
+ 1
+ read-write
+
+
+ FH0_F0_OST
+ 7
+ 1
+ read-write
+
+
+ FH0_A_CBC_D
+ 8
+ 2
+ read-write
+
+
+ FH0_A_CBC_U
+ 10
+ 2
+ read-write
+
+
+ FH0_A_OST_D
+ 12
+ 2
+ read-write
+
+
+ FH0_A_OST_U
+ 14
+ 2
+ read-write
+
+
+ FH0_B_CBC_D
+ 16
+ 2
+ read-write
+
+
+ FH0_B_CBC_U
+ 18
+ 2
+ read-write
+
+
+ FH0_B_OST_D
+ 20
+ 2
+ read-write
+
+
+ FH0_B_OST_U
+ 22
+ 2
+ read-write
+
+
+
+
+ FH0_CFG1
+ 0x6C
+ 0x20
+
+
+ FH0_CLR_OST
+ 0
+ 1
+ read-write
+
+
+ FH0_CBCPULSE
+ 1
+ 2
+ read-write
+
+
+ FH0_FORCE_CBC
+ 3
+ 1
+ read-write
+
+
+ FH0_FORCE_OST
+ 4
+ 1
+ read-write
+
+
+
+
+ FH0_STATUS
+ 0x70
+ 0x20
+
+
+ FH0_CBC_ON
+ 0
+ 1
+ read-only
+
+
+ FH0_OST_ON
+ 1
+ 1
+ read-only
+
+
+
+
+ GEN1_STMP_CFG
+ 0x74
+ 0x20
+
+
+ GEN1_A_UPMETHOD
+ 0
+ 4
+ read-write
+
+
+ GEN1_B_UPMETHOD
+ 4
+ 4
+ read-write
+
+
+ GEN1_A_SHDW_FULL
+ 8
+ 1
+ read-write
+
+
+ GEN1_B_SHDW_FULL
+ 9
+ 1
+ read-write
+
+
+
+
+ GEN1_TSTMP_A
+ 0x78
+ 0x20
+
+
+ GEN1_A
+ 0
+ 16
+ read-write
+
+
+
+
+ GEN1_TSTMP_B
+ 0x7C
+ 0x20
+
+
+ GEN1_B
+ 0
+ 16
+ read-write
+
+
+
+
+ GEN1_CFG0
+ 0x80
+ 0x20
+
+
+ GEN1_CFG_UPMETHOD
+ 0
+ 4
+ read-write
+
+
+ GEN1_T0_SEL
+ 4
+ 3
+ read-write
+
+
+ GEN1_T1_SEL
+ 7
+ 3
+ read-write
+
+
+
+
+ GEN1_FORCE
+ 0x84
+ 0x20
+ 0x00000020
+
+
+ GEN1_CNTUFORCE_UPMETHOD
+ 0
+ 6
+ read-write
+
+
+ GEN1_A_CNTUFORCE_MODE
+ 6
+ 2
+ read-write
+
+
+ GEN1_B_CNTUFORCE_MODE
+ 8
+ 2
+ read-write
+
+
+ GEN1_A_NCIFORCE
+ 10
+ 1
+ read-write
+
+
+ GEN1_A_NCIFORCE_MODE
+ 11
+ 2
+ read-write
+
+
+ GEN1_B_NCIFORCE
+ 13
+ 1
+ read-write
+
+
+ GEN1_B_NCIFORCE_MODE
+ 14
+ 2
+ read-write
+
+
+
+
+ GEN1_A
+ 0x88
+ 0x20
+
+
+ UTEZ
+ 0
+ 2
+ read-write
+
+
+ UTEP
+ 2
+ 2
+ read-write
+
+
+ UTEA
+ 4
+ 2
+ read-write
+
+
+ UTEB
+ 6
+ 2
+ read-write
+
+
+ UT0
+ 8
+ 2
+ read-write
+
+
+ UT1
+ 10
+ 2
+ read-write
+
+
+ DTEZ
+ 12
+ 2
+ read-write
+
+
+ DTEP
+ 14
+ 2
+ read-write
+
+
+ DTEA
+ 16
+ 2
+ read-write
+
+
+ DTEB
+ 18
+ 2
+ read-write
+
+
+ DT0
+ 20
+ 2
+ read-write
+
+
+ DT1
+ 22
+ 2
+ read-write
+
+
+
+
+ GEN1_B
+ 0x8C
+ 0x20
+
+
+ UTEZ
+ 0
+ 2
+ read-write
+
+
+ UTEP
+ 2
+ 2
+ read-write
+
+
+ UTEA
+ 4
+ 2
+ read-write
+
+
+ UTEB
+ 6
+ 2
+ read-write
+
+
+ UT0
+ 8
+ 2
+ read-write
+
+
+ UT1
+ 10
+ 2
+ read-write
+
+
+ DTEZ
+ 12
+ 2
+ read-write
+
+
+ DTEP
+ 14
+ 2
+ read-write
+
+
+ DTEA
+ 16
+ 2
+ read-write
+
+
+ DTEB
+ 18
+ 2
+ read-write
+
+
+ DT0
+ 20
+ 2
+ read-write
+
+
+ DT1
+ 22
+ 2
+ read-write
+
+
+
+
+ DT1_CFG
+ 0x90
+ 0x20
+ 0x00018000
+
+
+ DT1_FED_UPMETHOD
+ 0
+ 4
+ read-write
+
+
+ DT1_RED_UPMETHOD
+ 4
+ 4
+ read-write
+
+
+ DT1_DEB_MODE
+ 8
+ 1
+ read-write
+
+
+ DT1_A_OUTSWAP
+ 9
+ 1
+ read-write
+
+
+ DT1_B_OUTSWAP
+ 10
+ 1
+ read-write
+
+
+ DT1_RED_INSEL
+ 11
+ 1
+ read-write
+
+
+ DT1_FED_INSEL
+ 12
+ 1
+ read-write
+
+
+ DT1_RED_OUTINVERT
+ 13
+ 1
+ read-write
+
+
+ DT1_FED_OUTINVERT
+ 14
+ 1
+ read-write
+
+
+ DT1_A_OUTBYPASS
+ 15
+ 1
+ read-write
+
+
+ DT1_B_OUTBYPASS
+ 16
+ 1
+ read-write
+
+
+ DT1_CLK_SEL
+ 17
+ 1
+ read-write
+
+
+
+
+ DT1_FED_CFG
+ 0x94
+ 0x20
+
+
+ DT1_FED
+ 0
+ 16
+ read-write
+
+
+
+
+ DT1_RED_CFG
+ 0x98
+ 0x20
+
+
+ DT1_RED
+ 0
+ 16
+ read-write
+
+
+
+
+ CARRIER1_CFG
+ 0x9C
+ 0x20
+
+
+ CARRIER1_EN
+ 0
+ 1
+ read-write
+
+
+ CARRIER1_PRESCALE
+ 1
+ 4
+ read-write
+
+
+ CARRIER1_DUTY
+ 5
+ 3
+ read-write
+
+
+ CARRIER1_OSHTWTH
+ 8
+ 4
+ read-write
+
+
+ CARRIER1_OUT_INVERT
+ 12
+ 1
+ read-write
+
+
+ CARRIER1_IN_INVERT
+ 13
+ 1
+ read-write
+
+
+
+
+ FH1_CFG0
+ 0xA0
+ 0x20
+
+
+ FH1_SW_CBC
+ 0
+ 1
+ read-write
+
+
+ FH1_F2_CBC
+ 1
+ 1
+ read-write
+
+
+ FH1_F1_CBC
+ 2
+ 1
+ read-write
+
+
+ FH1_F0_CBC
+ 3
+ 1
+ read-write
+
+
+ FH1_SW_OST
+ 4
+ 1
+ read-write
+
+
+ FH1_F2_OST
+ 5
+ 1
+ read-write
+
+
+ FH1_F1_OST
+ 6
+ 1
+ read-write
+
+
+ FH1_F0_OST
+ 7
+ 1
+ read-write
+
+
+ FH1_A_CBC_D
+ 8
+ 2
+ read-write
+
+
+ FH1_A_CBC_U
+ 10
+ 2
+ read-write
+
+
+ FH1_A_OST_D
+ 12
+ 2
+ read-write
+
+
+ FH1_A_OST_U
+ 14
+ 2
+ read-write
+
+
+ FH1_B_CBC_D
+ 16
+ 2
+ read-write
+
+
+ FH1_B_CBC_U
+ 18
+ 2
+ read-write
+
+
+ FH1_B_OST_D
+ 20
+ 2
+ read-write
+
+
+ FH1_B_OST_U
+ 22
+ 2
+ read-write
+
+
+
+
+ FH1_CFG1
+ 0xA4
+ 0x20
+
+
+ FH1_CLR_OST
+ 0
+ 1
+ read-write
+
+
+ FH1_CBCPULSE
+ 1
+ 2
+ read-write
+
+
+ FH1_FORCE_CBC
+ 3
+ 1
+ read-write
+
+
+ FH1_FORCE_OST
+ 4
+ 1
+ read-write
+
+
+
+
+ FH1_STATUS
+ 0xA8
+ 0x20
+
+
+ FH1_CBC_ON
+ 0
+ 1
+ read-only
+
+
+ FH1_OST_ON
+ 1
+ 1
+ read-only
+
+
+
+
+ GEN2_STMP_CFG
+ 0xAC
+ 0x20
+
+
+ GEN2_A_UPMETHOD
+ 0
+ 4
+ read-write
+
+
+ GEN2_B_UPMETHOD
+ 4
+ 4
+ read-write
+
+
+ GEN2_A_SHDW_FULL
+ 8
+ 1
+ read-write
+
+
+ GEN2_B_SHDW_FULL
+ 9
+ 1
+ read-write
+
+
+
+
+ GEN2_TSTMP_A
+ 0xB0
+ 0x20
+
+
+ GEN2_A
+ 0
+ 16
+ read-write
+
+
+
+
+ GEN2_TSTMP_B
+ 0xB4
+ 0x20
+
+
+ GEN2_B
+ 0
+ 16
+ read-write
+
+
+
+
+ GEN2_CFG0
+ 0xB8
+ 0x20
+
+
+ GEN2_CFG_UPMETHOD
+ 0
+ 4
+ read-write
+
+
+ GEN2_T0_SEL
+ 4
+ 3
+ read-write
+
+
+ GEN2_T1_SEL
+ 7
+ 3
+ read-write
+
+
+
+
+ GEN2_FORCE
+ 0xBC
+ 0x20
+ 0x00000020
+
+
+ GEN2_CNTUFORCE_UPMETHOD
+ 0
+ 6
+ read-write
+
+
+ GEN2_A_CNTUFORCE_MODE
+ 6
+ 2
+ read-write
+
+
+ GEN2_B_CNTUFORCE_MODE
+ 8
+ 2
+ read-write
+
+
+ GEN2_A_NCIFORCE
+ 10
+ 1
+ read-write
+
+
+ GEN2_A_NCIFORCE_MODE
+ 11
+ 2
+ read-write
+
+
+ GEN2_B_NCIFORCE
+ 13
+ 1
+ read-write
+
+
+ GEN2_B_NCIFORCE_MODE
+ 14
+ 2
+ read-write
+
+
+
+
+ GEN2_A
+ 0xC0
+ 0x20
+
+
+ UTEZ
+ 0
+ 2
+ read-write
+
+
+ UTEP
+ 2
+ 2
+ read-write
+
+
+ UTEA
+ 4
+ 2
+ read-write
+
+
+ UTEB
+ 6
+ 2
+ read-write
+
+
+ UT0
+ 8
+ 2
+ read-write
+
+
+ UT1
+ 10
+ 2
+ read-write
+
+
+ DTEZ
+ 12
+ 2
+ read-write
+
+
+ DTEP
+ 14
+ 2
+ read-write
+
+
+ DTEA
+ 16
+ 2
+ read-write
+
+
+ DTEB
+ 18
+ 2
+ read-write
+
+
+ DT0
+ 20
+ 2
+ read-write
+
+
+ DT1
+ 22
+ 2
+ read-write
+
+
+
+
+ GEN2_B
+ 0xC4
+ 0x20
+
+
+ UTEZ
+ 0
+ 2
+ read-write
+
+
+ UTEP
+ 2
+ 2
+ read-write
+
+
+ UTEA
+ 4
+ 2
+ read-write
+
+
+ UTEB
+ 6
+ 2
+ read-write
+
+
+ UT0
+ 8
+ 2
+ read-write
+
+
+ UT1
+ 10
+ 2
+ read-write
+
+
+ DTEZ
+ 12
+ 2
+ read-write
+
+
+ DTEP
+ 14
+ 2
+ read-write
+
+
+ DTEA
+ 16
+ 2
+ read-write
+
+
+ DTEB
+ 18
+ 2
+ read-write
+
+
+ DT0
+ 20
+ 2
+ read-write
+
+
+ DT1
+ 22
+ 2
+ read-write
+
+
+
+
+ DT2_CFG
+ 0xC8
+ 0x20
+ 0x00018000
+
+
+ DT2_FED_UPMETHOD
+ 0
+ 4
+ read-write
+
+
+ DT2_RED_UPMETHOD
+ 4
+ 4
+ read-write
+
+
+ DT2_DEB_MODE
+ 8
+ 1
+ read-write
+
+
+ DT2_A_OUTSWAP
+ 9
+ 1
+ read-write
+
+
+ DT2_B_OUTSWAP
+ 10
+ 1
+ read-write
+
+
+ DT2_RED_INSEL
+ 11
+ 1
+ read-write
+
+
+ DT2_FED_INSEL
+ 12
+ 1
+ read-write
+
+
+ DT2_RED_OUTINVERT
+ 13
+ 1
+ read-write
+
+
+ DT2_FED_OUTINVERT
+ 14
+ 1
+ read-write
+
+
+ DT2_A_OUTBYPASS
+ 15
+ 1
+ read-write
+
+
+ DT2_B_OUTBYPASS
+ 16
+ 1
+ read-write
+
+
+ DT2_CLK_SEL
+ 17
+ 1
+ read-write
+
+
+
+
+ DT2_FED_CFG
+ 0xCC
+ 0x20
+
+
+ DT2_FED
+ 0
+ 16
+ read-write
+
+
+
+
+ DT2_RED_CFG
+ 0xD0
+ 0x20
+
+
+ DT2_RED
+ 0
+ 16
+ read-write
+
+
+
+
+ CARRIER2_CFG
+ 0xD4
+ 0x20
+
+
+ CARRIER2_EN
+ 0
+ 1
+ read-write
+
+
+ CARRIER2_PRESCALE
+ 1
+ 4
+ read-write
+
+
+ CARRIER2_DUTY
+ 5
+ 3
+ read-write
+
+
+ CARRIER2_OSHTWTH
+ 8
+ 4
+ read-write
+
+
+ CARRIER2_OUT_INVERT
+ 12
+ 1
+ read-write
+
+
+ CARRIER2_IN_INVERT
+ 13
+ 1
+ read-write
+
+
+
+
+ FH2_CFG0
+ 0xD8
+ 0x20
+
+
+ FH2_SW_CBC
+ 0
+ 1
+ read-write
+
+
+ FH2_F2_CBC
+ 1
+ 1
+ read-write
+
+
+ FH2_F1_CBC
+ 2
+ 1
+ read-write
+
+
+ FH2_F0_CBC
+ 3
+ 1
+ read-write
+
+
+ FH2_SW_OST
+ 4
+ 1
+ read-write
+
+
+ FH2_F2_OST
+ 5
+ 1
+ read-write
+
+
+ FH2_F1_OST
+ 6
+ 1
+ read-write
+
+
+ FH2_F0_OST
+ 7
+ 1
+ read-write
+
+
+ FH2_A_CBC_D
+ 8
+ 2
+ read-write
+
+
+ FH2_A_CBC_U
+ 10
+ 2
+ read-write
+
+
+ FH2_A_OST_D
+ 12
+ 2
+ read-write
+
+
+ FH2_A_OST_U
+ 14
+ 2
+ read-write
+
+
+ FH2_B_CBC_D
+ 16
+ 2
+ read-write
+
+
+ FH2_B_CBC_U
+ 18
+ 2
+ read-write
+
+
+ FH2_B_OST_D
+ 20
+ 2
+ read-write
+
+
+ FH2_B_OST_U
+ 22
+ 2
+ read-write
+
+
+
+
+ FH2_CFG1
+ 0xDC
+ 0x20
+
+
+ FH2_CLR_OST
+ 0
+ 1
+ read-write
+
+
+ FH2_CBCPULSE
+ 1
+ 2
+ read-write
+
+
+ FH2_FORCE_CBC
+ 3
+ 1
+ read-write
+
+
+ FH2_FORCE_OST
+ 4
+ 1
+ read-write
+
+
+
+
+ FH2_STATUS
+ 0xE0
+ 0x20
+
+
+ FH2_CBC_ON
+ 0
+ 1
+ read-only
+
+
+ FH2_OST_ON
+ 1
+ 1
+ read-only
+
+
+
+
+ FAULT_DETECT
+ 0xE4
+ 0x20
+
+
+ F0_EN
+ 0
+ 1
+ read-write
+
+
+ F1_EN
+ 1
+ 1
+ read-write
+
+
+ F2_EN
+ 2
+ 1
+ read-write
+
+
+ F0_POLE
+ 3
+ 1
+ read-write
+
+
+ F1_POLE
+ 4
+ 1
+ read-write
+
+
+ F2_POLE
+ 5
+ 1
+ read-write
+
+
+ EVENT_F0
+ 6
+ 1
+ read-only
+
+
+ EVENT_F1
+ 7
+ 1
+ read-only
+
+
+ EVENT_F2
+ 8
+ 1
+ read-only
+
+
+
+
+ CAP_TIMER_CFG
+ 0xE8
+ 0x20
+
+
+ CAP_TIMER_EN
+ 0
+ 1
+ read-write
+
+
+ CAP_SYNCI_EN
+ 1
+ 1
+ read-write
+
+
+ CAP_SYNCI_SEL
+ 2
+ 3
+ read-write
+
+
+ CAP_SYNC_SW
+ 5
+ 1
+ write-only
+
+
+
+
+ CAP_TIMER_PHASE
+ 0xEC
+ 0x20
+
+
+ CAP_TIMER_PHASE
+ 0
+ 32
+ read-write
+
+
+
+
+ CAP_CH0_CFG
+ 0xF0
+ 0x20
+
+
+ CAP0_EN
+ 0
+ 1
+ read-write
+
+
+ CAP0_MODE
+ 1
+ 2
+ read-write
+
+
+ CAP0_PRESCALE
+ 3
+ 8
+ read-write
+
+
+ CAP0_IN_INVERT
+ 11
+ 1
+ read-write
+
+
+ CAP0_SW
+ 12
+ 1
+ write-only
+
+
+
+
+ CAP_CH1_CFG
+ 0xF4
+ 0x20
+
+
+ CAP1_EN
+ 0
+ 1
+ read-write
+
+
+ CAP1_MODE
+ 1
+ 2
+ read-write
+
+
+ CAP1_PRESCALE
+ 3
+ 8
+ read-write
+
+
+ CAP1_IN_INVERT
+ 11
+ 1
+ read-write
+
+
+ CAP1_SW
+ 12
+ 1
+ write-only
+
+
+
+
+ CAP_CH2_CFG
+ 0xF8
+ 0x20
+
+
+ CAP2_EN
+ 0
+ 1
+ read-write
+
+
+ CAP2_MODE
+ 1
+ 2
+ read-write
+
+
+ CAP2_PRESCALE
+ 3
+ 8
+ read-write
+
+
+ CAP2_IN_INVERT
+ 11
+ 1
+ read-write
+
+
+ CAP2_SW
+ 12
+ 1
+ write-only
+
+
+
+
+ CAP_CH0
+ 0xFC
+ 0x20
+
+
+ CAP0_VALUE
+ 0
+ 32
+ read-only
+
+
+
+
+ CAP_CH1
+ 0x100
+ 0x20
+
+
+ CAP1_VALUE
+ 0
+ 32
+ read-only
+
+
+
+
+ CAP_CH2
+ 0x104
+ 0x20
+
+
+ CAP2_VALUE
+ 0
+ 32
+ read-only
+
+
+
+
+ CAP_STATUS
+ 0x108
+ 0x20
+
+
+ CAP0_EDGE
+ 0
+ 1
+ read-only
+
+
+ CAP1_EDGE
+ 1
+ 1
+ read-only
+
+
+ CAP2_EDGE
+ 2
+ 1
+ read-only
+
+
+
+
+ UPDATE_CFG
+ 0x10C
+ 0x20
+ 0x00000055
+
+
+ GLOBAL_UP_EN
+ 0
+ 1
+ read-write
+
+
+ GLOBAL_FORCE_UP
+ 1
+ 1
+ read-write
+
+
+ OP0_UP_EN
+ 2
+ 1
+ read-write
+
+
+ OP0_FORCE_UP
+ 3
+ 1
+ read-write
+
+
+ OP1_UP_EN
+ 4
+ 1
+ read-write
+
+
+ OP1_FORCE_UP
+ 5
+ 1
+ read-write
+
+
+ OP2_UP_EN
+ 6
+ 1
+ read-write
+
+
+ OP2_FORCE_UP
+ 7
+ 1
+ read-write
+
+
+
+
+ INT_ENA
+ 0x110
+ 0x20
+
+
+ TIMER0_STOP_INT_ENA
+ 0
+ 1
+ read-write
+
+
+ TIMER1_STOP_INT_ENA
+ 1
+ 1
+ read-write
+
+
+ TIMER2_STOP_INT_ENA
+ 2
+ 1
+ read-write
+
+
+ TIMER0_TEZ_INT_ENA
+ 3
+ 1
+ read-write
+
+
+ TIMER1_TEZ_INT_ENA
+ 4
+ 1
+ read-write
+
+
+ TIMER2_TEZ_INT_ENA
+ 5
+ 1
+ read-write
+
+
+ TIMER0_TEP_INT_ENA
+ 6
+ 1
+ read-write
+
+
+ TIMER1_TEP_INT_ENA
+ 7
+ 1
+ read-write
+
+
+ TIMER2_TEP_INT_ENA
+ 8
+ 1
+ read-write
+
+
+ FAULT0_INT_ENA
+ 9
+ 1
+ read-write
+
+
+ FAULT1_INT_ENA
+ 10
+ 1
+ read-write
+
+
+ FAULT2_INT_ENA
+ 11
+ 1
+ read-write
+
+
+ FAULT0_CLR_INT_ENA
+ 12
+ 1
+ read-write
+
+
+ FAULT1_CLR_INT_ENA
+ 13
+ 1
+ read-write
+
+
+ FAULT2_CLR_INT_ENA
+ 14
+ 1
+ read-write
+
+
+ OP0_TEA_INT_ENA
+ 15
+ 1
+ read-write
+
+
+ OP1_TEA_INT_ENA
+ 16
+ 1
+ read-write
+
+
+ OP2_TEA_INT_ENA
+ 17
+ 1
+ read-write
+
+
+ OP0_TEB_INT_ENA
+ 18
+ 1
+ read-write
+
+
+ OP1_TEB_INT_ENA
+ 19
+ 1
+ read-write
+
+
+ OP2_TEB_INT_ENA
+ 20
+ 1
+ read-write
+
+
+ FH0_CBC_INT_ENA
+ 21
+ 1
+ read-write
+
+
+ FH1_CBC_INT_ENA
+ 22
+ 1
+ read-write
+
+
+ FH2_CBC_INT_ENA
+ 23
+ 1
+ read-write
+
+
+ FH0_OST_INT_ENA
+ 24
+ 1
+ read-write
+
+
+ FH1_OST_INT_ENA
+ 25
+ 1
+ read-write
+
+
+ FH2_OST_INT_ENA
+ 26
+ 1
+ read-write
+
+
+ CAP0_INT_ENA
+ 27
+ 1
+ read-write
+
+
+ CAP1_INT_ENA
+ 28
+ 1
+ read-write
+
+
+ CAP2_INT_ENA
+ 29
+ 1
+ read-write
+
+
+
+
+ INT_RAW
+ 0x114
+ 0x20
+
+
+ TIMER0_STOP_INT_RAW
+ 0
+ 1
+ read-only
+
+
+ TIMER1_STOP_INT_RAW
+ 1
+ 1
+ read-only
+
+
+ TIMER2_STOP_INT_RAW
+ 2
+ 1
+ read-only
+
+
+ TIMER0_TEZ_INT_RAW
+ 3
+ 1
+ read-only
+
+
+ TIMER1_TEZ_INT_RAW
+ 4
+ 1
+ read-only
+
+
+ TIMER2_TEZ_INT_RAW
+ 5
+ 1
+ read-only
+
+
+ TIMER0_TEP_INT_RAW
+ 6
+ 1
+ read-only
+
+
+ TIMER1_TEP_INT_RAW
+ 7
+ 1
+ read-only
+
+
+ TIMER2_TEP_INT_RAW
+ 8
+ 1
+ read-only
+
+
+ FAULT0_INT_RAW
+ 9
+ 1
+ read-only
+
+
+ FAULT1_INT_RAW
+ 10
+ 1
+ read-only
+
+
+ FAULT2_INT_RAW
+ 11
+ 1
+ read-only
+
+
+ FAULT0_CLR_INT_RAW
+ 12
+ 1
+ read-only
+
+
+ FAULT1_CLR_INT_RAW
+ 13
+ 1
+ read-only
+
+
+ FAULT2_CLR_INT_RAW
+ 14
+ 1
+ read-only
+
+
+ OP0_TEA_INT_RAW
+ 15
+ 1
+ read-only
+
+
+ OP1_TEA_INT_RAW
+ 16
+ 1
+ read-only
+
+
+ OP2_TEA_INT_RAW
+ 17
+ 1
+ read-only
+
+
+ OP0_TEB_INT_RAW
+ 18
+ 1
+ read-only
+
+
+ OP1_TEB_INT_RAW
+ 19
+ 1
+ read-only
+
+
+ OP2_TEB_INT_RAW
+ 20
+ 1
+ read-only
+
+
+ FH0_CBC_INT_RAW
+ 21
+ 1
+ read-only
+
+
+ FH1_CBC_INT_RAW
+ 22
+ 1
+ read-only
+
+
+ FH2_CBC_INT_RAW
+ 23
+ 1
+ read-only
+
+
+ FH0_OST_INT_RAW
+ 24
+ 1
+ read-only
+
+
+ FH1_OST_INT_RAW
+ 25
+ 1
+ read-only
+
+
+ FH2_OST_INT_RAW
+ 26
+ 1
+ read-only
+
+
+ CAP0_INT_RAW
+ 27
+ 1
+ read-only
+
+
+ CAP1_INT_RAW
+ 28
+ 1
+ read-only
+
+
+ CAP2_INT_RAW
+ 29
+ 1
+ read-only
+
+
+
+
+ INT_ST
+ 0x118
+ 0x20
+
+
+ TIMER0_STOP_INT_ST
+ 0
+ 1
+ read-only
+
+
+ TIMER1_STOP_INT_ST
+ 1
+ 1
+ read-only
+
+
+ TIMER2_STOP_INT_ST
+ 2
+ 1
+ read-only
+
+
+ TIMER0_TEZ_INT_ST
+ 3
+ 1
+ read-only
+
+
+ TIMER1_TEZ_INT_ST
+ 4
+ 1
+ read-only
+
+
+ TIMER2_TEZ_INT_ST
+ 5
+ 1
+ read-only
+
+
+ TIMER0_TEP_INT_ST
+ 6
+ 1
+ read-only
+
+
+ TIMER1_TEP_INT_ST
+ 7
+ 1
+ read-only
+
+
+ TIMER2_TEP_INT_ST
+ 8
+ 1
+ read-only
+
+
+ FAULT0_INT_ST
+ 9
+ 1
+ read-only
+
+
+ FAULT1_INT_ST
+ 10
+ 1
+ read-only
+
+
+ FAULT2_INT_ST
+ 11
+ 1
+ read-only
+
+
+ FAULT0_CLR_INT_ST
+ 12
+ 1
+ read-only
+
+
+ FAULT1_CLR_INT_ST
+ 13
+ 1
+ read-only
+
+
+ FAULT2_CLR_INT_ST
+ 14
+ 1
+ read-only
+
+
+ OP0_TEA_INT_ST
+ 15
+ 1
+ read-only
+
+
+ OP1_TEA_INT_ST
+ 16
+ 1
+ read-only
+
+
+ OP2_TEA_INT_ST
+ 17
+ 1
+ read-only
+
+
+ OP0_TEB_INT_ST
+ 18
+ 1
+ read-only
+
+
+ OP1_TEB_INT_ST
+ 19
+ 1
+ read-only
+
+
+ OP2_TEB_INT_ST
+ 20
+ 1
+ read-only
+
+
+ FH0_CBC_INT_ST
+ 21
+ 1
+ read-only
+
+
+ FH1_CBC_INT_ST
+ 22
+ 1
+ read-only
+
+
+ FH2_CBC_INT_ST
+ 23
+ 1
+ read-only
+
+
+ FH0_OST_INT_ST
+ 24
+ 1
+ read-only
+
+
+ FH1_OST_INT_ST
+ 25
+ 1
+ read-only
+
+
+ FH2_OST_INT_ST
+ 26
+ 1
+ read-only
+
+
+ CAP0_INT_ST
+ 27
+ 1
+ read-only
+
+
+ CAP1_INT_ST
+ 28
+ 1
+ read-only
+
+
+ CAP2_INT_ST
+ 29
+ 1
+ read-only
+
+
+
+
+ INT_CLR
+ 0x11C
+ 0x20
+
+
+ TIMER0_STOP_INT_CLR
+ 0
+ 1
+ write-only
+
+
+ TIMER1_STOP_INT_CLR
+ 1
+ 1
+ write-only
+
+
+ TIMER2_STOP_INT_CLR
+ 2
+ 1
+ write-only
+
+
+ TIMER0_TEZ_INT_CLR
+ 3
+ 1
+ write-only
+
+
+ TIMER1_TEZ_INT_CLR
+ 4
+ 1
+ write-only
+
+
+ TIMER2_TEZ_INT_CLR
+ 5
+ 1
+ write-only
+
+
+ TIMER0_TEP_INT_CLR
+ 6
+ 1
+ write-only
+
+
+ TIMER1_TEP_INT_CLR
+ 7
+ 1
+ write-only
+
+
+ TIMER2_TEP_INT_CLR
+ 8
+ 1
+ write-only
+
+
+ FAULT0_INT_CLR
+ 9
+ 1
+ write-only
+
+
+ FAULT1_INT_CLR
+ 10
+ 1
+ write-only
+
+
+ FAULT2_INT_CLR
+ 11
+ 1
+ write-only
+
+
+ FAULT0_CLR_INT_CLR
+ 12
+ 1
+ write-only
+
+
+ FAULT1_CLR_INT_CLR
+ 13
+ 1
+ write-only
+
+
+ FAULT2_CLR_INT_CLR
+ 14
+ 1
+ write-only
+
+
+ OP0_TEA_INT_CLR
+ 15
+ 1
+ write-only
+
+
+ OP1_TEA_INT_CLR
+ 16
+ 1
+ write-only
+
+
+ OP2_TEA_INT_CLR
+ 17
+ 1
+ write-only
+
+
+ OP0_TEB_INT_CLR
+ 18
+ 1
+ write-only
+
+
+ OP1_TEB_INT_CLR
+ 19
+ 1
+ write-only
+
+
+ OP2_TEB_INT_CLR
+ 20
+ 1
+ write-only
+
+
+ FH0_CBC_INT_CLR
+ 21
+ 1
+ write-only
+
+
+ FH1_CBC_INT_CLR
+ 22
+ 1
+ write-only
+
+
+ FH2_CBC_INT_CLR
+ 23
+ 1
+ write-only
+
+
+ FH0_OST_INT_CLR
+ 24
+ 1
+ write-only
+
+
+ FH1_OST_INT_CLR
+ 25
+ 1
+ write-only
+
+
+ FH2_OST_INT_CLR
+ 26
+ 1
+ write-only
+
+
+ CAP0_INT_CLR
+ 27
+ 1
+ write-only
+
+
+ CAP1_INT_CLR
+ 28
+ 1
+ write-only
+
+
+ CAP2_INT_CLR
+ 29
+ 1
+ write-only
+
+
+
+
+ CLK
+ 0x120
+ 0x20
+
+
+ EN
+ 0
+ 1
+ read-write
+
+
+
+
+ VERSION
+ 0x124
+ 0x20
+ 0x02107230
+
+
+ DATE
+ 0
+ 28
+ read-write
+
+
+
+
+
+
+ PWM1
+ Motor Control Pulse-Width Modulation
+ 0x3FF6C000
+
+ PWM1
+ 40
+
+
+
+ NRX
+ Peripheral NRX
+ NRX
+ 0x3FF5CC00
+
+ 0x0
+ 0x4
+ registers
+
+
+
+ NRXPD_CTRL
+ WiFi RX control register
+ 0xD4
+ 0x20
+
+
+ DEMAP_FORCE_PD
+ 0
+ 1
+ read-write
+
+
+ DEMAP_FORCE_PU
+ 1
+ 1
+ read-write
+
+
+ VIT_FORCE_PD
+ 2
+ 1
+ read-write
+
+
+ VIT_FORCE_PU
+ 3
+ 1
+ read-write
+
+
+ RX_ROT_FORCE_PD
+ 4
+ 1
+ read-write
+
+
+ RX_ROT_FORCE_PU
+ 5
+ 1
+ read-write
+
+
+ CHAN_EST_FORCE_PD
+ 6
+ 1
+ read-write
+
+
+ CHAN_EST_FORCE_PU
+ 7
+ 1
+ read-write
+
+
+
+
+
+
+ PCNT
+ Pulse Count Controller
+ PCNT
+ 0x3FF57000
+
+ 0x0
+ 0xB8
+ registers
+
+
+ PCNT
+ 48
+
+
+
+ U0_CONF0
+ 0x0
+ 0x20
+ 0x00003C10
+
+
+ FILTER_THRES_U0
+ This register is used to filter pluse whose width is smaller than this value for unit0.
+ 0
+ 10
+ read-write
+
+
+ FILTER_EN_U0
+ This is the enable bit for filtering input signals for unit0.
+ 10
+ 1
+ read-write
+
+
+ THR_ZERO_EN_U0
+ This is the enable bit for comparing unit0's count with 0 value.
+ 11
+ 1
+ read-write
+
+
+ THR_H_LIM_EN_U0
+ This is the enable bit for comparing unit0's count with thr_h_lim value.
+ 12
+ 1
+ read-write
+
+
+ THR_L_LIM_EN_U0
+ This is the enable bit for comparing unit0's count with thr_l_lim value.
+ 13
+ 1
+ read-write
+
+
+ THR_THRES0_EN_U0
+ This is the enable bit for comparing unit0's count with thres0 value.
+ 14
+ 1
+ read-write
+
+
+ THR_THRES1_EN_U0
+ This is the enable bit for comparing unit0's count with thres1 value .
+ 15
+ 1
+ read-write
+
+
+ CH0_NEG_MODE_U0
+ This register is used to control the mode of channel0's input negedge signal for unit0. 2'd1: increase at the negedge of input signal 2'd2:decrease at the negedge of input signal others:forbidden
+ 16
+ 2
+ read-write
+
+
+ CH0_POS_MODE_U0
+ This register is used to control the mode of channel0's input posedge signal for unit0. 2'd1: increase at the posedge of input signal 2'd2:decrease at the posedge of input signal others:forbidden
+ 18
+ 2
+ read-write
+
+
+ CH0_HCTRL_MODE_U0
+ This register is used to control the mode of channel0's high control signal for unit0. 2'd0:increase when control signal is low 2'd1: decrease when control signal is high others:forbidden
+ 20
+ 2
+ read-write
+
+
+ CH0_LCTRL_MODE_U0
+ This register is used to control the mode of channel0's low control signal for unit0. 2'd0:increase when control signal is low 2'd1: decrease when control signal is high others:forbidden
+ 22
+ 2
+ read-write
+
+
+ CH1_NEG_MODE_U0
+ This register is used to control the mode of channel1's input negedge signal for unit0. 2'd1: increase at the negedge of input signal 2'd2:decrease at the negedge of input signal others:forbidden
+ 24
+ 2
+ read-write
+
+
+ CH1_POS_MODE_U0
+ This register is used to control the mode of channel1's input posedge signal for unit0. 2'd1: increase at the posedge of input signal 2'd2:decrease at the posedge of input signal others:forbidden
+ 26
+ 2
+ read-write
+
+
+ CH1_HCTRL_MODE_U0
+ This register is used to control the mode of channel1's high control signal for unit0. 2'd0:increase when control signal is low 2'd1: decrease when control signal is high others:forbidden
+ 28
+ 2
+ read-write
+
+
+ CH1_LCTRL_MODE_U0
+ This register is used to control the mode of channel1's low control signal for unit0. 2'd0:increase when control signal is low 2'd1: decrease when control signal is high others:forbidden
+ 30
+ 2
+ read-write
+
+
+
+
+ U0_CONF1
+ 0x4
+ 0x20
+
+
+ CNT_THRES0_U0
+ This register is used to configure thres0 value for unit0.
+ 0
+ 16
+ read-write
+
+
+ CNT_THRES1_U0
+ This register is used to configure thres1 value for unit0.
+ 16
+ 16
+ read-write
+
+
+
+
+ U0_CONF2
+ 0x8
+ 0x20
+
+
+ CNT_H_LIM_U0
+ This register is used to configure thr_h_lim value for unit0.
+ 0
+ 16
+ read-write
+
+
+ CNT_L_LIM_U0
+ This register is used to confiugre thr_l_lim value for unit0.
+ 16
+ 16
+ read-write
+
+
+
+
+ U1_CONF0
+ 0xC
+ 0x20
+ 0x00003C10
+
+
+ FILTER_THRES_U1
+ This register is used to filter pluse whose width is smaller than this value for unit1.
+ 0
+ 10
+ read-write
+
+
+ FILTER_EN_U1
+ This is the enable bit for filtering input signals for unit1.
+ 10
+ 1
+ read-write
+
+
+ THR_ZERO_EN_U1
+ This is the enable bit for comparing unit1's count with 0 value.
+ 11
+ 1
+ read-write
+
+
+ THR_H_LIM_EN_U1
+ This is the enable bit for comparing unit1's count with thr_h_lim value.
+ 12
+ 1
+ read-write
+
+
+ THR_L_LIM_EN_U1
+ This is the enable bit for comparing unit1's count with thr_l_lim value.
+ 13
+ 1
+ read-write
+
+
+ THR_THRES0_EN_U1
+ This is the enable bit for comparing unit1's count with thres0 value.
+ 14
+ 1
+ read-write
+
+
+ THR_THRES1_EN_U1
+ This is the enable bit for comparing unit1's count with thres1 value .
+ 15
+ 1
+ read-write
+
+
+ CH0_NEG_MODE_U1
+ This register is used to control the mode of channel0's input negedge signal for unit1. 2'd1: increase at the negedge of input signal 2'd2:decrease at the negedge of input signal others:forbidden
+ 16
+ 2
+ read-write
+
+
+ CH0_POS_MODE_U1
+ This register is used to control the mode of channel0's input posedge signal for unit1. 2'd1: increase at the posedge of input signal 2'd2:decrease at the posedge of input signal others:forbidden
+ 18
+ 2
+ read-write
+
+
+ CH0_HCTRL_MODE_U1
+ This register is used to control the mode of channel0's high control signal for unit1. 2'd0:increase when control signal is low 2'd1: decrease when control signal is high others:forbidden
+ 20
+ 2
+ read-write
+
+
+ CH0_LCTRL_MODE_U1
+ This register is used to control the mode of channel0's low control signal for unit1. 2'd0:increase when control signal is low 2'd1: decrease when control signal is high others:forbidden
+ 22
+ 2
+ read-write
+
+
+ CH1_NEG_MODE_U1
+ This register is used to control the mode of channel1's input negedge signal for unit1. 2'd1: increase at the negedge of input signal 2'd2:decrease at the negedge of input signal others:forbidden
+ 24
+ 2
+ read-write
+
+
+ CH1_POS_MODE_U1
+ This register is used to control the mode of channel1's input posedge signal for unit1. 2'd1: increase at the posedge of input signal 2'd2:decrease at the posedge of input signal others:forbidden
+ 26
+ 2
+ read-write
+
+
+ CH1_HCTRL_MODE_U1
+ This register is used to control the mode of channel1's high control signal for unit1. 2'd0:increase when control signal is low 2'd1: decrease when control signal is high others:forbidden
+ 28
+ 2
+ read-write
+
+
+ CH1_LCTRL_MODE_U1
+ This register is used to control the mode of channel1's low control signal for unit1. 2'd0:increase when control signal is low 2'd1: decrease when control signal is high others:forbidden
+ 30
+ 2
+ read-write
+
+
+
+
+ U1_CONF1
+ 0x10
+ 0x20
+
+
+ CNT_THRES0_U1
+ This register is used to configure thres0 value for unit1.
+ 0
+ 16
+ read-write
+
+
+ CNT_THRES1_U1
+ This register is used to configure thres1 value for unit1.
+ 16
+ 16
+ read-write
+
+
+
+
+ U1_CONF2
+ 0x14
+ 0x20
+
+
+ CNT_H_LIM_U1
+ This register is used to configure thr_h_lim value for unit1.
+ 0
+ 16
+ read-write
+
+
+ CNT_L_LIM_U1
+ This register is used to confiugre thr_l_lim value for unit1.
+ 16
+ 16
+ read-write
+
+
+
+
+ U2_CONF0
+ 0x18
+ 0x20
+ 0x00003C10
+
+
+ FILTER_THRES_U2
+ This register is used to filter pluse whose width is smaller than this value for unit2.
+ 0
+ 10
+ read-write
+
+
+ FILTER_EN_U2
+ This is the enable bit for filtering input signals for unit2.
+ 10
+ 1
+ read-write
+
+
+ THR_ZERO_EN_U2
+ This is the enable bit for comparing unit2's count with 0 value.
+ 11
+ 1
+ read-write
+
+
+ THR_H_LIM_EN_U2
+ This is the enable bit for comparing unit2's count with thr_h_lim value.
+ 12
+ 1
+ read-write
+
+
+ THR_L_LIM_EN_U2
+ This is the enable bit for comparing unit2's count with thr_l_lim value.
+ 13
+ 1
+ read-write
+
+
+ THR_THRES0_EN_U2
+ This is the enable bit for comparing unit2's count with thres0 value.
+ 14
+ 1
+ read-write
+
+
+ THR_THRES1_EN_U2
+ This is the enable bit for comparing unit2's count with thres1 value .
+ 15
+ 1
+ read-write
+
+
+ CH0_NEG_MODE_U2
+ This register is used to control the mode of channel0's input negedge signal for unit2. 2'd1: increase at the negedge of input signal 2'd2:decrease at the negedge of input signal others:forbidden
+ 16
+ 2
+ read-write
+
+
+ CH0_POS_MODE_U2
+ This register is used to control the mode of channel0's input posedge signal for unit2. 2'd1: increase at the posedge of input signal 2'd2:decrease at the posedge of input signal others:forbidden
+ 18
+ 2
+ read-write
+
+
+ CH0_HCTRL_MODE_U2
+ This register is used to control the mode of channel0's high control signal for unit2. 2'd0:increase when control signal is low 2'd1: decrease when control signal is high others:forbidden
+ 20
+ 2
+ read-write
+
+
+ CH0_LCTRL_MODE_U2
+ This register is used to control the mode of channel0's low control signal for unit2. 2'd0:increase when control signal is low 2'd1: decrease when control signal is high others:forbidden
+ 22
+ 2
+ read-write
+
+
+ CH1_NEG_MODE_U2
+ This register is used to control the mode of channel1's input negedge signal for unit2. 2'd1: increase at the negedge of input signal 2'd2:decrease at the negedge of input signal others:forbidden
+ 24
+ 2
+ read-write
+
+
+ CH1_POS_MODE_U2
+ This register is used to control the mode of channel1's input posedge signal for unit2. 2'd1: increase at the posedge of input signal 2'd2:decrease at the posedge of input signal others:forbidden
+ 26
+ 2
+ read-write
+
+
+ CH1_HCTRL_MODE_U2
+ This register is used to control the mode of channel1's high control signal for unit2. 2'd0:increase when control signal is low 2'd1: decrease when control signal is high others:forbidden
+ 28
+ 2
+ read-write
+
+
+ CH1_LCTRL_MODE_U2
+ This register is used to control the mode of channel1's low control signal for unit2. 2'd0:increase when control signal is low 2'd1: decrease when control signal is high others:forbidden
+ 30
+ 2
+ read-write
+
+
+
+
+ U2_CONF1
+ 0x1C
+ 0x20
+
+
+ CNT_THRES0_U2
+ This register is used to configure thres0 value for unit2.
+ 0
+ 16
+ read-write
+
+
+ CNT_THRES1_U2
+ This register is used to configure thres1 value for unit2.
+ 16
+ 16
+ read-write
+
+
+
+
+ U2_CONF2
+ 0x20
+ 0x20
+
+
+ CNT_H_LIM_U2
+ This register is used to configure thr_h_lim value for unit2.
+ 0
+ 16
+ read-write
+
+
+ CNT_L_LIM_U2
+ This register is used to confiugre thr_l_lim value for unit2.
+ 16
+ 16
+ read-write
+
+
+
+
+ U3_CONF0
+ 0x24
+ 0x20
+ 0x00003C10
+
+
+ FILTER_THRES_U3
+ This register is used to filter pluse whose width is smaller than this value for unit3.
+ 0
+ 10
+ read-write
+
+
+ FILTER_EN_U3
+ This is the enable bit for filtering input signals for unit3.
+ 10
+ 1
+ read-write
+
+
+ THR_ZERO_EN_U3
+ This is the enable bit for comparing unit3's count with 0 value.
+ 11
+ 1
+ read-write
+
+
+ THR_H_LIM_EN_U3
+ This is the enable bit for comparing unit3's count with thr_h_lim value.
+ 12
+ 1
+ read-write
+
+
+ THR_L_LIM_EN_U3
+ This is the enable bit for comparing unit3's count with thr_l_lim value.
+ 13
+ 1
+ read-write
+
+
+ THR_THRES0_EN_U3
+ This is the enable bit for comparing unit3's count with thres0 value.
+ 14
+ 1
+ read-write
+
+
+ THR_THRES1_EN_U3
+ This is the enable bit for comparing unit3's count with thres1 value .
+ 15
+ 1
+ read-write
+
+
+ CH0_NEG_MODE_U3
+ This register is used to control the mode of channel0's input negedge signal for unit3. 2'd1: increase at the negedge of input signal 2'd2:decrease at the negedge of input signal others:forbidden
+ 16
+ 2
+ read-write
+
+
+ CH0_POS_MODE_U3
+ This register is used to control the mode of channel0's input posedge signal for unit3. 2'd1: increase at the posedge of input signal 2'd2:decrease at the posedge of input signal others:forbidden
+ 18
+ 2
+ read-write
+
+
+ CH0_HCTRL_MODE_U3
+ This register is used to control the mode of channel0's high control signal for unit3. 2'd0:increase when control signal is low 2'd1: decrease when control signal is high others:forbidden
+ 20
+ 2
+ read-write
+
+
+ CH0_LCTRL_MODE_U3
+ This register is used to control the mode of channel0's low control signal for unit3. 2'd0:increase when control signal is low 2'd1: decrease when control signal is high others:forbidden
+ 22
+ 2
+ read-write
+
+
+ CH1_NEG_MODE_U3
+ This register is used to control the mode of channel1's input negedge signal for unit3. 2'd1: increase at the negedge of input signal 2'd2:decrease at the negedge of input signal others:forbidden
+ 24
+ 2
+ read-write
+
+
+ CH1_POS_MODE_U3
+ This register is used to control the mode of channel1's input posedge signal for unit3. 2'd1: increase at the posedge of input signal 2'd2:decrease at the posedge of input signal others:forbidden
+ 26
+ 2
+ read-write
+
+
+ CH1_HCTRL_MODE_U3
+ This register is used to control the mode of channel1's high control signal for unit3. 2'd0:increase when control signal is low 2'd1: decrease when control signal is high others:forbidden
+ 28
+ 2
+ read-write
+
+
+ CH1_LCTRL_MODE_U3
+ This register is used to control the mode of channel1's low control signal for unit3. 2'd0:increase when control signal is low 2'd1: decrease when control signal is high others:forbidden
+ 30
+ 2
+ read-write
+
+
+
+
+ U3_CONF1
+ 0x28
+ 0x20
+
+
+ CNT_THRES0_U3
+ This register is used to configure thres0 value for unit3.
+ 0
+ 16
+ read-write
+
+
+ CNT_THRES1_U3
+ This register is used to configure thres1 value for unit3.
+ 16
+ 16
+ read-write
+
+
+
+
+ U3_CONF2
+ 0x2C
+ 0x20
+
+
+ CNT_H_LIM_U3
+ This register is used to configure thr_h_lim value for unit3.
+ 0
+ 16
+ read-write
+
+
+ CNT_L_LIM_U3
+ This register is used to confiugre thr_l_lim value for unit3.
+ 16
+ 16
+ read-write
+
+
+
+
+ U4_CONF0
+ 0x30
+ 0x20
+ 0x00003C10
+
+
+ FILTER_THRES_U4
+ This register is used to filter pluse whose width is smaller than this value for unit4.
+ 0
+ 10
+ read-write
+
+
+ FILTER_EN_U4
+ This is the enable bit for filtering input signals for unit4.
+ 10
+ 1
+ read-write
+
+
+ THR_ZERO_EN_U4
+ This is the enable bit for comparing unit4's count with 0 value.
+ 11
+ 1
+ read-write
+
+
+ THR_H_LIM_EN_U4
+ This is the enable bit for comparing unit4's count with thr_h_lim value.
+ 12
+ 1
+ read-write
+
+
+ THR_L_LIM_EN_U4
+ This is the enable bit for comparing unit4's count with thr_l_lim value.
+ 13
+ 1
+ read-write
+
+
+ THR_THRES0_EN_U4
+ This is the enable bit for comparing unit4's count with thres0 value.
+ 14
+ 1
+ read-write
+
+
+ THR_THRES1_EN_U4
+ This is the enable bit for comparing unit4's count with thres1 value .
+ 15
+ 1
+ read-write
+
+
+ CH0_NEG_MODE_U4
+ This register is used to control the mode of channel0's input negedge signal for unit4. 2'd1: increase at the negedge of input signal 2'd2:decrease at the negedge of input signal others:forbidden
+ 16
+ 2
+ read-write
+
+
+ CH0_POS_MODE_U4
+ This register is used to control the mode of channel0's input posedge signal for unit4. 2'd1: increase at the posedge of input signal 2'd2:decrease at the posedge of input signal others:forbidden
+ 18
+ 2
+ read-write
+
+
+ CH0_HCTRL_MODE_U4
+ This register is used to control the mode of channel0's high control signal for unit4. 2'd0:increase when control signal is low 2'd1: decrease when control signal is high others:forbidden
+ 20
+ 2
+ read-write
+
+
+ CH0_LCTRL_MODE_U4
+ This register is used to control the mode of channel0's low control signal for unit4. 2'd0:increase when control signal is low 2'd1: decrease when control signal is high others:forbidden
+ 22
+ 2
+ read-write
+
+
+ CH1_NEG_MODE_U4
+ This register is used to control the mode of channel1's input negedge signal for unit4. 2'd1: increase at the negedge of input signal 2'd2:decrease at the negedge of input signal others:forbidden
+ 24
+ 2
+ read-write
+
+
+ CH1_POS_MODE_U4
+ This register is used to control the mode of channel1's input posedge signal for unit4. 2'd1: increase at the posedge of input signal 2'd2:decrease at the posedge of input signal others:forbidden
+ 26
+ 2
+ read-write
+
+
+ CH1_HCTRL_MODE_U4
+ This register is used to control the mode of channel1's high control signal for unit4. 2'd0:increase when control signal is low 2'd1: decrease when control signal is high others:forbidden
+ 28
+ 2
+ read-write
+
+
+ CH1_LCTRL_MODE_U4
+ This register is used to control the mode of channel1's low control signal for unit4. 2'd0:increase when control signal is low 2'd1: decrease when control signal is high others:forbidden
+ 30
+ 2
+ read-write
+
+
+
+
+ U4_CONF1
+ 0x34
+ 0x20
+
+
+ CNT_THRES0_U4
+ This register is used to configure thres0 value for unit4.
+ 0
+ 16
+ read-write
+
+
+ CNT_THRES1_U4
+ This register is used to configure thres1 value for unit4.
+ 16
+ 16
+ read-write
+
+
+
+
+ U4_CONF2
+ 0x38
+ 0x20
+
+
+ CNT_H_LIM_U4
+ This register is used to configure thr_h_lim value for unit4.
+ 0
+ 16
+ read-write
+
+
+ CNT_L_LIM_U4
+ This register is used to confiugre thr_l_lim value for unit4.
+ 16
+ 16
+ read-write
+
+
+
+
+ U5_CONF0
+ 0x3C
+ 0x20
+ 0x00003C10
+
+
+ FILTER_THRES_U5
+ This register is used to filter pluse whose width is smaller than this value for unit5.
+ 0
+ 10
+ read-write
+
+
+ FILTER_EN_U5
+ This is the enable bit for filtering input signals for unit5.
+ 10
+ 1
+ read-write
+
+
+ THR_ZERO_EN_U5
+ This is the enable bit for comparing unit5's count with 0 value.
+ 11
+ 1
+ read-write
+
+
+ THR_H_LIM_EN_U5
+ This is the enable bit for comparing unit5's count with thr_h_lim value.
+ 12
+ 1
+ read-write
+
+
+ THR_L_LIM_EN_U5
+ This is the enable bit for comparing unit5's count with thr_l_lim value.
+ 13
+ 1
+ read-write
+
+
+ THR_THRES0_EN_U5
+ This is the enable bit for comparing unit5's count with thres0 value.
+ 14
+ 1
+ read-write
+
+
+ THR_THRES1_EN_U5
+ This is the enable bit for comparing unit5's count with thres1 value .
+ 15
+ 1
+ read-write
+
+
+ CH0_NEG_MODE_U5
+ This register is used to control the mode of channel0's input negedge signal for unit5. 2'd1: increase at the negedge of input signal 2'd2:decrease at the negedge of input signal others:forbidden
+ 16
+ 2
+ read-write
+
+
+ CH0_POS_MODE_U5
+ This register is used to control the mode of channel0's input posedge signal for unit5. 2'd1: increase at the posedge of input signal 2'd2:decrease at the posedge of input signal others:forbidden
+ 18
+ 2
+ read-write
+
+
+ CH0_HCTRL_MODE_U5
+ This register is used to control the mode of channel0's high control signal for unit5. 2'd0:increase when control signal is low 2'd1: decrease when control signal is high others:forbidden
+ 20
+ 2
+ read-write
+
+
+ CH0_LCTRL_MODE_U5
+ This register is used to control the mode of channel0's low control signal for unit5. 2'd0:increase when control signal is low 2'd1: decrease when control signal is high others:forbidden
+ 22
+ 2
+ read-write
+
+
+ CH1_NEG_MODE_U5
+ This register is used to control the mode of channel1's input negedge signal for unit5. 2'd1: increase at the negedge of input signal 2'd2:decrease at the negedge of input signal others:forbidden
+ 24
+ 2
+ read-write
+
+
+ CH1_POS_MODE_U5
+ This register is used to control the mode of channel1's input posedge signal for unit5. 2'd1: increase at the posedge of input signal 2'd2:decrease at the posedge of input signal others:forbidden
+ 26
+ 2
+ read-write
+
+
+ CH1_HCTRL_MODE_U5
+ This register is used to control the mode of channel1's high control signal for unit5. 2'd0:increase when control signal is low 2'd1: decrease when control signal is high others:forbidden
+ 28
+ 2
+ read-write
+
+
+ CH1_LCTRL_MODE_U5
+ This register is used to control the mode of channel1's low control signal for unit5. 2'd0:increase when control signal is low 2'd1: decrease when control signal is high others:forbidden
+ 30
+ 2
+ read-write
+
+
+
+
+ U5_CONF1
+ 0x40
+ 0x20
+
+
+ CNT_THRES0_U5
+ This register is used to configure thres0 value for unit5.
+ 0
+ 16
+ read-write
+
+
+ CNT_THRES1_U5
+ This register is used to configure thres1 value for unit5.
+ 16
+ 16
+ read-write
+
+
+
+
+ U5_CONF2
+ 0x44
+ 0x20
+
+
+ CNT_H_LIM_U5
+ This register is used to configure thr_h_lim value for unit5.
+ 0
+ 16
+ read-write
+
+
+ CNT_L_LIM_U5
+ This register is used to confiugre thr_l_lim value for unit5.
+ 16
+ 16
+ read-write
+
+
+
+
+ U6_CONF0
+ 0x48
+ 0x20
+ 0x00003C10
+
+
+ FILTER_THRES_U6
+ This register is used to filter pluse whose width is smaller than this value for unit6.
+ 0
+ 10
+ read-write
+
+
+ FILTER_EN_U6
+ This is the enable bit for filtering input signals for unit6.
+ 10
+ 1
+ read-write
+
+
+ THR_ZERO_EN_U6
+ This is the enable bit for comparing unit6's count with 0 value.
+ 11
+ 1
+ read-write
+
+
+ THR_H_LIM_EN_U6
+ This is the enable bit for comparing unit6's count with thr_h_lim value.
+ 12
+ 1
+ read-write
+
+
+ THR_L_LIM_EN_U6
+ This is the enable bit for comparing unit6's count with thr_l_lim value.
+ 13
+ 1
+ read-write
+
+
+ THR_THRES0_EN_U6
+ This is the enable bit for comparing unit6's count with thres0 value.
+ 14
+ 1
+ read-write
+
+
+ THR_THRES1_EN_U6
+ This is the enable bit for comparing unit6's count with thres1 value .
+ 15
+ 1
+ read-write
+
+
+ CH0_NEG_MODE_U6
+ This register is used to control the mode of channel0's input negedge signal for unit6. 2'd1: increase at the negedge of input signal 2'd2:decrease at the negedge of input signal others:forbidden
+ 16
+ 2
+ read-write
+
+
+ CH0_POS_MODE_U6
+ This register is used to control the mode of channel0's input posedge signal for unit6. 2'd1: increase at the posedge of input signal 2'd2:decrease at the posedge of input signal others:forbidden
+ 18
+ 2
+ read-write
+
+
+ CH0_HCTRL_MODE_U6
+ This register is used to control the mode of channel0's high control signal for unit6. 2'd0:increase when control signal is low 2'd1: decrease when control signal is high others:forbidden
+ 20
+ 2
+ read-write
+
+
+ CH0_LCTRL_MODE_U6
+ This register is used to control the mode of channel0's low control signal for unit6. 2'd0:increase when control signal is low 2'd1: decrease when control signal is high others:forbidden
+ 22
+ 2
+ read-write
+
+
+ CH1_NEG_MODE_U6
+ This register is used to control the mode of channel1's input negedge signal for unit6. 2'd1: increase at the negedge of input signal 2'd2:decrease at the negedge of input signal others:forbidden
+ 24
+ 2
+ read-write
+
+
+ CH1_POS_MODE_U6
+ This register is used to control the mode of channel1's input posedge signal for unit6. 2'd1: increase at the posedge of input signal 2'd2:decrease at the posedge of input signal others:forbidden
+ 26
+ 2
+ read-write
+
+
+ CH1_HCTRL_MODE_U6
+ This register is used to control the mode of channel1's high control signal for unit6. 2'd0:increase when control signal is low 2'd1: decrease when control signal is high others:forbidden
+ 28
+ 2
+ read-write
+
+
+ CH1_LCTRL_MODE_U6
+ This register is used to control the mode of channel1's low control signal for unit6. 2'd0:increase when control signal is low 2'd1: decrease when control signal is high others:forbidden
+ 30
+ 2
+ read-write
+
+
+
+
+ U6_CONF1
+ 0x4C
+ 0x20
+
+
+ CNT_THRES0_U6
+ This register is used to configure thres0 value for unit6.
+ 0
+ 16
+ read-write
+
+
+ CNT_THRES1_U6
+ This register is used to configure thres1 value for unit6.
+ 16
+ 16
+ read-write
+
+
+
+
+ U6_CONF2
+ 0x50
+ 0x20
+
+
+ CNT_H_LIM_U6
+ This register is used to configure thr_h_lim value for unit6.
+ 0
+ 16
+ read-write
+
+
+ CNT_L_LIM_U6
+ This register is used to confiugre thr_l_lim value for unit6.
+ 16
+ 16
+ read-write
+
+
+
+
+ U7_CONF0
+ 0x54
+ 0x20
+ 0x00003C10
+
+
+ FILTER_THRES_U7
+ This register is used to filter pluse whose width is smaller than this value for unit7.
+ 0
+ 10
+ read-write
+
+
+ FILTER_EN_U7
+ This is the enable bit for filtering input signals for unit7.
+ 10
+ 1
+ read-write
+
+
+ THR_ZERO_EN_U7
+ This is the enable bit for comparing unit7's count with 0 value.
+ 11
+ 1
+ read-write
+
+
+ THR_H_LIM_EN_U7
+ This is the enable bit for comparing unit7's count with thr_h_lim value.
+ 12
+ 1
+ read-write
+
+
+ THR_L_LIM_EN_U7
+ This is the enable bit for comparing unit7's count with thr_l_lim value.
+ 13
+ 1
+ read-write
+
+
+ THR_THRES0_EN_U7
+ This is the enable bit for comparing unit7's count with thres0 value.
+ 14
+ 1
+ read-write
+
+
+ THR_THRES1_EN_U7
+ This is the enable bit for comparing unit7's count with thres1 value .
+ 15
+ 1
+ read-write
+
+
+ CH0_NEG_MODE_U7
+ This register is used to control the mode of channel0's input negedge signal for unit7. 2'd1: increase at the negedge of input signal 2'd2:decrease at the negedge of input signal others:forbidden
+ 16
+ 2
+ read-write
+
+
+ CH0_POS_MODE_U7
+ This register is used to control the mode of channel0's input posedge signal for unit7. 2'd1: increase at the posedge of input signal 2'd2:decrease at the posedge of input signal others:forbidden
+ 18
+ 2
+ read-write
+
+
+ CH0_HCTRL_MODE_U7
+ This register is used to control the mode of channel0's high control signal for unit7. 2'd0:increase when control signal is low 2'd1: decrease when control signal is high others:forbidden
+ 20
+ 2
+ read-write
+
+
+ CH0_LCTRL_MODE_U7
+ This register is used to control the mode of channel0's low control signal for unit7. 2'd0:increase when control signal is low 2'd1: decrease when control signal is high others:forbidden
+ 22
+ 2
+ read-write
+
+
+ CH1_NEG_MODE_U7
+ This register is used to control the mode of channel1's input negedge signal for unit7. 2'd1: increase at the negedge of input signal 2'd2:decrease at the negedge of input signal others:forbidden
+ 24
+ 2
+ read-write
+
+
+ CH1_POS_MODE_U7
+ This register is used to control the mode of channel1's input posedge signal for unit7. 2'd1: increase at the posedge of input signal 2'd2:decrease at the posedge of input signal others:forbidden
+ 26
+ 2
+ read-write
+
+
+ CH1_HCTRL_MODE_U7
+ This register is used to control the mode of channel1's high control signal for unit7. 2'd0:increase when control signal is low 2'd1: decrease when control signal is high others:forbidden
+ 28
+ 2
+ read-write
+
+
+ CH1_LCTRL_MODE_U7
+ This register is used to control the mode of channel1's low control signal for unit7. 2'd0:increase when control signal is low 2'd1: decrease when control signal is high others:forbidden
+ 30
+ 2
+ read-write
+
+
+
+
+ U7_CONF1
+ 0x58
+ 0x20
+
+
+ CNT_THRES0_U7
+ This register is used to configure thres0 value for unit7.
+ 0
+ 16
+ read-write
+
+
+ CNT_THRES1_U7
+ This register is used to configure thres1 value for unit7.
+ 16
+ 16
+ read-write
+
+
+
+
+ U7_CONF2
+ 0x5C
+ 0x20
+
+
+ CNT_H_LIM_U7
+ This register is used to configure thr_h_lim value for unit7.
+ 0
+ 16
+ read-write
+
+
+ CNT_L_LIM_U7
+ This register is used to confiugre thr_l_lim value for unit7.
+ 16
+ 16
+ read-write
+
+
+
+
+ U0_CNT
+ 0x60
+ 0x20
+
+
+ PLUS_CNT_U0
+ This register stores the current pulse count value for unit0.
+ 0
+ 16
+ read-only
+
+
+
+
+ U1_CNT
+ 0x64
+ 0x20
+
+
+ PLUS_CNT_U1
+ This register stores the current pulse count value for unit1.
+ 0
+ 16
+ read-only
+
+
+
+
+ U2_CNT
+ 0x68
+ 0x20
+
+
+ PLUS_CNT_U2
+ This register stores the current pulse count value for unit2.
+ 0
+ 16
+ read-only
+
+
+
+
+ U3_CNT
+ 0x6C
+ 0x20
+
+
+ PLUS_CNT_U3
+ This register stores the current pulse count value for unit3.
+ 0
+ 16
+ read-only
+
+
+
+
+ U4_CNT
+ 0x70
+ 0x20
+
+
+ PLUS_CNT_U4
+ This register stores the current pulse count value for unit4.
+ 0
+ 16
+ read-only
+
+
+
+
+ U5_CNT
+ 0x74
+ 0x20
+
+
+ PLUS_CNT_U5
+ This register stores the current pulse count value for unit5.
+ 0
+ 16
+ read-only
+
+
+
+
+ U6_CNT
+ 0x78
+ 0x20
+
+
+ PLUS_CNT_U6
+ This register stores the current pulse count value for unit6.
+ 0
+ 16
+ read-only
+
+
+
+
+ U7_CNT
+ 0x7C
+ 0x20
+
+
+ PLUS_CNT_U7
+ This register stores the current pulse count value for unit7.
+ 0
+ 16
+ read-only
+
+
+
+
+ INT_RAW
+ 0x80
+ 0x20
+
+
+ CNT_THR_EVENT_U0_INT_RAW
+ This is the interrupt raw bit for channel0 event.
+ 0
+ 1
+ read-only
+
+
+ CNT_THR_EVENT_U1_INT_RAW
+ This is the interrupt raw bit for channel1 event.
+ 1
+ 1
+ read-only
+
+
+ CNT_THR_EVENT_U2_INT_RAW
+ This is the interrupt raw bit for channel2 event.
+ 2
+ 1
+ read-only
+
+
+ CNT_THR_EVENT_U3_INT_RAW
+ This is the interrupt raw bit for channel3 event.
+ 3
+ 1
+ read-only
+
+
+ CNT_THR_EVENT_U4_INT_RAW
+ This is the interrupt raw bit for channel4 event.
+ 4
+ 1
+ read-only
+
+
+ CNT_THR_EVENT_U5_INT_RAW
+ This is the interrupt raw bit for channel5 event.
+ 5
+ 1
+ read-only
+
+
+ CNT_THR_EVENT_U6_INT_RAW
+ This is the interrupt raw bit for channel6 event.
+ 6
+ 1
+ read-only
+
+
+ CNT_THR_EVENT_U7_INT_RAW
+ This is the interrupt raw bit for channel7 event.
+ 7
+ 1
+ read-only
+
+
+
+
+ INT_ST
+ 0x84
+ 0x20
+
+
+ CNT_THR_EVENT_U0_INT_ST
+ This is the interrupt status bit for channel0 event.
+ 0
+ 1
+ read-only
+
+
+ CNT_THR_EVENT_U1_INT_ST
+ This is the interrupt status bit for channel1 event.
+ 1
+ 1
+ read-only
+
+
+ CNT_THR_EVENT_U2_INT_ST
+ This is the interrupt status bit for channel2 event.
+ 2
+ 1
+ read-only
+
+
+ CNT_THR_EVENT_U3_INT_ST
+ This is the interrupt status bit for channel3 event.
+ 3
+ 1
+ read-only
+
+
+ CNT_THR_EVENT_U4_INT_ST
+ This is the interrupt status bit for channel4 event.
+ 4
+ 1
+ read-only
+
+
+ CNT_THR_EVENT_U5_INT_ST
+ This is the interrupt status bit for channel5 event.
+ 5
+ 1
+ read-only
+
+
+ CNT_THR_EVENT_U6_INT_ST
+ This is the interrupt status bit for channel6 event.
+ 6
+ 1
+ read-only
+
+
+ CNT_THR_EVENT_U7_INT_ST
+ This is the interrupt status bit for channel7 event.
+ 7
+ 1
+ read-only
+
+
+
+
+ INT_ENA
+ 0x88
+ 0x20
+
+
+ CNT_THR_EVENT_U0_INT_ENA
+ This is the interrupt enable bit for channel0 event.
+ 0
+ 1
+ read-write
+
+
+ CNT_THR_EVENT_U1_INT_ENA
+ This is the interrupt enable bit for channel1 event.
+ 1
+ 1
+ read-write
+
+
+ CNT_THR_EVENT_U2_INT_ENA
+ This is the interrupt enable bit for channel2 event.
+ 2
+ 1
+ read-write
+
+
+ CNT_THR_EVENT_U3_INT_ENA
+ This is the interrupt enable bit for channel3 event.
+ 3
+ 1
+ read-write
+
+
+ CNT_THR_EVENT_U4_INT_ENA
+ This is the interrupt enable bit for channel4 event.
+ 4
+ 1
+ read-write
+
+
+ CNT_THR_EVENT_U5_INT_ENA
+ This is the interrupt enable bit for channel5 event.
+ 5
+ 1
+ read-write
+
+
+ CNT_THR_EVENT_U6_INT_ENA
+ This is the interrupt enable bit for channel6 event.
+ 6
+ 1
+ read-write
+
+
+ CNT_THR_EVENT_U7_INT_ENA
+ This is the interrupt enable bit for channel7 event.
+ 7
+ 1
+ read-write
+
+
+
+
+ INT_CLR
+ 0x8C
+ 0x20
+
+
+ CNT_THR_EVENT_U0_INT_CLR
+ Set this bit to clear channel0 event interrupt.
+ 0
+ 1
+ write-only
+
+
+ CNT_THR_EVENT_U1_INT_CLR
+ Set this bit to clear channel1 event interrupt.
+ 1
+ 1
+ write-only
+
+
+ CNT_THR_EVENT_U2_INT_CLR
+ Set this bit to clear channel2 event interrupt.
+ 2
+ 1
+ write-only
+
+
+ CNT_THR_EVENT_U3_INT_CLR
+ Set this bit to clear channel3 event interrupt.
+ 3
+ 1
+ write-only
+
+
+ CNT_THR_EVENT_U4_INT_CLR
+ Set this bit to clear channel4 event interrupt.
+ 4
+ 1
+ write-only
+
+
+ CNT_THR_EVENT_U5_INT_CLR
+ Set this bit to clear channel5 event interrupt.
+ 5
+ 1
+ write-only
+
+
+ CNT_THR_EVENT_U6_INT_CLR
+ Set this bit to clear channel6 event interrupt.
+ 6
+ 1
+ write-only
+
+
+ CNT_THR_EVENT_U7_INT_CLR
+ Set this bit to clear channel7 event interrupt.
+ 7
+ 1
+ write-only
+
+
+
+
+ U0_STATUS
+ 0x90
+ 0x20
+
+
+ CORE_STATUS_U0
+ 0
+ 32
+ read-only
+
+
+ STATUS_CNT_MODE
+ 0
+ 2
+ read-write
+
+
+ STATUS_THRES1
+ 2
+ 1
+ read-write
+
+
+ STATUS_THRES0
+ 3
+ 1
+ read-write
+
+
+ STATUS_L_LIM
+ 4
+ 1
+ read-write
+
+
+ STATUS_H_LIM
+ 5
+ 1
+ read-write
+
+
+ STATUS_ZERO
+ 6
+ 1
+ read-write
+
+
+
+
+ U1_STATUS
+ 0x94
+ 0x20
+
+
+ CORE_STATUS_U1
+ 0
+ 32
+ read-only
+
+
+
+
+ U2_STATUS
+ 0x98
+ 0x20
+
+
+ CORE_STATUS_U2
+ 0
+ 32
+ read-only
+
+
+
+
+ U3_STATUS
+ 0x9C
+ 0x20
+
+
+ CORE_STATUS_U3
+ 0
+ 32
+ read-only
+
+
+
+
+ U4_STATUS
+ 0xA0
+ 0x20
+
+
+ CORE_STATUS_U4
+ 0
+ 32
+ read-only
+
+
+
+
+ U5_STATUS
+ 0xA4
+ 0x20
+
+
+ CORE_STATUS_U5
+ 0
+ 32
+ read-only
+
+
+
+
+ U6_STATUS
+ 0xA8
+ 0x20
+
+
+ CORE_STATUS_U6
+ 0
+ 32
+ read-only
+
+
+
+
+ U7_STATUS
+ 0xAC
+ 0x20
+
+
+ CORE_STATUS_U7
+ 0
+ 32
+ read-only
+
+
+
+
+ CTRL
+ 0xB0
+ 0x20
+ 0x00005555
+
+
+ PLUS_CNT_RST_U0
+ Set this bit to clear unit0's counter.
+ 0
+ 1
+ read-write
+
+
+ CNT_PAUSE_U0
+ Set this bit to pause unit0's counter.
+ 1
+ 1
+ read-write
+
+
+ PLUS_CNT_RST_U1
+ Set this bit to clear unit1's counter.
+ 2
+ 1
+ read-write
+
+
+ CNT_PAUSE_U1
+ Set this bit to pause unit1's counter.
+ 3
+ 1
+ read-write
+
+
+ PLUS_CNT_RST_U2
+ Set this bit to clear unit2's counter.
+ 4
+ 1
+ read-write
+
+
+ CNT_PAUSE_U2
+ Set this bit to pause unit2's counter.
+ 5
+ 1
+ read-write
+
+
+ PLUS_CNT_RST_U3
+ Set this bit to clear unit3's counter.
+ 6
+ 1
+ read-write
+
+
+ CNT_PAUSE_U3
+ Set this bit to pause unit3's counter.
+ 7
+ 1
+ read-write
+
+
+ PLUS_CNT_RST_U4
+ Set this bit to clear unit4's counter.
+ 8
+ 1
+ read-write
+
+
+ CNT_PAUSE_U4
+ Set this bit to pause unit4's counter.
+ 9
+ 1
+ read-write
+
+
+ PLUS_CNT_RST_U5
+ Set this bit to clear unit5's counter.
+ 10
+ 1
+ read-write
+
+
+ CNT_PAUSE_U5
+ Set this bit to pause unit5's counter.
+ 11
+ 1
+ read-write
+
+
+ PLUS_CNT_RST_U6
+ Set this bit to clear unit6's counter.
+ 12
+ 1
+ read-write
+
+
+ CNT_PAUSE_U6
+ Set this bit to pause unit6's counter.
+ 13
+ 1
+ read-write
+
+
+ PLUS_CNT_RST_U7
+ Set this bit to clear unit7's counter.
+ 14
+ 1
+ read-write
+
+
+ CNT_PAUSE_U7
+ Set this bit to pause unit7's counter.
+ 15
+ 1
+ read-write
+
+
+ CLK_EN
+ 16
+ 1
+ read-write
+
+
+
+
+ DATE
+ 0xFC
+ 0x20
+ 0x14122600
+
+
+ DATE
+ 0
+ 32
+ read-write
+
+
+
+
+
+
+ RMT
+ Remote Control Peripheral
+ RMT
+ 0x3FF56000
+
+ 0x0
+ 0xF8
+ registers
+
+
+ RMT
+ 47
+
+
+
+ CH0DATA
+ 0x0
+ 0x20
+
+
+ CH1DATA
+ 0x4
+ 0x20
+
+
+ CH2DATA
+ 0x8
+ 0x20
+
+
+ CH3DATA
+ 0xC
+ 0x20
+
+
+ CH4DATA
+ 0x10
+ 0x20
+
+
+ CH5DATA
+ 0x14
+ 0x20
+
+
+ CH6DATA
+ 0x18
+ 0x20
+
+
+ CH7DATA
+ 0x1C
+ 0x20
+
+
+ 8
+ 0x8
+ 0-7
+ CH%sCONF0
+ 0x20
+ 0x20
+ 0x31100002
+
+
+ DIV_CNT
+ This register is used to configure the frequency divider's factor in channel0.
+ 0
+ 8
+ read-write
+
+
+ IDLE_THRES
+ In receive mode when no edge is detected on the input signal for longer than reg_idle_thres_ch0 then the receive process is done.
+ 8
+ 16
+ read-write
+
+
+ MEM_SIZE
+ This register is used to configure the the amount of memory blocks allocated to channel0.
+ 24
+ 4
+ read-write
+
+
+ CARRIER_EN
+ This is the carrier modulation enable control bit for channel0.
+ 28
+ 1
+ read-write
+
+
+ CARRIER_OUT_LV
+ This bit is used to configure the way carrier wave is modulated for channel0.1'b1:transmit on low output level 1'b0:transmit on high output level.
+ 29
+ 1
+ read-write
+
+
+ MEM_PD
+ This bit is used to reduce power consumed by mem. 1:mem is in low power state.
+ 30
+ 1
+ read-write
+
+
+ CLK_EN
+ This bit is used to control clock.when software config RMT internal registers it controls the register clock.
+ 31
+ 1
+ read-write
+
+
+
+
+ 8
+ 0x8
+ 0-7
+ CH%sCONF1
+ 0x24
+ 0x20
+ 0x00000F20
+
+
+ TX_START
+ Set this bit to start sending data for channel0.
+ 0
+ 1
+ read-write
+
+
+ RX_EN
+ Set this bit to enbale receving data for channel0.
+ 1
+ 1
+ read-write
+
+
+ MEM_WR_RST
+ Set this bit to reset write ram address for channel0 by receiver access.
+ 2
+ 1
+ read-write
+
+
+ MEM_RD_RST
+ Set this bit to reset read ram address for channel0 by transmitter access.
+ 3
+ 1
+ read-write
+
+
+ APB_MEM_RST
+ Set this bit to reset W/R ram address for channel0 by apb fifo access
+ 4
+ 1
+ read-write
+
+
+ MEM_OWNER
+ This is the mark of channel0's ram usage right.1'b1:receiver uses the ram 0:transmitter uses the ram
+ 5
+ 1
+ read-write
+
+
+ TX_CONTI_MODE
+ Set this bit to continue sending from the first data to the last data in channel0 again and again.
+ 6
+ 1
+ read-write
+
+
+ RX_FILTER_EN
+ This is the receive filter enable bit for channel0.
+ 7
+ 1
+ read-write
+
+
+ RX_FILTER_THRES
+ in receive mode channel0 ignore input pulse when the pulse width is smaller then this value.
+ 8
+ 8
+ read-write
+
+
+ REF_CNT_RST
+ This bit is used to reset divider in channel0.
+ 16
+ 1
+ read-write
+
+
+ REF_ALWAYS_ON
+ This bit is used to select base clock. 1'b1:clk_apb 1'b0:clk_ref
+ 17
+ 1
+ read-write
+
+
+ IDLE_OUT_LV
+ This bit configures the output signal's level for channel0 in IDLE state.
+ 18
+ 1
+ read-write
+
+
+ IDLE_OUT_EN
+ This is the output enable control bit for channel0 in IDLE state.
+ 19
+ 1
+ read-write
+
+
+
+
+ CH0STATUS
+ 0x60
+ 0x20
+
+
+ STATUS
+ The status for channel0
+ 0
+ 32
+ read-only
+
+
+ MEM_WADDR_EX
+ The current memory read address of channel0.
+ 0
+ 10
+ read-only
+
+
+ MEM_RADDR_EX
+ The current memory write address of channel0.
+ 12
+ 10
+ read-only
+
+
+ STATE
+ The channel0 state machine status register.3'h0 : idle, 3'h1 : send, 3'h2 : read memory, 3'h3 : receive, 3'h4 : wait.
+ 24
+ 3
+ read-only
+
+
+ MEM_OWNER_ERR
+ When channel0 is configured for receive mode, this bit will turn to high level if rmt_mem_owner register is not set to 1.
+ 27
+ 1
+ read-only
+
+
+ MEM_FULL
+ The memory full status bit for channel0 turns to high level when mem_waddr_ex is greater than or equal to the configuration range.
+ 28
+ 1
+ read-only
+
+
+ MEM_EMPTY
+ The memory empty status bit for channel0. in acyclic mode, this bit turns to high level when mem_raddr_ex is greater than or equal to the configured range.
+ 29
+ 1
+ read-only
+
+
+ APB_MEM_WR_ERR
+ The apb write memory status bit for channel0 turns to high level when the apb write address exceeds the configuration range.
+ 30
+ 1
+ read-only
+
+
+ APB_MEM_RD_ERR
+ The apb read memory status bit for channel0 turns to high level when the apb read address exceeds the configuration range.
+ 31
+ 1
+ read-only
+
+
+
+
+ CH1STATUS
+ 0x64
+ 0x20
+
+
+ STATUS
+ The status for channel1
+ 0
+ 32
+ read-only
+
+
+ MEM_WADDR_EX
+ The current memory read address of channel1.
+ 0
+ 10
+ read-only
+
+
+ MEM_RADDR_EX
+ The current memory write address of channel1.
+ 12
+ 10
+ read-only
+
+
+ STATE
+ The channel1 state machine status register.3'h0 : idle, 3'h1 : send, 3'h2 : read memory, 3'h3 : receive, 3'h4 : wait.
+ 24
+ 3
+ read-only
+
+
+ MEM_OWNER_ERR
+ When channel1 is configured for receive mode, this bit will turn to high level if rmt_mem_owner register is not set to 1.
+ 27
+ 1
+ read-only
+
+
+ MEM_FULL
+ The memory full status bit for channel1 turns to high level when mem_waddr_ex is greater than or equal to the configuration range.
+ 28
+ 1
+ read-only
+
+
+ MEM_EMPTY
+ The memory empty status bit for channel1. in acyclic mode, this bit turns to high level when mem_raddr_ex is greater than or equal to the configured range.
+ 29
+ 1
+ read-only
+
+
+ APB_MEM_WR_ERR
+ The apb write memory status bit for channel1 turns to high level when the apb write address exceeds the configuration range.
+ 30
+ 1
+ read-only
+
+
+ APB_MEM_RD_ERR
+ The apb read memory status bit for channel1 turns to high level when the apb read address exceeds the configuration range.
+ 31
+ 1
+ read-only
+
+
+
+
+ CH2STATUS
+ 0x68
+ 0x20
+
+
+ STATUS
+ The status for channel2
+ 0
+ 32
+ read-only
+
+
+ MEM_WADDR_EX
+ The current memory read address of channel2.
+ 0
+ 10
+ read-only
+
+
+ MEM_RADDR_EX
+ The current memory write address of channel2.
+ 12
+ 10
+ read-only
+
+
+ STATE
+ The channel2 state machine status register.3'h0 : idle, 3'h1 : send, 3'h2 : read memory, 3'h3 : receive, 3'h4 : wait.
+ 24
+ 3
+ read-only
+
+
+ MEM_OWNER_ERR
+ When channel2 is configured for receive mode, this bit will turn to high level if rmt_mem_owner register is not set to 1.
+ 27
+ 1
+ read-only
+
+
+ MEM_FULL
+ The memory full status bit for channel2 turns to high level when mem_waddr_ex is greater than or equal to the configuration range.
+ 28
+ 1
+ read-only
+
+
+ MEM_EMPTY
+ The memory empty status bit for channel2. in acyclic mode, this bit turns to high level when mem_raddr_ex is greater than or equal to the configured range.
+ 29
+ 1
+ read-only
+
+
+ APB_MEM_WR_ERR
+ The apb write memory status bit for channel2 turns to high level when the apb write address exceeds the configuration range.
+ 30
+ 1
+ read-only
+
+
+ APB_MEM_RD_ERR
+ The apb read memory status bit for channel2 turns to high level when the apb read address exceeds the configuration range.
+ 31
+ 1
+ read-only
+
+
+
+
+ CH3STATUS
+ 0x6C
+ 0x20
+
+
+ STATUS
+ The status for channel3
+ 0
+ 32
+ read-only
+
+
+ MEM_WADDR_EX
+ The current memory read address of channel3.
+ 0
+ 10
+ read-only
+
+
+ MEM_RADDR_EX
+ The current memory write address of channel3.
+ 12
+ 10
+ read-only
+
+
+ STATE
+ The channel3 state machine status register.3'h0 : idle, 3'h1 : send, 3'h2 : read memory, 3'h3 : receive, 3'h4 : wait.
+ 24
+ 3
+ read-only
+
+
+ MEM_OWNER_ERR
+ When channel3 is configured for receive mode, this bit will turn to high level if rmt_mem_owner register is not set to 1.
+ 27
+ 1
+ read-only
+
+
+ MEM_FULL
+ The memory full status bit for channel3 turns to high level when mem_waddr_ex is greater than or equal to the configuration range.
+ 28
+ 1
+ read-only
+
+
+ MEM_EMPTY
+ The memory empty status bit for channel3. in acyclic mode, this bit turns to high level when mem_raddr_ex is greater than or equal to the configured range.
+ 29
+ 1
+ read-only
+
+
+ APB_MEM_WR_ERR
+ The apb write memory status bit for channel3 turns to high level when the apb write address exceeds the configuration range.
+ 30
+ 1
+ read-only
+
+
+ APB_MEM_RD_ERR
+ The apb read memory status bit for channel3 turns to high level when the apb read address exceeds the configuration range.
+ 31
+ 1
+ read-only
+
+
+
+
+ CH4STATUS
+ 0x70
+ 0x20
+
+
+ STATUS
+ The status for channel4
+ 0
+ 32
+ read-only
+
+
+ MEM_WADDR_EX
+ The current memory read address of channel4.
+ 0
+ 10
+ read-only
+
+
+ MEM_RADDR_EX
+ The current memory write address of channel4.
+ 12
+ 10
+ read-only
+
+
+ STATE
+ The channel4 state machine status register.3'h0 : idle, 3'h1 : send, 3'h2 : read memory, 3'h3 : receive, 3'h4 : wait.
+ 24
+ 3
+ read-only
+
+
+ MEM_OWNER_ERR
+ When channel4 is configured for receive mode, this bit will turn to high level if rmt_mem_owner register is not set to 1.
+ 27
+ 1
+ read-only
+
+
+ MEM_FULL
+ The memory full status bit for channel4 turns to high level when mem_waddr_ex is greater than or equal to the configuration range.
+ 28
+ 1
+ read-only
+
+
+ MEM_EMPTY
+ The memory empty status bit for channel4. in acyclic mode, this bit turns to high level when mem_raddr_ex is greater than or equal to the configured range.
+ 29
+ 1
+ read-only
+
+
+ APB_MEM_WR_ERR
+ The apb write memory status bit for channel4 turns to high level when the apb write address exceeds the configuration range.
+ 30
+ 1
+ read-only
+
+
+ APB_MEM_RD_ERR
+ The apb read memory status bit for channel4 turns to high level when the apb read address exceeds the configuration range.
+ 31
+ 1
+ read-only
+
+
+
+
+ CH5STATUS
+ 0x74
+ 0x20
+
+
+ STATUS
+ The status for channel5
+ 0
+ 32
+ read-only
+
+
+ MEM_WADDR_EX
+ The current memory read address of channel5.
+ 0
+ 10
+ read-only
+
+
+ MEM_RADDR_EX
+ The current memory write address of channel5.
+ 12
+ 10
+ read-only
+
+
+ STATE
+ The channel5 state machine status register.3'h0 : idle, 3'h1 : send, 3'h2 : read memory, 3'h3 : receive, 3'h4 : wait.
+ 24
+ 3
+ read-only
+
+
+ MEM_OWNER_ERR
+ When channel5 is configured for receive mode, this bit will turn to high level if rmt_mem_owner register is not set to 1.
+ 27
+ 1
+ read-only
+
+
+ MEM_FULL
+ The memory full status bit for channel5 turns to high level when mem_waddr_ex is greater than or equal to the configuration range.
+ 28
+ 1
+ read-only
+
+
+ MEM_EMPTY
+ The memory empty status bit for channel5. in acyclic mode, this bit turns to high level when mem_raddr_ex is greater than or equal to the configured range.
+ 29
+ 1
+ read-only
+
+
+ APB_MEM_WR_ERR
+ The apb write memory status bit for channel5 turns to high level when the apb write address exceeds the configuration range.
+ 30
+ 1
+ read-only
+
+
+ APB_MEM_RD_ERR
+ The apb read memory status bit for channel5 turns to high level when the apb read address exceeds the configuration range.
+ 31
+ 1
+ read-only
+
+
+
+
+ CH6STATUS
+ 0x78
+ 0x20
+
+
+ STATUS
+ The status for channel6
+ 0
+ 32
+ read-only
+
+
+ MEM_WADDR_EX
+ The current memory read address of channel6.
+ 0
+ 10
+ read-only
+
+
+ MEM_RADDR_EX
+ The current memory write address of channel6.
+ 12
+ 10
+ read-only
+
+
+ STATE
+ The channel6 state machine status register.3'h0 : idle, 3'h1 : send, 3'h2 : read memory, 3'h3 : receive, 3'h4 : wait.
+ 24
+ 3
+ read-only
+
+
+ MEM_OWNER_ERR
+ When channel6 is configured for receive mode, this bit will turn to high level if rmt_mem_owner register is not set to 1.
+ 27
+ 1
+ read-only
+
+
+ MEM_FULL
+ The memory full status bit for channel6 turns to high level when mem_waddr_ex is greater than or equal to the configuration range.
+ 28
+ 1
+ read-only
+
+
+ MEM_EMPTY
+ The memory empty status bit for channel6. in acyclic mode, this bit turns to high level when mem_raddr_ex is greater than or equal to the configured range.
+ 29
+ 1
+ read-only
+
+
+ APB_MEM_WR_ERR
+ The apb write memory status bit for channel6 turns to high level when the apb write address exceeds the configuration range.
+ 30
+ 1
+ read-only
+
+
+ APB_MEM_RD_ERR
+ The apb read memory status bit for channel6 turns to high level when the apb read address exceeds the configuration range.
+ 31
+ 1
+ read-only
+
+
+
+
+ CH7STATUS
+ 0x7C
+ 0x20
+
+
+ STATUS
+ The status for channel7
+ 0
+ 32
+ read-only
+
+
+ MEM_WADDR_EX
+ The current memory read address of channel7.
+ 0
+ 10
+ read-only
+
+
+ MEM_RADDR_EX
+ The current memory write address of channel7.
+ 12
+ 10
+ read-only
+
+
+ STATE
+ The channel7 state machine status register.3'h0 : idle, 3'h1 : send, 3'h2 : read memory, 3'h3 : receive, 3'h4 : wait.
+ 24
+ 3
+ read-only
+
+
+ MEM_OWNER_ERR
+ When channel7 is configured for receive mode, this bit will turn to high level if rmt_mem_owner register is not set to 1.
+ 27
+ 1
+ read-only
+
+
+ MEM_FULL
+ The memory full status bit for channel7 turns to high level when mem_waddr_ex is greater than or equal to the configuration range.
+ 28
+ 1
+ read-only
+
+
+ MEM_EMPTY
+ The memory empty status bit for channel7. in acyclic mode, this bit turns to high level when mem_raddr_ex is greater than or equal to the configured range.
+ 29
+ 1
+ read-only
+
+
+ APB_MEM_WR_ERR
+ The apb write memory status bit for channel7 turns to high level when the apb write address exceeds the configuration range.
+ 30
+ 1
+ read-only
+
+
+ APB_MEM_RD_ERR
+ The apb read memory status bit for channel7 turns to high level when the apb read address exceeds the configuration range.
+ 31
+ 1
+ read-only
+
+
+
+
+ CH0ADDR
+ 0x80
+ 0x20
+
+
+ APB_MEM_ADDR
+ The ram relative address in channel0 by apb fifo access
+ 0
+ 32
+ read-only
+
+
+
+
+ CH1ADDR
+ 0x84
+ 0x20
+
+
+ APB_MEM_ADDR
+ The ram relative address in channel1 by apb fifo access
+ 0
+ 32
+ read-only
+
+
+
+
+ CH2ADDR
+ 0x88
+ 0x20
+
+
+ APB_MEM_ADDR
+ The ram relative address in channel2 by apb fifo access
+ 0
+ 32
+ read-only
+
+
+
+
+ CH3ADDR
+ 0x8C
+ 0x20
+
+
+ APB_MEM_ADDR
+ The ram relative address in channel3 by apb fifo access
+ 0
+ 32
+ read-only
+
+
+
+
+ CH4ADDR
+ 0x90
+ 0x20
+
+
+ APB_MEM_ADDR
+ The ram relative address in channel4 by apb fifo access
+ 0
+ 32
+ read-only
+
+
+
+
+ CH5ADDR
+ 0x94
+ 0x20
+
+
+ APB_MEM_ADDR
+ The ram relative address in channel5 by apb fifo access
+ 0
+ 32
+ read-only
+
+
+
+
+ CH6ADDR
+ 0x98
+ 0x20
+
+
+ APB_MEM_ADDR
+ The ram relative address in channel6 by apb fifo access
+ 0
+ 32
+ read-only
+
+
+
+
+ CH7ADDR
+ 0x9C
+ 0x20
+
+
+ APB_MEM_ADDR
+ The ram relative address in channel7 by apb fifo access
+ 0
+ 32
+ read-only
+
+
+
+
+ INT_RAW
+ 0xA0
+ 0x20
+
+
+ 8
+ 0x3
+ 0-7
+ CH%s_TX_END_INT_RAW
+ The interrupt raw bit for channel %s turns to high level when the transmit process is done.
+ 0
+ 1
+ read-only
+
+
+ 8
+ 0x3
+ 0-7
+ CH%s_RX_END_INT_RAW
+ The interrupt raw bit for channel %s turns to high level when the receive process is done.
+ 1
+ 1
+ read-only
+
+
+ 8
+ 0x3
+ 0-7
+ CH%s_ERR_INT_RAW
+ The interrupt raw bit for channel %s turns to high level when channle %s detects some errors.
+ 2
+ 1
+ read-only
+
+
+ 8
+ 0x1
+ 0-7
+ CH%s_TX_THR_EVENT_INT_RAW
+ The interrupt raw bit for channel %s turns to high level when transmitter in channle%s have send datas more than reg_rmt_tx_lim_ch%s after detecting this interrupt software can updata the old datas with new datas.
+ 24
+ 1
+ read-only
+
+
+
+
+ INT_ST
+ 0xA4
+ 0x20
+
+
+ 8
+ 0x3
+ 0-7
+ CH%s_TX_END_INT_ST
+ The interrupt state bit for channel %s's mt_ch%s_tx_end_int_raw when mt_ch%s_tx_end_int_ena is set to %s.
+ 0
+ 1
+ read-only
+
+
+ 8
+ 0x3
+ 0-7
+ CH%s_RX_END_INT_ST
+ The interrupt state bit for channel %s's rmt_ch%s_rx_end_int_raw when rmt_ch%s_rx_end_int_ena is set to %s.
+ 1
+ 1
+ read-only
+
+
+ 8
+ 0x3
+ 0-7
+ CH%s_ERR_INT_ST
+ The interrupt state bit for channel %s's rmt_ch%s_err_int_raw when rmt_ch%s_err_int_ena is set to %s.
+ 2
+ 1
+ read-only
+
+
+ 8
+ 0x1
+ 0-7
+ CH%s_TX_THR_EVENT_INT_ST
+ The interrupt state bit for channel %s's rmt_ch%s_tx_thr_event_int_raw when mt_ch%s_tx_thr_event_int_ena is set to 1.
+ 24
+ 1
+ read-only
+
+
+
+
+ INT_ENA
+ 0xA8
+ 0x20
+
+
+ 8
+ 0x3
+ 0-7
+ CH%s_TX_END_INT_ENA
+ Set this bit to enable rmt_ch%s_tx_end_int_st.
+ 0
+ 1
+ read-write
+
+
+ 8
+ 0x3
+ 0-7
+ CH%s_RX_END_INT_ENA
+ Set this bit to enable rmt_ch%s_rx_end_int_st.
+ 1
+ 1
+ read-write
+
+
+ 8
+ 0x3
+ 0-7
+ CH%s_ERR_INT_ENA
+ Set this bit to enable rmt_ch%s_err_int_st.
+ 2
+ 1
+ read-write
+
+
+ 8
+ 0x1
+ 0-7
+ CH%s_TX_THR_EVENT_INT_ENA
+ Set this bit to enable rmt_ch%s_tx_thr_event_int_st.
+ 24
+ 1
+ read-write
+
+
+
+
+ INT_CLR
+ 0xAC
+ 0x20
+
+
+ 8
+ 0x3
+ 0-7
+ CH%s_TX_END_INT_CLR
+ Set this bit to clear the rmt_ch%s_rx_end_int_raw..
+ 0
+ 1
+ write-only
+
+
+ 8
+ 0x3
+ 0-7
+ CH%s_RX_END_INT_CLR
+ Set this bit to clear the rmt_ch%s_tx_end_int_raw.
+ 1
+ 1
+ write-only
+
+
+ 8
+ 0x3
+ 0-7
+ CH%s_ERR_INT_CLR
+ Set this bit to clear the rmt_ch%s_err_int_raw.
+ 2
+ 1
+ write-only
+
+
+ 8
+ 0x1
+ 0-7
+ CH%s_TX_THR_EVENT_INT_CLR
+ Set this bit to clear the rmt_ch%s_tx_thr_event_int_raw interrupt.
+ 24
+ 1
+ write-only
+
+
+
+
+ CH0CARRIER_DUTY
+ 0xB0
+ 0x20
+ 0x00400040
+
+
+ CARRIER_LOW
+ This register is used to configure carrier wave's low level value for channel0.
+ 0
+ 16
+ read-write
+
+
+ CARRIER_HIGH
+ This register is used to configure carrier wave's high level value for channel0.
+ 16
+ 16
+ read-write
+
+
+
+
+ CH1CARRIER_DUTY
+ 0xB4
+ 0x20
+ 0x00400040
+
+
+ CARRIER_LOW
+ This register is used to configure carrier wave's low level value for channel1.
+ 0
+ 16
+ read-write
+
+
+ CARRIER_HIGH
+ This register is used to configure carrier wave's high level value for channel1.
+ 16
+ 16
+ read-write
+
+
+
+
+ CH2CARRIER_DUTY
+ 0xB8
+ 0x20
+ 0x00400040
+
+
+ CARRIER_LOW
+ This register is used to configure carrier wave's low level value for channel2.
+ 0
+ 16
+ read-write
+
+
+ CARRIER_HIGH
+ This register is used to configure carrier wave's high level value for channel2.
+ 16
+ 16
+ read-write
+
+
+
+
+ CH3CARRIER_DUTY
+ 0xBC
+ 0x20
+ 0x00400040
+
+
+ CARRIER_LOW
+ This register is used to configure carrier wave's low level value for channel3.
+ 0
+ 16
+ read-write
+
+
+ CARRIER_HIGH
+ This register is used to configure carrier wave's high level value for channel3.
+ 16
+ 16
+ read-write
+
+
+
+
+ CH4CARRIER_DUTY
+ 0xC0
+ 0x20
+ 0x00400040
+
+
+ CARRIER_LOW
+ This register is used to configure carrier wave's low level value for channel4.
+ 0
+ 16
+ read-write
+
+
+ CARRIER_HIGH
+ This register is used to configure carrier wave's high level value for channel4.
+ 16
+ 16
+ read-write
+
+
+
+
+ CH5CARRIER_DUTY
+ 0xC4
+ 0x20
+ 0x00400040
+
+
+ CARRIER_LOW
+ This register is used to configure carrier wave's low level value for channel5.
+ 0
+ 16
+ read-write
+
+
+ CARRIER_HIGH
+ This register is used to configure carrier wave's high level value for channel5.
+ 16
+ 16
+ read-write
+
+
+
+
+ CH6CARRIER_DUTY
+ 0xC8
+ 0x20
+ 0x00400040
+
+
+ CARRIER_LOW
+ This register is used to configure carrier wave's low level value for channel6.
+ 0
+ 16
+ read-write
+
+
+ CARRIER_HIGH
+ This register is used to configure carrier wave's high level value for channel6.
+ 16
+ 16
+ read-write
+
+
+
+
+ CH7CARRIER_DUTY
+ 0xCC
+ 0x20
+ 0x00400040
+
+
+ CARRIER_LOW
+ This register is used to configure carrier wave's low level value for channel7.
+ 0
+ 16
+ read-write
+
+
+ CARRIER_HIGH
+ This register is used to configure carrier wave's high level value for channel7.
+ 16
+ 16
+ read-write
+
+
+
+
+ 8
+ 0x4
+ 0-7
+ CH%s_TX_LIM
+ 0xD0
+ 0x20
+ 0x00000080
+
+
+ TX_LIM
+ When channel0 sends more than reg_rmt_tx_lim_ch0 datas then channel0 produce the relative interrupt.
+ 0
+ 9
+ read-write
+
+
+
+
+ APB_CONF
+ 0xF0
+ 0x20
+
+
+ APB_FIFO_MASK
+ Set this bit to disable apb fifo access
+ 0
+ 1
+ read-write
+
+
+ MEM_TX_WRAP_EN
+ when datas need to be send is more than channel's mem can store then set this bit to enable reusage of mem this bit is used together with reg_rmt_tx_lim_chn.
+ 1
+ 1
+ read-write
+
+
+
+
+ DATE
+ 0xFC
+ 0x20
+ 0x16022600
+
+
+ DATE
+ This is the version register.
+ 0
+ 32
+ read-write
+
+
+
+
+
+
+ RNG
+ Hardware random number generator
+ RNG
+ 0x60035000
+
+ 0x0
+ 0x4
+ registers
+
+
+
+ DATA
+ Random number data
+ 0x144
+ 0x20
+
+
+
+
+ RSA
+ RSA (Rivest Shamir Adleman) Accelerator
+ RSA
+ 0x3FF02000
+
+ 0x0
+ 0x1C
+ registers
+
+
+ RSA
+ 51
+
+
+
+ M_PRIME
+ 0x0
+ 0x20
+
+
+ M_PRIME
+ This register contains M’.
+ 0
+ 8
+ read-write
+
+
+
+
+ MODEXP_MODE
+ 0x4
+ 0x20
+
+
+ MODEXP_MODE
+ This register contains the mode of modular exponentiation.
+ 0
+ 2
+ read-write
+
+
+
+
+ MODEXP_START
+ 0x8
+ 0x20
+
+
+ MODEXP_START
+ Write 1 to start modular exponentiation.
+ 0
+ 1
+ write-only
+
+
+
+
+ MULT_MODE
+ 0xC
+ 0x20
+
+
+ MULT_MODE
+ This register contains the mode of modular multiplication and multiplication.
+ 0
+ 1
+ read-write
+
+
+
+
+ MULT_START
+ 0x10
+ 0x20
+
+
+ MULT_START
+ Write 1 to start modular multiplication or multiplication.
+ 0
+ 1
+ write-only
+
+
+
+
+ INTERRUPT
+ 0x14
+ 0x20
+
+
+ INTERRUPT
+ RSA interrupt status register. Will read 1 once an operation has completed.
+ 0
+ 1
+ read-write
+
+
+
+
+ CLEAN
+ 0x18
+ 0x20
+
+
+ CLEAN
+ This bit will read 1 once the memory initialization is completed.
+ 0
+ 1
+ read-only
+
+
+
+
+
+
+ RTC_CNTL
+ Real-Time Clock Control
+ RTC_CNTL
+ 0x3FF48000
+
+ 0x0
+ 0xDC
+ registers
+
+
+ RTC_CORE
+ 46
+
+
+
+ OPTIONS0
+ 0x0
+ 0x20
+ 0x1C492000
+
+
+ SW_STALL_APPCPU_C0
+ {reg_sw_stall_appcpu_c1[5:0] reg_sw_stall_appcpu_c0[1:0]} == 0x86 will stall APP CPU
+ 0
+ 2
+ read-write
+
+
+ SW_STALL_PROCPU_C0
+ {reg_sw_stall_procpu_c1[5:0] reg_sw_stall_procpu_c0[1:0]} == 0x86 will stall PRO CPU
+ 2
+ 2
+ read-write
+
+
+ SW_APPCPU_RST
+ APP CPU SW reset
+ 4
+ 1
+ write-only
+
+
+ SW_PROCPU_RST
+ PRO CPU SW reset
+ 5
+ 1
+ write-only
+
+
+ BB_I2C_FORCE_PD
+ BB_I2C force power down
+ 6
+ 1
+ read-write
+
+
+ BB_I2C_FORCE_PU
+ BB_I2C force power up
+ 7
+ 1
+ read-write
+
+
+ BBPLL_I2C_FORCE_PD
+ BB_PLL _I2C force power down
+ 8
+ 1
+ read-write
+
+
+ BBPLL_I2C_FORCE_PU
+ BB_PLL_I2C force power up
+ 9
+ 1
+ read-write
+
+
+ BBPLL_FORCE_PD
+ BB_PLL force power down
+ 10
+ 1
+ read-write
+
+
+ BBPLL_FORCE_PU
+ BB_PLL force power up
+ 11
+ 1
+ read-write
+
+
+ XTL_FORCE_PD
+ crystall force power down
+ 12
+ 1
+ read-write
+
+
+ XTL_FORCE_PU
+ crystall force power up
+ 13
+ 1
+ read-write
+
+
+ BIAS_SLEEP_FOLW_8M
+ BIAS_SLEEP follow CK8M
+ 14
+ 1
+ read-write
+
+
+ BIAS_FORCE_SLEEP
+ BIAS_SLEEP force sleep
+ 15
+ 1
+ read-write
+
+
+ BIAS_FORCE_NOSLEEP
+ BIAS_SLEEP force no sleep
+ 16
+ 1
+ read-write
+
+
+ BIAS_I2C_FOLW_8M
+ BIAS_I2C follow CK8M
+ 17
+ 1
+ read-write
+
+
+ BIAS_I2C_FORCE_PD
+ BIAS_I2C force power down
+ 18
+ 1
+ read-write
+
+
+ BIAS_I2C_FORCE_PU
+ BIAS_I2C force power up
+ 19
+ 1
+ read-write
+
+
+ BIAS_CORE_FOLW_8M
+ BIAS_CORE follow CK8M
+ 20
+ 1
+ read-write
+
+
+ BIAS_CORE_FORCE_PD
+ BIAS_CORE force power down
+ 21
+ 1
+ read-write
+
+
+ BIAS_CORE_FORCE_PU
+ BIAS_CORE force power up
+ 22
+ 1
+ read-write
+
+
+ XTL_FORCE_ISO
+ 23
+ 1
+ read-write
+
+
+ PLL_FORCE_ISO
+ 24
+ 1
+ read-write
+
+
+ ANALOG_FORCE_ISO
+ 25
+ 1
+ read-write
+
+
+ XTL_FORCE_NOISO
+ 26
+ 1
+ read-write
+
+
+ PLL_FORCE_NOISO
+ 27
+ 1
+ read-write
+
+
+ ANALOG_FORCE_NOISO
+ 28
+ 1
+ read-write
+
+
+ DG_WRAP_FORCE_RST
+ digital wrap force reset in deep sleep
+ 29
+ 1
+ read-write
+
+
+ DG_WRAP_FORCE_NORST
+ digital core force no reset in deep sleep
+ 30
+ 1
+ read-write
+
+
+ SW_SYS_RST
+ SW system reset
+ 31
+ 1
+ write-only
+
+
+
+
+ SLP_TIMER0
+ 0x4
+ 0x20
+
+
+ SLP_VAL_LO
+ RTC sleep timer low 32 bits
+ 0
+ 32
+ read-write
+
+
+
+
+ SLP_TIMER1
+ 0x8
+ 0x20
+
+
+ SLP_VAL_HI
+ RTC sleep timer high 16 bits
+ 0
+ 16
+ read-write
+
+
+ MAIN_TIMER_ALARM_EN
+ timer alarm enable bit
+ 16
+ 1
+ read-write
+
+
+
+
+ TIME_UPDATE
+ 0xC
+ 0x20
+
+
+ TIME_VALID
+ To indicate the register is updated
+ 30
+ 1
+ read-only
+
+
+ TIME_UPDATE
+ Set 1: to update register with RTC timer
+ 31
+ 1
+ write-only
+
+
+
+
+ TIME0
+ 0x10
+ 0x20
+
+
+ TIME_LO
+ RTC timer low 32 bits
+ 0
+ 32
+ read-only
+
+
+
+
+ TIME1
+ 0x14
+ 0x20
+
+
+ TIME_HI
+ RTC timer high 16 bits
+ 0
+ 16
+ read-only
+
+
+
+
+ STATE0
+ 0x18
+ 0x20
+ 0x00300000
+
+
+ TOUCH_WAKEUP_FORCE_EN
+ touch controller force wake up
+ 20
+ 1
+ read-write
+
+
+ ULP_CP_WAKEUP_FORCE_EN
+ ULP-coprocessor force wake up
+ 21
+ 1
+ read-write
+
+
+ APB2RTC_BRIDGE_SEL
+ 1: APB to RTC using bridge 0: APB to RTC using sync
+ 22
+ 1
+ read-write
+
+
+ TOUCH_SLP_TIMER_EN
+ touch timer enable bit
+ 23
+ 1
+ read-write
+
+
+ ULP_CP_SLP_TIMER_EN
+ ULP-coprocessor timer enable bit
+ 24
+ 1
+ read-write
+
+
+ SDIO_ACTIVE_IND
+ SDIO active indication
+ 28
+ 1
+ read-only
+
+
+ SLP_WAKEUP
+ sleep wakeup bit
+ 29
+ 1
+ read-write
+
+
+ SLP_REJECT
+ sleep reject bit
+ 30
+ 1
+ read-write
+
+
+ SLEEP_EN
+ sleep enable bit
+ 31
+ 1
+ read-write
+
+
+
+
+ TIMER1
+ 0x1C
+ 0x20
+ 0x28140403
+
+
+ CPU_STALL_EN
+ CPU stall enable bit
+ 0
+ 1
+ read-write
+
+
+ CPU_STALL_WAIT
+ CPU stall wait cycles in fast_clk_rtc
+ 1
+ 5
+ read-write
+
+
+ CK8M_WAIT
+ CK8M wait cycles in slow_clk_rtc
+ 6
+ 8
+ read-write
+
+
+ XTL_BUF_WAIT
+ XTAL wait cycles in slow_clk_rtc
+ 14
+ 10
+ read-write
+
+
+ PLL_BUF_WAIT
+ PLL wait cycles in slow_clk_rtc
+ 24
+ 8
+ read-write
+
+
+
+
+ TIMER2
+ 0x20
+ 0x20
+ 0x01080000
+
+
+ ULPCP_TOUCH_START_WAIT
+ wait cycles in slow_clk_rtc before ULP-coprocessor / touch controller start to work
+ 15
+ 9
+ read-write
+
+
+ MIN_TIME_CK8M_OFF
+ minimal cycles in slow_clk_rtc for CK8M in power down state
+ 24
+ 8
+ read-write
+
+
+
+
+ TIMER3
+ 0x24
+ 0x20
+ 0x14160A08
+
+
+ WIFI_WAIT_TIMER
+ 0
+ 9
+ read-write
+
+
+ WIFI_POWERUP_TIMER
+ 9
+ 7
+ read-write
+
+
+ ROM_RAM_WAIT_TIMER
+ 16
+ 9
+ read-write
+
+
+ ROM_RAM_POWERUP_TIMER
+ 25
+ 7
+ read-write
+
+
+
+
+ TIMER4
+ 0x28
+ 0x20
+ 0x10200A08
+
+
+ WAIT_TIMER
+ 0
+ 9
+ read-write
+
+
+ POWERUP_TIMER
+ 9
+ 7
+ read-write
+
+
+ DG_WRAP_WAIT_TIMER
+ 16
+ 9
+ read-write
+
+
+ DG_WRAP_POWERUP_TIMER
+ 25
+ 7
+ read-write
+
+
+
+
+ TIMER5
+ 0x2C
+ 0x20
+ 0x12148001
+
+
+ ULP_CP_SUBTIMER_PREDIV
+ 0
+ 8
+ read-write
+
+
+ MIN_SLP_VAL
+ minimal sleep cycles in slow_clk_rtc
+ 8
+ 8
+ read-write
+
+
+ RTCMEM_WAIT_TIMER
+ 16
+ 9
+ read-write
+
+
+ RTCMEM_POWERUP_TIMER
+ 25
+ 7
+ read-write
+
+
+
+
+ ANA_CONF
+ 0x30
+ 0x20
+ 0x00800000
+
+
+ PLLA_FORCE_PD
+ PLLA force power down
+ 23
+ 1
+ read-write
+
+
+ PLLA_FORCE_PU
+ PLLA force power up
+ 24
+ 1
+ read-write
+
+
+ BBPLL_CAL_SLP_START
+ start BBPLL calibration during sleep
+ 25
+ 1
+ read-write
+
+
+ PVTMON_PU
+ 1: PVTMON power up otherwise power down
+ 26
+ 1
+ read-write
+
+
+ TXRF_I2C_PU
+ 1: TXRF_I2C power up otherwise power down
+ 27
+ 1
+ read-write
+
+
+ RFRX_PBUS_PU
+ 1: RFRX_PBUS power up otherwise power down
+ 28
+ 1
+ read-write
+
+
+ CKGEN_I2C_PU
+ 1: CKGEN_I2C power up otherwise power down
+ 30
+ 1
+ read-write
+
+
+ PLL_I2C_PU
+ 1: PLL_I2C power up otherwise power down
+ 31
+ 1
+ read-write
+
+
+
+
+ RESET_STATE
+ 0x34
+ 0x20
+ 0x00003000
+
+
+ RESET_CAUSE_PROCPU
+ reset cause of PRO CPU
+ 0
+ 6
+ read-only
+
+
+ RESET_CAUSE_APPCPU
+ reset cause of APP CPU
+ 6
+ 6
+ read-only
+
+
+ APPCPU_STAT_VECTOR_SEL
+ APP CPU state vector sel
+ 12
+ 1
+ read-write
+
+
+ PROCPU_STAT_VECTOR_SEL
+ PRO CPU state vector sel
+ 13
+ 1
+ read-write
+
+
+
+
+ WAKEUP_STATE
+ 0x38
+ 0x20
+ 0x00006000
+
+
+ WAKEUP_CAUSE
+ wakeup cause
+ 0
+ 11
+ read-only
+
+
+ WAKEUP_ENA
+ wakeup enable bitmap
+ 11
+ 11
+ read-write
+
+
+ GPIO_WAKEUP_FILTER
+ enable filter for gpio wakeup event
+ 22
+ 1
+ read-write
+
+
+
+
+ INT_ENA
+ 0x3C
+ 0x20
+
+
+ SLP_WAKEUP_INT_ENA
+ enable sleep wakeup interrupt
+ 0
+ 1
+ read-write
+
+
+ SLP_REJECT_INT_ENA
+ enable sleep reject interrupt
+ 1
+ 1
+ read-write
+
+
+ SDIO_IDLE_INT_ENA
+ enable SDIO idle interrupt
+ 2
+ 1
+ read-write
+
+
+ WDT_INT_ENA
+ enable RTC WDT interrupt
+ 3
+ 1
+ read-write
+
+
+ TIME_VALID_INT_ENA
+ enable RTC time valid interrupt
+ 4
+ 1
+ read-write
+
+
+ ULP_CP_INT_ENA
+ enable ULP-coprocessor interrupt
+ 5
+ 1
+ read-write
+
+
+ TOUCH_INT_ENA
+ enable touch interrupt
+ 6
+ 1
+ read-write
+
+
+ BROWN_OUT_INT_ENA
+ enable brown out interrupt
+ 7
+ 1
+ read-write
+
+
+ MAIN_TIMER_INT_ENA
+ enable RTC main timer interrupt
+ 8
+ 1
+ read-write
+
+
+
+
+ INT_RAW
+ 0x40
+ 0x20
+
+
+ SLP_WAKEUP_INT_RAW
+ sleep wakeup interrupt raw
+ 0
+ 1
+ read-only
+
+
+ SLP_REJECT_INT_RAW
+ sleep reject interrupt raw
+ 1
+ 1
+ read-only
+
+
+ SDIO_IDLE_INT_RAW
+ SDIO idle interrupt raw
+ 2
+ 1
+ read-only
+
+
+ WDT_INT_RAW
+ RTC WDT interrupt raw
+ 3
+ 1
+ read-only
+
+
+ TIME_VALID_INT_RAW
+ RTC time valid interrupt raw
+ 4
+ 1
+ read-only
+
+
+ ULP_CP_INT_RAW
+ ULP-coprocessor interrupt raw
+ 5
+ 1
+ read-only
+
+
+ TOUCH_INT_RAW
+ touch interrupt raw
+ 6
+ 1
+ read-only
+
+
+ BROWN_OUT_INT_RAW
+ brown out interrupt raw
+ 7
+ 1
+ read-only
+
+
+ MAIN_TIMER_INT_RAW
+ RTC main timer interrupt raw
+ 8
+ 1
+ read-only
+
+
+
+
+ INT_ST
+ 0x44
+ 0x20
+
+
+ SLP_WAKEUP_INT_ST
+ sleep wakeup interrupt state
+ 0
+ 1
+ read-only
+
+
+ SLP_REJECT_INT_ST
+ sleep reject interrupt state
+ 1
+ 1
+ read-only
+
+
+ SDIO_IDLE_INT_ST
+ SDIO idle interrupt state
+ 2
+ 1
+ read-only
+
+
+ WDT_INT_ST
+ RTC WDT interrupt state
+ 3
+ 1
+ read-only
+
+
+ TIME_VALID_INT_ST
+ RTC time valid interrupt state
+ 4
+ 1
+ read-only
+
+
+ SAR_INT_ST
+ ULP-coprocessor interrupt state
+ 5
+ 1
+ read-only
+
+
+ TOUCH_INT_ST
+ touch interrupt state
+ 6
+ 1
+ read-only
+
+
+ BROWN_OUT_INT_ST
+ brown out interrupt state
+ 7
+ 1
+ read-only
+
+
+ MAIN_TIMER_INT_ST
+ RTC main timer interrupt state
+ 8
+ 1
+ read-only
+
+
+
+
+ INT_CLR
+ 0x48
+ 0x20
+
+
+ SLP_WAKEUP_INT_CLR
+ Clear sleep wakeup interrupt state
+ 0
+ 1
+ write-only
+
+
+ SLP_REJECT_INT_CLR
+ Clear sleep reject interrupt state
+ 1
+ 1
+ write-only
+
+
+ SDIO_IDLE_INT_CLR
+ Clear SDIO idle interrupt state
+ 2
+ 1
+ write-only
+
+
+ WDT_INT_CLR
+ Clear RTC WDT interrupt state
+ 3
+ 1
+ write-only
+
+
+ TIME_VALID_INT_CLR
+ Clear RTC time valid interrupt state
+ 4
+ 1
+ write-only
+
+
+ SAR_INT_CLR
+ Clear ULP-coprocessor interrupt state
+ 5
+ 1
+ write-only
+
+
+ TOUCH_INT_CLR
+ Clear touch interrupt state
+ 6
+ 1
+ write-only
+
+
+ BROWN_OUT_INT_CLR
+ Clear brown out interrupt state
+ 7
+ 1
+ write-only
+
+
+ MAIN_TIMER_INT_CLR
+ Clear RTC main timer interrupt state
+ 8
+ 1
+ write-only
+
+
+
+
+ STORE0
+ 0x4C
+ 0x20
+
+
+ SCRATCH0
+ 32-bit general purpose retention register
+ 0
+ 32
+ read-write
+
+
+
+
+ STORE1
+ 0x50
+ 0x20
+
+
+ SCRATCH1
+ 32-bit general purpose retention register
+ 0
+ 32
+ read-write
+
+
+
+
+ STORE2
+ 0x54
+ 0x20
+
+
+ SCRATCH2
+ 32-bit general purpose retention register
+ 0
+ 32
+ read-write
+
+
+
+
+ STORE3
+ 0x58
+ 0x20
+
+
+ SCRATCH3
+ 32-bit general purpose retention register
+ 0
+ 32
+ read-write
+
+
+
+
+ EXT_XTL_CONF
+ 0x5C
+ 0x20
+
+
+ XTL_EXT_CTR_LV
+ 0: power down XTAL at high level 1: power down XTAL at low level
+ 30
+ 1
+ read-write
+
+
+ XTL_EXT_CTR_EN
+ enable control XTAL by external pads
+ 31
+ 1
+ read-write
+
+
+
+
+ EXT_WAKEUP_CONF
+ 0x60
+ 0x20
+
+
+ EXT_WAKEUP0_LV
+ 0: external wakeup at low level 1: external wakeup at high level
+ 30
+ 1
+ read-write
+
+
+ EXT_WAKEUP1_LV
+ 0: external wakeup at low level 1: external wakeup at high level
+ 31
+ 1
+ read-write
+
+
+
+
+ SLP_REJECT_CONF
+ 0x64
+ 0x20
+
+
+ GPIO_REJECT_EN
+ enable GPIO reject
+ 24
+ 1
+ read-write
+
+
+ SDIO_REJECT_EN
+ enable SDIO reject
+ 25
+ 1
+ read-write
+
+
+ LIGHT_SLP_REJECT_EN
+ enable reject for light sleep
+ 26
+ 1
+ read-write
+
+
+ DEEP_SLP_REJECT_EN
+ enable reject for deep sleep
+ 27
+ 1
+ read-write
+
+
+ REJECT_CAUSE
+ sleep reject cause
+ 28
+ 4
+ read-only
+
+
+
+
+ CPU_PERIOD_CONF
+ 0x68
+ 0x20
+
+
+ CPUSEL_CONF
+ CPU sel option
+ 29
+ 1
+ read-write
+
+
+ CPUPERIOD_SEL
+ CPU period sel
+ 30
+ 2
+ read-write
+
+
+
+
+ SDIO_ACT_CONF
+ 0x6C
+ 0x20
+
+
+ SDIO_ACT_DNUM
+ 22
+ 10
+ read-write
+
+
+
+
+ CLK_CONF
+ 0x70
+ 0x20
+ 0x00002210
+
+
+ CK8M_DIV
+ CK8M_D256_OUT divider. 00: div128 01: div256 10: div512 11: div1024.
+ 4
+ 2
+ read-write
+
+ CK8M_DIV
+ read-write
+
+ DIV128
+ DIV128
+ 0
+
+
+ DIV256
+ DIV256
+ 1
+
+
+ DIV512
+ DIV512
+ 2
+
+
+ DIV1024
+ DIV1024
+ 3
+
+
+
+
+ ENB_CK8M
+ disable CK8M and CK8M_D256_OUT
+ 6
+ 1
+ read-write
+
+
+ ENB_CK8M_DIV
+ 1: CK8M_D256_OUT is actually CK8M 0: CK8M_D256_OUT is CK8M divided by 256
+ 7
+ 1
+ read-write
+
+ ENB_CK8M_DIV
+ read-write
+
+ CK8M_DIV_256
+ CK8M_DIV_256
+ 0
+
+
+ CK8M
+ CK8M
+ 1
+
+
+
+
+ DIG_XTAL32K_EN
+ enable CK_XTAL_32K for digital core (no relationship with RTC core)
+ 8
+ 1
+ read-write
+
+
+ DIG_CLK8M_D256_EN
+ enable CK8M_D256_OUT for digital core (no relationship with RTC core)
+ 9
+ 1
+ read-write
+
+
+ DIG_CLK8M_EN
+ enable CK8M for digital core (no relationship with RTC core)
+ 10
+ 1
+ read-write
+
+
+ CK8M_DFREQ_FORCE
+ 11
+ 1
+ read-write
+
+
+ CK8M_DIV_SEL
+ divider = reg_ck8m_div_sel + 1
+ 12
+ 3
+ read-write
+
+
+ XTAL_FORCE_NOGATING
+ XTAL force no gating during sleep
+ 15
+ 1
+ read-write
+
+
+ CK8M_FORCE_NOGATING
+ CK8M force no gating during sleep
+ 16
+ 1
+ read-write
+
+
+ CK8M_DFREQ
+ CK8M_DFREQ
+ 17
+ 8
+ read-write
+
+
+ CK8M_FORCE_PD
+ CK8M force power down
+ 25
+ 1
+ read-write
+
+
+ CK8M_FORCE_PU
+ CK8M force power up
+ 26
+ 1
+ read-write
+
+
+ SOC_CLK_SEL
+ SOC clock sel. 0: XTAL 1: PLL 2: CK8M 3: APLL
+ 27
+ 2
+ read-write
+
+ SOC_CLK_SEL
+ read-write
+
+ XTAL
+ XTAL
+ 0
+
+
+ PLL
+ PLL
+ 1
+
+
+ CK8M
+ CK8M
+ 2
+
+
+ APLL
+ APLL
+ 3
+
+
+
+
+ FAST_CLK_RTC_SEL
+ fast_clk_rtc sel. 0: XTAL div 4 1: CK8M
+ 29
+ 1
+ read-write
+
+ FAST_CLK_RTC_SEL
+ read-write
+
+ XTAL_DIV_4
+ XTAL_DIV_4
+ 0
+
+
+ CK8M
+ CK8M
+ 1
+
+
+
+
+ ANA_CLK_RTC_SEL
+ slow_clk_rtc sel. 0: SLOW_CK 1: CK_XTAL_32K 2: CK8M_D256_OUT
+ 30
+ 2
+ read-write
+
+ ANA_CLK_RTC_SEL
+ read-write
+
+ SLOW_CK
+ SLOW_CK
+ 0
+
+
+ CK_XTAL_32K
+ CK_XTAL_32K
+ 1
+
+
+ CK8M_D256_OUT
+ CK8M_D256_OUT
+ 2
+
+
+
+
+
+
+ SDIO_CONF
+ 0x74
+ 0x20
+ 0x02A00000
+
+
+ SDIO_PD_EN
+ power down SDIO_REG in sleep. Only active when reg_sdio_force = 0
+ 21
+ 1
+ read-write
+
+
+ SDIO_FORCE
+ 1: use SW option to control SDIO_REG 0: use state machine
+ 22
+ 1
+ read-write
+
+
+ SDIO_TIEH
+ SW option for SDIO_TIEH. Only active when reg_sdio_force = 1
+ 23
+ 1
+ read-write
+
+
+ REG1P8_READY
+ read only register for REG1P8_READY
+ 24
+ 1
+ read-only
+
+
+ DREFL_SDIO
+ SW option for DREFL_SDIO. Only active when reg_sdio_force = 1
+ 25
+ 2
+ read-write
+
+
+ DREFM_SDIO
+ SW option for DREFM_SDIO. Only active when reg_sdio_force = 1
+ 27
+ 2
+ read-write
+
+
+ DREFH_SDIO
+ SW option for DREFH_SDIO. Only active when reg_sdio_force = 1
+ 29
+ 2
+ read-write
+
+
+ XPD_SDIO
+ SW option for XPD_SDIO_REG. Only active when reg_sdio_force = 1
+ 31
+ 1
+ read-write
+
+
+
+
+ BIAS_CONF
+ 0x78
+ 0x20
+
+
+ DBG_ATTEN
+ DBG_ATTEN
+ 24
+ 2
+ read-write
+
+
+ ENB_SCK_XTAL
+ ENB_SCK_XTAL
+ 26
+ 1
+ read-write
+
+
+ INC_HEARTBEAT_REFRESH
+ INC_HEARTBEAT_REFRESH
+ 27
+ 1
+ read-write
+
+
+ DEC_HEARTBEAT_PERIOD
+ DEC_HEARTBEAT_PERIOD
+ 28
+ 1
+ read-write
+
+
+ INC_HEARTBEAT_PERIOD
+ INC_HEARTBEAT_PERIOD
+ 29
+ 1
+ read-write
+
+
+ DEC_HEARTBEAT_WIDTH
+ DEC_HEARTBEAT_WIDTH
+ 30
+ 1
+ read-write
+
+
+ RST_BIAS_I2C
+ RST_BIAS_I2C
+ 31
+ 1
+ read-write
+
+
+
+
+ REG
+ 0x7C
+ 0x20
+ 0x29002400
+
+
+ SCK_DCAP_FORCE
+ N/A
+ 7
+ 1
+ read-write
+
+
+ DIG_DBIAS_SLP
+ DIG_REG_DBIAS during sleep
+ 8
+ 3
+ read-write
+
+
+ DIG_DBIAS_WAK
+ DIG_REG_DBIAS during wakeup
+ 11
+ 3
+ read-write
+
+
+ SCK_DCAP
+ SCK_DCAP
+ 14
+ 8
+ read-write
+
+
+ DBIAS_SLP
+ RTC_DBIAS during sleep
+ 22
+ 3
+ read-write
+
+
+ DBIAS_WAK
+ RTC_DBIAS during wakeup
+ 25
+ 3
+ read-write
+
+
+ DBOOST_FORCE_PD
+ RTC_DBOOST force power down
+ 28
+ 1
+ read-write
+
+
+ DBOOST_FORCE_PU
+ RTC_DBOOST force power up
+ 29
+ 1
+ read-write
+
+
+ FORCE_PD
+ RTC_REG force power down (for RTC_REG power down means decrease the voltage to 0.8v or lower )
+ 30
+ 1
+ read-write
+
+
+ FORCE_PU
+ RTC_REG force power up
+ 31
+ 1
+ read-write
+
+
+
+
+ PWC
+ 0x80
+ 0x20
+ 0x00012925
+
+
+ FASTMEM_FORCE_NOISO
+ Fast RTC memory force no ISO
+ 0
+ 1
+ read-write
+
+
+ FASTMEM_FORCE_ISO
+ Fast RTC memory force ISO
+ 1
+ 1
+ read-write
+
+
+ SLOWMEM_FORCE_NOISO
+ RTC memory force no ISO
+ 2
+ 1
+ read-write
+
+
+ SLOWMEM_FORCE_ISO
+ RTC memory force ISO
+ 3
+ 1
+ read-write
+
+
+ FORCE_ISO
+ rtc_peri force ISO
+ 4
+ 1
+ read-write
+
+
+ FORCE_NOISO
+ rtc_peri force no ISO
+ 5
+ 1
+ read-write
+
+
+ FASTMEM_FOLW_CPU
+ 1: Fast RTC memory PD following CPU 0: fast RTC memory PD following RTC state machine
+ 6
+ 1
+ read-write
+
+
+ FASTMEM_FORCE_LPD
+ Fast RTC memory force PD
+ 7
+ 1
+ read-write
+
+
+ FASTMEM_FORCE_LPU
+ Fast RTC memory force no PD
+ 8
+ 1
+ read-write
+
+
+ SLOWMEM_FOLW_CPU
+ 1: RTC memory PD following CPU 0: RTC memory PD following RTC state machine
+ 9
+ 1
+ read-write
+
+
+ SLOWMEM_FORCE_LPD
+ RTC memory force PD
+ 10
+ 1
+ read-write
+
+
+ SLOWMEM_FORCE_LPU
+ RTC memory force no PD
+ 11
+ 1
+ read-write
+
+
+ FASTMEM_FORCE_PD
+ Fast RTC memory force power down
+ 12
+ 1
+ read-write
+
+
+ FASTMEM_FORCE_PU
+ Fast RTC memory force power up
+ 13
+ 1
+ read-write
+
+
+ FASTMEM_PD_EN
+ enable power down fast RTC memory in sleep
+ 14
+ 1
+ read-write
+
+
+ SLOWMEM_FORCE_PD
+ RTC memory force power down
+ 15
+ 1
+ read-write
+
+
+ SLOWMEM_FORCE_PU
+ RTC memory force power up
+ 16
+ 1
+ read-write
+
+
+ SLOWMEM_PD_EN
+ enable power down RTC memory in sleep
+ 17
+ 1
+ read-write
+
+
+ FORCE_PD
+ rtc_peri force power down
+ 18
+ 1
+ read-write
+
+
+ FORCE_PU
+ rtc_peri force power up
+ 19
+ 1
+ read-write
+
+
+ PD_EN
+ enable power down rtc_peri in sleep
+ 20
+ 1
+ read-write
+
+
+
+
+ DIG_PWC
+ 0x84
+ 0x20
+ 0x00155550
+
+
+ LSLP_MEM_FORCE_PD
+ memories in digital core force PD in sleep
+ 3
+ 1
+ read-write
+
+
+ LSLP_MEM_FORCE_PU
+ memories in digital core force no PD in sleep
+ 4
+ 1
+ read-write
+
+
+ ROM0_FORCE_PD
+ ROM force power down
+ 5
+ 1
+ read-write
+
+
+ ROM0_FORCE_PU
+ ROM force power up
+ 6
+ 1
+ read-write
+
+
+ INTER_RAM0_FORCE_PD
+ internal SRAM 0 force power down
+ 7
+ 1
+ read-write
+
+
+ INTER_RAM0_FORCE_PU
+ internal SRAM 0 force power up
+ 8
+ 1
+ read-write
+
+
+ INTER_RAM1_FORCE_PD
+ internal SRAM 1 force power down
+ 9
+ 1
+ read-write
+
+
+ INTER_RAM1_FORCE_PU
+ internal SRAM 1 force power up
+ 10
+ 1
+ read-write
+
+
+ INTER_RAM2_FORCE_PD
+ internal SRAM 2 force power down
+ 11
+ 1
+ read-write
+
+
+ INTER_RAM2_FORCE_PU
+ internal SRAM 2 force power up
+ 12
+ 1
+ read-write
+
+
+ INTER_RAM3_FORCE_PD
+ internal SRAM 3 force power down
+ 13
+ 1
+ read-write
+
+
+ INTER_RAM3_FORCE_PU
+ internal SRAM 3 force power up
+ 14
+ 1
+ read-write
+
+
+ INTER_RAM4_FORCE_PD
+ internal SRAM 4 force power down
+ 15
+ 1
+ read-write
+
+
+ INTER_RAM4_FORCE_PU
+ internal SRAM 4 force power up
+ 16
+ 1
+ read-write
+
+
+ WIFI_FORCE_PD
+ wifi force power down
+ 17
+ 1
+ read-write
+
+
+ WIFI_FORCE_PU
+ wifi force power up
+ 18
+ 1
+ read-write
+
+
+ DG_WRAP_FORCE_PD
+ digital core force power down
+ 19
+ 1
+ read-write
+
+
+ DG_WRAP_FORCE_PU
+ digital core force power up
+ 20
+ 1
+ read-write
+
+
+ ROM0_PD_EN
+ enable power down ROM in sleep
+ 24
+ 1
+ read-write
+
+
+ INTER_RAM0_PD_EN
+ enable power down internal SRAM 0 in sleep
+ 25
+ 1
+ read-write
+
+
+ INTER_RAM1_PD_EN
+ enable power down internal SRAM 1 in sleep
+ 26
+ 1
+ read-write
+
+
+ INTER_RAM2_PD_EN
+ enable power down internal SRAM 2 in sleep
+ 27
+ 1
+ read-write
+
+
+ INTER_RAM3_PD_EN
+ enable power down internal SRAM 3 in sleep
+ 28
+ 1
+ read-write
+
+
+ INTER_RAM4_PD_EN
+ enable power down internal SRAM 4 in sleep
+ 29
+ 1
+ read-write
+
+
+ WIFI_PD_EN
+ enable power down wifi in sleep
+ 30
+ 1
+ read-write
+
+
+ DG_WRAP_PD_EN
+ enable power down digital core in sleep
+ 31
+ 1
+ read-write
+
+
+
+
+ DIG_ISO
+ 0x88
+ 0x20
+ 0xAAAA5000
+
+
+ FORCE_OFF
+ 7
+ 1
+ read-write
+
+
+ FORCE_ON
+ 8
+ 1
+ read-write
+
+
+ DG_PAD_AUTOHOLD
+ read only register to indicate digital pad auto-hold status
+ 9
+ 1
+ read-only
+
+
+ CLR_DG_PAD_AUTOHOLD
+ wtite only register to clear digital pad auto-hold
+ 10
+ 1
+ write-only
+
+
+ DG_PAD_AUTOHOLD_EN
+ digital pad enable auto-hold
+ 11
+ 1
+ read-write
+
+
+ DG_PAD_FORCE_NOISO
+ digital pad force no ISO
+ 12
+ 1
+ read-write
+
+
+ DG_PAD_FORCE_ISO
+ digital pad force ISO
+ 13
+ 1
+ read-write
+
+
+ DG_PAD_FORCE_UNHOLD
+ digital pad force un-hold
+ 14
+ 1
+ read-write
+
+
+ DG_PAD_FORCE_HOLD
+ digital pad force hold
+ 15
+ 1
+ read-write
+
+
+ ROM0_FORCE_ISO
+ ROM force ISO
+ 16
+ 1
+ read-write
+
+
+ ROM0_FORCE_NOISO
+ ROM force no ISO
+ 17
+ 1
+ read-write
+
+
+ INTER_RAM0_FORCE_ISO
+ internal SRAM 0 force ISO
+ 18
+ 1
+ read-write
+
+
+ INTER_RAM0_FORCE_NOISO
+ internal SRAM 0 force no ISO
+ 19
+ 1
+ read-write
+
+
+ INTER_RAM1_FORCE_ISO
+ internal SRAM 1 force ISO
+ 20
+ 1
+ read-write
+
+
+ INTER_RAM1_FORCE_NOISO
+ internal SRAM 1 force no ISO
+ 21
+ 1
+ read-write
+
+
+ INTER_RAM2_FORCE_ISO
+ internal SRAM 2 force ISO
+ 22
+ 1
+ read-write
+
+
+ INTER_RAM2_FORCE_NOISO
+ internal SRAM 2 force no ISO
+ 23
+ 1
+ read-write
+
+
+ INTER_RAM3_FORCE_ISO
+ internal SRAM 3 force ISO
+ 24
+ 1
+ read-write
+
+
+ INTER_RAM3_FORCE_NOISO
+ internal SRAM 3 force no ISO
+ 25
+ 1
+ read-write
+
+
+ INTER_RAM4_FORCE_ISO
+ internal SRAM 4 force ISO
+ 26
+ 1
+ read-write
+
+
+ INTER_RAM4_FORCE_NOISO
+ internal SRAM 4 force no ISO
+ 27
+ 1
+ read-write
+
+
+ WIFI_FORCE_ISO
+ wifi force ISO
+ 28
+ 1
+ read-write
+
+
+ WIFI_FORCE_NOISO
+ wifi force no ISO
+ 29
+ 1
+ read-write
+
+
+ DG_WRAP_FORCE_ISO
+ digital core force ISO
+ 30
+ 1
+ read-write
+
+
+ DG_WRAP_FORCE_NOISO
+ digital core force no ISO
+ 31
+ 1
+ read-write
+
+
+
+
+ WDTCONFIG0
+ 0x8C
+ 0x20
+ 0x00004C80
+
+
+ WDT_PAUSE_IN_SLP
+ pause WDT in sleep
+ 7
+ 1
+ read-write
+
+
+ WDT_APPCPU_RESET_EN
+ enable WDT reset APP CPU
+ 8
+ 1
+ read-write
+
+
+ WDT_PROCPU_RESET_EN
+ enable WDT reset PRO CPU
+ 9
+ 1
+ read-write
+
+
+ WDT_FLASHBOOT_MOD_EN
+ enable WDT in flash boot
+ 10
+ 1
+ read-write
+
+
+ WDT_SYS_RESET_LENGTH
+ system reset counter length
+ 11
+ 3
+ read-write
+
+
+ WDT_CPU_RESET_LENGTH
+ CPU reset counter length
+ 14
+ 3
+ read-write
+
+
+ WDT_LEVEL_INT_EN
+ N/A
+ 17
+ 1
+ read-write
+
+
+ WDT_EDGE_INT_EN
+ N/A
+ 18
+ 1
+ read-write
+
+
+ WDT_STG3
+ 1: interrupt stage en 2: CPU reset stage en 3: system reset stage en 4: RTC reset stage en
+ 19
+ 3
+ read-write
+
+
+ WDT_STG2
+ 1: interrupt stage en 2: CPU reset stage en 3: system reset stage en 4: RTC reset stage en
+ 22
+ 3
+ read-write
+
+
+ WDT_STG1
+ 1: interrupt stage en 2: CPU reset stage en 3: system reset stage en 4: RTC reset stage en
+ 25
+ 3
+ read-write
+
+
+ WDT_STG0
+ 1: interrupt stage en 2: CPU reset stage en 3: system reset stage en 4: RTC reset stage en
+ 28
+ 3
+ read-write
+
+
+ WDT_EN
+ enable RTC WDT
+ 31
+ 1
+ read-write
+
+
+
+
+ WDTCONFIG1
+ 0x90
+ 0x20
+ 0x0001F400
+
+
+ WDT_STG0_HOLD
+ 0
+ 32
+ read-write
+
+
+
+
+ WDTCONFIG2
+ 0x94
+ 0x20
+ 0x00013880
+
+
+ WDT_STG1_HOLD
+ 0
+ 32
+ read-write
+
+
+
+
+ WDTCONFIG3
+ 0x98
+ 0x20
+ 0x00000FFF
+
+
+ WDT_STG2_HOLD
+ 0
+ 32
+ read-write
+
+
+
+
+ WDTCONFIG4
+ 0x9C
+ 0x20
+ 0x00000FFF
+
+
+ WDT_STG3_HOLD
+ 0
+ 32
+ read-write
+
+
+
+
+ WDTFEED
+ 0xA0
+ 0x20
+
+
+ WDT_FEED
+ 31
+ 1
+ write-only
+
+
+
+
+ WDTWPROTECT
+ 0xA4
+ 0x20
+ 0x50D83AA1
+
+
+ WDT_WKEY
+ 0
+ 32
+ read-write
+
+
+
+
+ TEST_MUX
+ 0xA8
+ 0x20
+
+
+ ENT_RTC
+ ENT_RTC
+ 29
+ 1
+ read-write
+
+
+ DTEST_RTC
+ DTEST_RTC
+ 30
+ 2
+ read-write
+
+
+
+
+ SW_CPU_STALL
+ 0xAC
+ 0x20
+
+
+ SW_STALL_APPCPU_C1
+ {reg_sw_stall_appcpu_c1[5:0] reg_sw_stall_appcpu_c0[1:0]} == 0x86 will stall APP CPU
+ 20
+ 6
+ read-write
+
+
+ SW_STALL_PROCPU_C1
+ {reg_sw_stall_procpu_c1[5:0] reg_sw_stall_procpu_c0[1:0]} == 0x86 will stall PRO CPU
+ 26
+ 6
+ read-write
+
+
+
+
+ STORE4
+ 0xB0
+ 0x20
+
+
+ SCRATCH4
+ 32-bit general purpose retention register
+ 0
+ 32
+ read-write
+
+
+
+
+ STORE5
+ 0xB4
+ 0x20
+
+
+ SCRATCH5
+ 32-bit general purpose retention register
+ 0
+ 32
+ read-write
+
+
+
+
+ STORE6
+ 0xB8
+ 0x20
+
+
+ SCRATCH6
+ 32-bit general purpose retention register
+ 0
+ 32
+ read-write
+
+
+
+
+ STORE7
+ 0xBC
+ 0x20
+
+
+ SCRATCH7
+ 32-bit general purpose retention register
+ 0
+ 32
+ read-write
+
+
+
+
+ LOW_POWER_ST
+ 0xC0
+ 0x20
+
+
+ LOW_POWER_DIAG0
+ 0
+ 32
+ read-only
+
+
+ RDY_FOR_WAKEUP
+ 1 if RTC controller is ready to execute WAKE instruction, 0 otherwise
+ 19
+ 1
+ read-only
+
+
+
+
+ DIAG1
+ 0xC4
+ 0x20
+
+
+ LOW_POWER_DIAG1
+ 0
+ 32
+ read-only
+
+
+
+
+ HOLD_FORCE
+ 0xC8
+ 0x20
+
+
+ ADC1_HOLD_FORCE
+ 0
+ 1
+ read-write
+
+
+ ADC2_HOLD_FORCE
+ 1
+ 1
+ read-write
+
+
+ PDAC1_HOLD_FORCE
+ 2
+ 1
+ read-write
+
+
+ PDAC2_HOLD_FORCE
+ 3
+ 1
+ read-write
+
+
+ SENSE1_HOLD_FORCE
+ 4
+ 1
+ read-write
+
+
+ SENSE2_HOLD_FORCE
+ 5
+ 1
+ read-write
+
+
+ SENSE3_HOLD_FORCE
+ 6
+ 1
+ read-write
+
+
+ SENSE4_HOLD_FORCE
+ 7
+ 1
+ read-write
+
+
+ TOUCH_PAD0_HOLD_FORCE
+ 8
+ 1
+ read-write
+
+
+ TOUCH_PAD1_HOLD_FORCE
+ 9
+ 1
+ read-write
+
+
+ TOUCH_PAD2_HOLD_FORCE
+ 10
+ 1
+ read-write
+
+
+ TOUCH_PAD3_HOLD_FORCE
+ 11
+ 1
+ read-write
+
+
+ TOUCH_PAD4_HOLD_FORCE
+ 12
+ 1
+ read-write
+
+
+ TOUCH_PAD5_HOLD_FORCE
+ 13
+ 1
+ read-write
+
+
+ TOUCH_PAD6_HOLD_FORCE
+ 14
+ 1
+ read-write
+
+
+ TOUCH_PAD7_HOLD_FORCE
+ 15
+ 1
+ read-write
+
+
+ X32P_HOLD_FORCE
+ 16
+ 1
+ read-write
+
+
+ X32N_HOLD_FORCE
+ 17
+ 1
+ read-write
+
+
+
+
+ EXT_WAKEUP1
+ 0xCC
+ 0x20
+
+
+ SEL
+ Bitmap to select RTC pads for ext wakeup1
+ 0
+ 18
+ read-write
+
+
+ STATUS_CLR
+ clear ext wakeup1 status
+ 18
+ 1
+ write-only
+
+
+
+
+ EXT_WAKEUP1_STATUS
+ 0xD0
+ 0x20
+
+
+ EXT_WAKEUP1_STATUS
+ ext wakeup1 status
+ 0
+ 18
+ read-only
+
+
+
+
+ BROWN_OUT
+ 0xD4
+ 0x20
+ 0x13FF0000
+
+
+ RTC_MEM_PID_CONF
+ 0
+ 8
+ read-write
+
+
+ RTC_MEM_CRC_START
+ 8
+ 1
+ read-write
+
+
+ RTC_MEM_CRC_ADDR
+ 9
+ 11
+ read-write
+
+
+ CLOSE_FLASH_ENA
+ enable close flash when brown out happens
+ 14
+ 1
+ read-write
+
+
+ PD_RF_ENA
+ enable power down RF when brown out happens
+ 15
+ 1
+ read-write
+
+
+ RST_WAIT
+ brown out reset wait cycles
+ 16
+ 10
+ read-write
+
+
+ RTC_MEM_CRC_LEN
+ 20
+ 11
+ read-write
+
+
+ RST_ENA
+ enable brown out reset
+ 26
+ 1
+ read-write
+
+
+ DBROWN_OUT_THRES
+ brown out threshold
+ 27
+ 3
+ read-write
+
+
+ ENA
+ enable brown out
+ 30
+ 1
+ read-write
+
+
+ DET
+ brown out detect
+ 31
+ 1
+ read-only
+
+
+ RTC_MEM_CRC_FINISH
+ 31
+ 1
+ read-write
+
+
+
+
+ DATE
+ 0x13C
+ 0x20
+ 0x01604280
+
+
+ CNTL_DATE
+ 0
+ 28
+ read-write
+
+
+
+
+
+
+ RTCIO
+ Peripheral RTCIO
+ RTC_GPIO
+ 0x3FF48400
+
+ 0x0
+ 0xCC
+ registers
+
+
+
+ OUT
+ 0x0
+ 0x20
+
+
+ DATA
+ GPIO0~17 output value
+ 14
+ 18
+ read-write
+
+
+
+
+ OUT_W1TS
+ 0x4
+ 0x20
+
+
+ OUT_DATA_W1TS
+ GPIO0~17 output value write 1 to set
+ 14
+ 18
+ write-only
+
+
+
+
+ OUT_W1TC
+ 0x8
+ 0x20
+
+
+ OUT_DATA_W1TC
+ GPIO0~17 output value write 1 to clear
+ 14
+ 18
+ write-only
+
+
+
+
+ ENABLE
+ 0xC
+ 0x20
+
+
+ ENABLE
+ GPIO0~17 output enable
+ 14
+ 18
+ read-write
+
+
+
+
+ ENABLE_W1TS
+ 0x10
+ 0x20
+
+
+ ENABLE_W1TS
+ GPIO0~17 output enable write 1 to set
+ 14
+ 18
+ write-only
+
+
+
+
+ ENABLE_W1TC
+ 0x14
+ 0x20
+
+
+ ENABLE_W1TC
+ GPIO0~17 output enable write 1 to clear
+ 14
+ 18
+ write-only
+
+
+
+
+ STATUS
+ 0x18
+ 0x20
+
+
+ INT
+ GPIO0~17 interrupt status
+ 14
+ 18
+ read-write
+
+
+
+
+ STATUS_W1TS
+ 0x1C
+ 0x20
+
+
+ STATUS_INT_W1TS
+ GPIO0~17 interrupt status write 1 to set
+ 14
+ 18
+ write-only
+
+
+
+
+ STATUS_W1TC
+ 0x20
+ 0x20
+
+
+ STATUS_INT_W1TC
+ GPIO0~17 interrupt status write 1 to clear
+ 14
+ 18
+ write-only
+
+
+
+
+ IN
+ 0x24
+ 0x20
+
+
+ NEXT
+ GPIO0~17 input value
+ 14
+ 18
+ read-only
+
+
+
+
+ 18
+ 0x4
+ 0-17
+ PIN%s
+ 0x28
+ 0x20
+
+
+ PAD_DRIVER
+ if set to 0: normal output if set to 1: open drain
+ 2
+ 1
+ read-write
+
+
+ INT_TYPE
+ if set to 0: GPIO interrupt disable if set to 1: rising edge trigger if set to 2: falling edge trigger if set to 3: any edge trigger if set to 4: low level trigger if set to 5: high level trigger
+ 7
+ 3
+ read-write
+
+
+ WAKEUP_ENABLE
+ GPIO wake up enable only available in light sleep
+ 10
+ 1
+ read-write
+
+
+
+
+ RTC_DEBUG_SEL
+ 0x70
+ 0x20
+
+
+ DEBUG_SEL0
+ 0
+ 5
+ read-write
+
+
+ DEBUG_SEL1
+ 5
+ 5
+ read-write
+
+
+ DEBUG_SEL2
+ 10
+ 5
+ read-write
+
+
+ DEBUG_SEL3
+ 15
+ 5
+ read-write
+
+
+ DEBUG_SEL4
+ 20
+ 5
+ read-write
+
+
+ DEBUG_12M_NO_GATING
+ 25
+ 1
+ read-write
+
+
+
+
+ DIG_PAD_HOLD
+ 0x74
+ 0x20
+
+
+ DIG_PAD_HOLD
+ select the digital pad hold value.
+ 0
+ 32
+ read-write
+
+
+
+
+ HALL_SENS
+ 0x78
+ 0x20
+
+
+ HALL_PHASE
+ Reverse phase of hall sensor
+ 30
+ 1
+ read-write
+
+
+ XPD_HALL
+ Power on hall sensor and connect to VP and VN
+ 31
+ 1
+ read-write
+
+
+
+
+ SENSOR_PADS
+ 0x7C
+ 0x20
+
+
+ SENSE4_FUN_IE
+ the input enable of the pad
+ 4
+ 1
+ read-write
+
+
+ SENSE4_SLP_IE
+ the input enable of the pad in sleep status
+ 5
+ 1
+ read-write
+
+
+ SENSE4_SLP_SEL
+ the sleep status selection signal of the pad
+ 6
+ 1
+ read-write
+
+
+ SENSE4_FUN_SEL
+ the functional selection signal of the pad
+ 7
+ 2
+ read-write
+
+
+ SENSE3_FUN_IE
+ the input enable of the pad
+ 9
+ 1
+ read-write
+
+
+ SENSE3_SLP_IE
+ the input enable of the pad in sleep status
+ 10
+ 1
+ read-write
+
+
+ SENSE3_SLP_SEL
+ the sleep status selection signal of the pad
+ 11
+ 1
+ read-write
+
+
+ SENSE3_FUN_SEL
+ the functional selection signal of the pad
+ 12
+ 2
+ read-write
+
+
+ SENSE2_FUN_IE
+ the input enable of the pad
+ 14
+ 1
+ read-write
+
+
+ SENSE2_SLP_IE
+ the input enable of the pad in sleep status
+ 15
+ 1
+ read-write
+
+
+ SENSE2_SLP_SEL
+ the sleep status selection signal of the pad
+ 16
+ 1
+ read-write
+
+
+ SENSE2_FUN_SEL
+ the functional selection signal of the pad
+ 17
+ 2
+ read-write
+
+
+ SENSE1_FUN_IE
+ the input enable of the pad
+ 19
+ 1
+ read-write
+
+
+ SENSE1_SLP_IE
+ the input enable of the pad in sleep status
+ 20
+ 1
+ read-write
+
+
+ SENSE1_SLP_SEL
+ the sleep status selection signal of the pad
+ 21
+ 1
+ read-write
+
+
+ SENSE1_FUN_SEL
+ the functional selection signal of the pad
+ 22
+ 2
+ read-write
+
+
+ SENSE4_MUX_SEL
+ Ă’1Ă“ select the digital function Ă“0Ă“slection the rtc function
+ 24
+ 1
+ read-write
+
+
+ SENSE3_MUX_SEL
+ Ă’1Ă“ select the digital function Ă“0Ă“slection the rtc function
+ 25
+ 1
+ read-write
+
+
+ SENSE2_MUX_SEL
+ Ă’1Ă“ select the digital function Ă“0Ă“slection the rtc function
+ 26
+ 1
+ read-write
+
+
+ SENSE1_MUX_SEL
+ Ă’1Ă“ select the digital function Ă“0Ă“slection the rtc function
+ 27
+ 1
+ read-write
+
+
+ SENSE4_HOLD
+ hold the current value of the output when setting the hold to Ă’1Ă“
+ 28
+ 1
+ read-write
+
+
+ SENSE3_HOLD
+ hold the current value of the output when setting the hold to Ă’1Ă“
+ 29
+ 1
+ read-write
+
+
+ SENSE2_HOLD
+ hold the current value of the output when setting the hold to Ă’1Ă“
+ 30
+ 1
+ read-write
+
+
+ SENSE1_HOLD
+ hold the current value of the output when setting the hold to Ă’1Ă“
+ 31
+ 1
+ read-write
+
+
+
+
+ ADC_PAD
+ 0x80
+ 0x20
+
+
+ ADC2_FUN_IE
+ the input enable of the pad
+ 18
+ 1
+ read-write
+
+
+ ADC2_SLP_IE
+ the input enable of the pad in sleep status
+ 19
+ 1
+ read-write
+
+
+ ADC2_SLP_SEL
+ the sleep status selection signal of the pad
+ 20
+ 1
+ read-write
+
+
+ ADC2_FUN_SEL
+ the functional selection signal of the pad
+ 21
+ 2
+ read-write
+
+
+ ADC1_FUN_IE
+ the input enable of the pad
+ 23
+ 1
+ read-write
+
+
+ ADC1_SLP_IE
+ the input enable of the pad in sleep status
+ 24
+ 1
+ read-write
+
+
+ ADC1_SLP_SEL
+ the sleep status selection signal of the pad
+ 25
+ 1
+ read-write
+
+
+ ADC1_FUN_SEL
+ the functional selection signal of the pad
+ 26
+ 2
+ read-write
+
+
+ ADC2_MUX_SEL
+ Ă’1Ă“ select the digital function Ă“0Ă“slection the rtc function
+ 28
+ 1
+ read-write
+
+
+ ADC1_MUX_SEL
+ Ă’1Ă“ select the digital function Ă“0Ă“slection the rtc function
+ 29
+ 1
+ read-write
+
+
+ ADC2_HOLD
+ hold the current value of the output when setting the hold to Ă’1Ă“
+ 30
+ 1
+ read-write
+
+
+ ADC1_HOLD
+ hold the current value of the output when setting the hold to Ă’1Ă“
+ 31
+ 1
+ read-write
+
+
+
+
+ PAD_DAC1
+ 0x84
+ 0x20
+ 0x80000000
+
+
+ PDAC1_DAC_XPD_FORCE
+ Power on DAC1. Usually we need to tristate PDAC1 if we power on the DAC i.e. IE=0 OE=0 RDE=0 RUE=0
+ 10
+ 1
+ read-write
+
+
+ PDAC1_FUN_IE
+ the input enable of the pad
+ 11
+ 1
+ read-write
+
+
+ PDAC1_SLP_OE
+ the output enable of the pad in sleep status
+ 12
+ 1
+ read-write
+
+
+ PDAC1_SLP_IE
+ the input enable of the pad in sleep status
+ 13
+ 1
+ read-write
+
+
+ PDAC1_SLP_SEL
+ the sleep status selection signal of the pad
+ 14
+ 1
+ read-write
+
+
+ PDAC1_FUN_SEL
+ the functional selection signal of the pad
+ 15
+ 2
+ read-write
+
+
+ PDAC1_MUX_SEL
+ Ă’1Ă“ select the digital function Ă“0Ă“slection the rtc function
+ 17
+ 1
+ read-write
+
+
+ PDAC1_XPD_DAC
+ Power on DAC1. Usually we need to tristate PDAC1 if we power on the DAC i.e. IE=0 OE=0 RDE=0 RUE=0
+ 18
+ 1
+ read-write
+
+
+ PDAC1_DAC
+ PAD DAC1 control code.
+ 19
+ 8
+ read-write
+
+
+ PDAC1_RUE
+ the pull up enable of the pad
+ 27
+ 1
+ read-write
+
+
+ PDAC1_RDE
+ the pull down enable of the pad
+ 28
+ 1
+ read-write
+
+
+ PDAC1_HOLD
+ hold the current value of the output when setting the hold to Ă’1Ă“
+ 29
+ 1
+ read-write
+
+
+ PDAC1_DRV
+ the driver strength of the pad
+ 30
+ 2
+ read-write
+
+
+
+
+ PAD_DAC2
+ 0x88
+ 0x20
+ 0x80000000
+
+
+ PDAC2_DAC_XPD_FORCE
+ Power on DAC2. Usually we need to tristate PDAC2 if we power on the DAC i.e. IE=0 OE=0 RDE=0 RUE=0
+ 10
+ 1
+ read-write
+
+
+ PDAC2_FUN_IE
+ the input enable of the pad
+ 11
+ 1
+ read-write
+
+
+ PDAC2_SLP_OE
+ the output enable of the pad in sleep status
+ 12
+ 1
+ read-write
+
+
+ PDAC2_SLP_IE
+ the input enable of the pad in sleep status
+ 13
+ 1
+ read-write
+
+
+ PDAC2_SLP_SEL
+ the sleep status selection signal of the pad
+ 14
+ 1
+ read-write
+
+
+ PDAC2_FUN_SEL
+ the functional selection signal of the pad
+ 15
+ 2
+ read-write
+
+
+ PDAC2_MUX_SEL
+ Ă’1Ă“ select the digital function Ă“0Ă“slection the rtc function
+ 17
+ 1
+ read-write
+
+
+ PDAC2_XPD_DAC
+ Power on DAC2. Usually we need to tristate PDAC1 if we power on the DAC i.e. IE=0 OE=0 RDE=0 RUE=0
+ 18
+ 1
+ read-write
+
+
+ PDAC2_DAC
+ PAD DAC2 control code.
+ 19
+ 8
+ read-write
+
+
+ PDAC2_RUE
+ the pull up enable of the pad
+ 27
+ 1
+ read-write
+
+
+ PDAC2_RDE
+ the pull down enable of the pad
+ 28
+ 1
+ read-write
+
+
+ PDAC2_HOLD
+ hold the current value of the output when setting the hold to Ă’1Ă“
+ 29
+ 1
+ read-write
+
+
+ PDAC2_DRV
+ the driver strength of the pad
+ 30
+ 2
+ read-write
+
+
+
+
+ XTAL_32K_PAD
+ 0x8C
+ 0x20
+ 0x84100010
+
+
+ DBIAS_XTAL_32K
+ 32K XTAL self-bias reference control.
+ 1
+ 2
+ read-write
+
+
+ DRES_XTAL_32K
+ 32K XTAL resistor bias control.
+ 3
+ 2
+ read-write
+
+
+ X32P_FUN_IE
+ the input enable of the pad
+ 5
+ 1
+ read-write
+
+
+ X32P_SLP_OE
+ the output enable of the pad in sleep status
+ 6
+ 1
+ read-write
+
+
+ X32P_SLP_IE
+ the input enable of the pad in sleep status
+ 7
+ 1
+ read-write
+
+
+ X32P_SLP_SEL
+ the sleep status selection signal of the pad
+ 8
+ 1
+ read-write
+
+
+ X32P_FUN_SEL
+ the functional selection signal of the pad
+ 9
+ 2
+ read-write
+
+
+ X32N_FUN_IE
+ the input enable of the pad
+ 11
+ 1
+ read-write
+
+
+ X32N_SLP_OE
+ the output enable of the pad in sleep status
+ 12
+ 1
+ read-write
+
+
+ X32N_SLP_IE
+ the input enable of the pad in sleep status
+ 13
+ 1
+ read-write
+
+
+ X32N_SLP_SEL
+ the sleep status selection signal of the pad
+ 14
+ 1
+ read-write
+
+
+ X32N_FUN_SEL
+ the functional selection signal of the pad
+ 15
+ 2
+ read-write
+
+
+ X32P_MUX_SEL
+ Ă’1Ă“ select the digital function Ă“0Ă“slection the rtc function
+ 17
+ 1
+ read-write
+
+
+ X32N_MUX_SEL
+ Ă’1Ă“ select the digital function Ă“0Ă“slection the rtc function
+ 18
+ 1
+ read-write
+
+
+ XPD_XTAL_32K
+ Power up 32kHz crystal oscillator
+ 19
+ 1
+ read-write
+
+
+ DAC_XTAL_32K
+ 32K XTAL bias current DAC.
+ 20
+ 2
+ read-write
+
+
+ X32P_RUE
+ the pull up enable of the pad
+ 22
+ 1
+ read-write
+
+
+ X32P_RDE
+ the pull down enable of the pad
+ 23
+ 1
+ read-write
+
+
+ X32P_HOLD
+ hold the current value of the output when setting the hold to Ă’1Ă“
+ 24
+ 1
+ read-write
+
+
+ X32P_DRV
+ the driver strength of the pad
+ 25
+ 2
+ read-write
+
+
+ X32N_RUE
+ the pull up enable of the pad
+ 27
+ 1
+ read-write
+
+
+ X32N_RDE
+ the pull down enable of the pad
+ 28
+ 1
+ read-write
+
+
+ X32N_HOLD
+ hold the current value of the output when setting the hold to Ă’1Ă“
+ 29
+ 1
+ read-write
+
+
+ X32N_DRV
+ the driver strength of the pad
+ 30
+ 2
+ read-write
+
+
+
+
+ TOUCH_CFG
+ 0x90
+ 0x20
+ 0x66000000
+
+
+ TOUCH_DCUR
+ touch sensor bias current. Should have option to tie with BIAS_SLEEP(When BIAS_SLEEP this setting is available
+ 23
+ 2
+ read-write
+
+
+ TOUCH_DRANGE
+ touch sensor saw wave voltage range.
+ 25
+ 2
+ read-write
+
+
+ TOUCH_DREFL
+ touch sensor saw wave bottom voltage.
+ 27
+ 2
+ read-write
+
+
+ TOUCH_DREFH
+ touch sensor saw wave top voltage.
+ 29
+ 2
+ read-write
+
+
+ TOUCH_XPD_BIAS
+ touch sensor bias power on.
+ 31
+ 1
+ read-write
+
+
+
+
+ TOUCH_PAD0
+ 0x94
+ 0x20
+ 0x52000000
+
+
+ TO_GPIO
+ connect the rtc pad input to digital pad input Ă“0Ă“ is availbale GPIO4
+ 12
+ 1
+ read-write
+
+
+ FUN_IE
+ the input enable of the pad
+ 13
+ 1
+ read-write
+
+
+ SLP_OE
+ the output enable of the pad in sleep status
+ 14
+ 1
+ read-write
+
+
+ SLP_IE
+ the input enable of the pad in sleep status
+ 15
+ 1
+ read-write
+
+
+ SLP_SEL
+ the sleep status selection signal of the pad
+ 16
+ 1
+ read-write
+
+
+ FUN_SEL
+ the functional selection signal of the pad
+ 17
+ 2
+ read-write
+
+
+ MUX_SEL
+ Ă’1Ă“ select the digital function Ă“0Ă“slection the rtc function
+ 19
+ 1
+ read-write
+
+
+ XPD
+ touch sensor power on.
+ 20
+ 1
+ read-write
+
+
+ TIE_OPT
+ default touch sensor tie option. 0: tie low 1: tie high.
+ 21
+ 1
+ read-write
+
+
+ START
+ start touch sensor.
+ 22
+ 1
+ read-write
+
+
+ DAC
+ touch sensor slope control. 3-bit for each touch panel default 100.
+ 23
+ 3
+ read-write
+
+
+ RUE
+ the pull up enable of the pad
+ 27
+ 1
+ read-write
+
+
+ RDE
+ the pull down enable of the pad
+ 28
+ 1
+ read-write
+
+
+ DRV
+ the driver strength of the pad
+ 29
+ 2
+ read-write
+
+
+ HOLD
+ hold the current value of the output when setting the hold to Ă’1Ă“
+ 31
+ 1
+ read-write
+
+
+
+
+ TOUCH_PAD1
+ 0x98
+ 0x20
+ 0x4A000000
+
+
+ TO_GPIO
+ connect the rtc pad input to digital pad input Ă“0Ă“ is availbale.GPIO0
+ 12
+ 1
+ read-write
+
+
+ FUN_IE
+ the input enable of the pad
+ 13
+ 1
+ read-write
+
+
+ SLP_OE
+ the output enable of the pad in sleep status
+ 14
+ 1
+ read-write
+
+
+ SLP_IE
+ the input enable of the pad in sleep status
+ 15
+ 1
+ read-write
+
+
+ SLP_SEL
+ the sleep status selection signal of the pad
+ 16
+ 1
+ read-write
+
+
+ FUN_SEL
+ the functional selection signal of the pad
+ 17
+ 2
+ read-write
+
+
+ MUX_SEL
+ Ă’1Ă“ select the digital function Ă“0Ă“slection the rtc function
+ 19
+ 1
+ read-write
+
+
+ XPD
+ touch sensor power on.
+ 20
+ 1
+ read-write
+
+
+ TIE_OPT
+ default touch sensor tie option. 0: tie low 1: tie high.
+ 21
+ 1
+ read-write
+
+
+ START
+ start touch sensor.
+ 22
+ 1
+ read-write
+
+
+ DAC
+ touch sensor slope control. 3-bit for each touch panel default 100.
+ 23
+ 3
+ read-write
+
+
+ RUE
+ the pull up enable of the pad
+ 27
+ 1
+ read-write
+
+
+ RDE
+ the pull down enable of the pad
+ 28
+ 1
+ read-write
+
+
+ DRV
+ the driver strength of the pad
+ 29
+ 2
+ read-write
+
+
+ HOLD
+ 31
+ 1
+ read-write
+
+
+
+
+ TOUCH_PAD2
+ 0x9C
+ 0x20
+ 0x52000000
+
+
+ TO_GPIO
+ connect the rtc pad input to digital pad input Ă“0Ă“ is availbale.GPIO2
+ 12
+ 1
+ read-write
+
+
+ FUN_IE
+ the input enable of the pad
+ 13
+ 1
+ read-write
+
+
+ SLP_OE
+ the output enable of the pad in sleep status
+ 14
+ 1
+ read-write
+
+
+ SLP_IE
+ the input enable of the pad in sleep status
+ 15
+ 1
+ read-write
+
+
+ SLP_SEL
+ the sleep status selection signal of the pad
+ 16
+ 1
+ read-write
+
+
+ FUN_SEL
+ the functional selection signal of the pad
+ 17
+ 2
+ read-write
+
+
+ MUX_SEL
+ Ă’1Ă“ select the digital function Ă“0Ă“slection the rtc function
+ 19
+ 1
+ read-write
+
+
+ XPD
+ touch sensor power on.
+ 20
+ 1
+ read-write
+
+
+ TIE_OPT
+ default touch sensor tie option. 0: tie low 1: tie high.
+ 21
+ 1
+ read-write
+
+
+ START
+ start touch sensor.
+ 22
+ 1
+ read-write
+
+
+ DAC
+ touch sensor slope control. 3-bit for each touch panel default 100.
+ 23
+ 3
+ read-write
+
+
+ RUE
+ the pull up enable of the pad
+ 27
+ 1
+ read-write
+
+
+ RDE
+ the pull down enable of the pad
+ 28
+ 1
+ read-write
+
+
+ DRV
+ the driver strength of the pad
+ 29
+ 2
+ read-write
+
+
+ HOLD
+ hold the current value of the output when setting the hold to Ă’1Ă“
+ 31
+ 1
+ read-write
+
+
+
+
+ TOUCH_PAD3
+ 0xA0
+ 0x20
+ 0x4A000000
+
+
+ TO_GPIO
+ connect the rtc pad input to digital pad input Ă“0Ă“ is availbale.MTDO
+ 12
+ 1
+ read-write
+
+
+ FUN_IE
+ the input enable of the pad
+ 13
+ 1
+ read-write
+
+
+ SLP_OE
+ the output enable of the pad in sleep status
+ 14
+ 1
+ read-write
+
+
+ SLP_IE
+ the input enable of the pad in sleep status
+ 15
+ 1
+ read-write
+
+
+ SLP_SEL
+ the sleep status selection signal of the pad
+ 16
+ 1
+ read-write
+
+
+ FUN_SEL
+ the functional selection signal of the pad
+ 17
+ 2
+ read-write
+
+
+ MUX_SEL
+ Ă’1Ă“ select the digital function Ă“0Ă“slection the rtc function
+ 19
+ 1
+ read-write
+
+
+ XPD
+ touch sensor power on.
+ 20
+ 1
+ read-write
+
+
+ TIE_OPT
+ default touch sensor tie option. 0: tie low 1: tie high.
+ 21
+ 1
+ read-write
+
+
+ START
+ start touch sensor.
+ 22
+ 1
+ read-write
+
+
+ DAC
+ touch sensor slope control. 3-bit for each touch panel default 100.
+ 23
+ 3
+ read-write
+
+
+ RUE
+ the pull up enable of the pad
+ 27
+ 1
+ read-write
+
+
+ RDE
+ the pull down enable of the pad
+ 28
+ 1
+ read-write
+
+
+ DRV
+ the driver strength of the pad
+ 29
+ 2
+ read-write
+
+
+ HOLD
+ hold the current value of the output when setting the hold to Ă’1Ă“
+ 31
+ 1
+ read-write
+
+
+
+
+ TOUCH_PAD4
+ 0xA4
+ 0x20
+ 0x52000000
+
+
+ TO_GPIO
+ connect the rtc pad input to digital pad input Ă“0Ă“ is availbale.MTCK
+ 12
+ 1
+ read-write
+
+
+ FUN_IE
+ the input enable of the pad
+ 13
+ 1
+ read-write
+
+
+ SLP_OE
+ the output enable of the pad in sleep status
+ 14
+ 1
+ read-write
+
+
+ SLP_IE
+ the input enable of the pad in sleep status
+ 15
+ 1
+ read-write
+
+
+ SLP_SEL
+ the sleep status selection signal of the pad
+ 16
+ 1
+ read-write
+
+
+ FUN_SEL
+ the functional selection signal of the pad
+ 17
+ 2
+ read-write
+
+
+ MUX_SEL
+ Ă’1Ă“ select the digital function Ă“0Ă“slection the rtc function
+ 19
+ 1
+ read-write
+
+
+ XPD
+ touch sensor power on.
+ 20
+ 1
+ read-write
+
+
+ TIE_OPT
+ default touch sensor tie option. 0: tie low 1: tie high.
+ 21
+ 1
+ read-write
+
+
+ START
+ start touch sensor.
+ 22
+ 1
+ read-write
+
+
+ DAC
+ touch sensor slope control. 3-bit for each touch panel default 100.
+ 23
+ 3
+ read-write
+
+
+ RUE
+ the pull up enable of the pad
+ 27
+ 1
+ read-write
+
+
+ RDE
+ the pull down enable of the pad
+ 28
+ 1
+ read-write
+
+
+ DRV
+ the driver strength of the pad
+ 29
+ 2
+ read-write
+
+
+ HOLD
+ hold the current value of the output when setting the hold to Ă’1Ă“
+ 31
+ 1
+ read-write
+
+
+
+
+ TOUCH_PAD5
+ 0xA8
+ 0x20
+ 0x52000000
+
+
+ TO_GPIO
+ connect the rtc pad input to digital pad input Ă“0Ă“ is availbale.MTDI
+ 12
+ 1
+ read-write
+
+
+ FUN_IE
+ the input enable of the pad
+ 13
+ 1
+ read-write
+
+
+ SLP_OE
+ the output enable of the pad in sleep status
+ 14
+ 1
+ read-write
+
+
+ SLP_IE
+ the input enable of the pad in sleep status
+ 15
+ 1
+ read-write
+
+
+ SLP_SEL
+ the sleep status selection signal of the pad
+ 16
+ 1
+ read-write
+
+
+ FUN_SEL
+ the functional selection signal of the pad
+ 17
+ 2
+ read-write
+
+
+ MUX_SEL
+ Ă’1Ă“ select the digital function Ă“0Ă“slection the rtc function
+ 19
+ 1
+ read-write
+
+
+ XPD
+ touch sensor power on.
+ 20
+ 1
+ read-write
+
+
+ TIE_OPT
+ default touch sensor tie option. 0: tie low 1: tie high.
+ 21
+ 1
+ read-write
+
+
+ START
+ start touch sensor.
+ 22
+ 1
+ read-write
+
+
+ DAC
+ touch sensor slope control. 3-bit for each touch panel default 100.
+ 23
+ 3
+ read-write
+
+
+ RUE
+ the pull up enable of the pad
+ 27
+ 1
+ read-write
+
+
+ RDE
+ the pull down enable of the pad
+ 28
+ 1
+ read-write
+
+
+ DRV
+ the driver strength of the pad
+ 29
+ 2
+ read-write
+
+
+ HOLD
+ hold the current value of the output when setting the hold to Ă’1Ă“
+ 31
+ 1
+ read-write
+
+
+
+
+ TOUCH_PAD6
+ 0xAC
+ 0x20
+ 0x4A000000
+
+
+ TO_GPIO
+ connect the rtc pad input to digital pad input Ă“0Ă“ is availbale.MTMS
+ 12
+ 1
+ read-write
+
+
+ FUN_IE
+ the input enable of the pad
+ 13
+ 1
+ read-write
+
+
+ SLP_OE
+ the output enable of the pad in sleep status
+ 14
+ 1
+ read-write
+
+
+ SLP_IE
+ the input enable of the pad in sleep status
+ 15
+ 1
+ read-write
+
+
+ SLP_SEL
+ the sleep status selection signal of the pad
+ 16
+ 1
+ read-write
+
+
+ FUN_SEL
+ the functional selection signal of the pad
+ 17
+ 2
+ read-write
+
+
+ MUX_SEL
+ Ă’1Ă“ select the digital function Ă“0Ă“slection the rtc function
+ 19
+ 1
+ read-write
+
+
+ XPD
+ touch sensor power on.
+ 20
+ 1
+ read-write
+
+
+ TIE_OPT
+ default touch sensor tie option. 0: tie low 1: tie high.
+ 21
+ 1
+ read-write
+
+
+ START
+ start touch sensor.
+ 22
+ 1
+ read-write
+
+
+ DAC
+ touch sensor slope control. 3-bit for each touch panel default 100.
+ 23
+ 3
+ read-write
+
+
+ RUE
+ the pull up enable of the pad
+ 27
+ 1
+ read-write
+
+
+ RDE
+ the pull down enable of the pad
+ 28
+ 1
+ read-write
+
+
+ DRV
+ the driver strength of the pad
+ 29
+ 2
+ read-write
+
+
+ HOLD
+ hold the current value of the output when setting the hold to Ă’1Ă“
+ 31
+ 1
+ read-write
+
+
+
+
+ TOUCH_PAD7
+ 0xB0
+ 0x20
+ 0x42000000
+
+
+ TO_GPIO
+ connect the rtc pad input to digital pad input Ă“0Ă“ is availbale.GPIO27
+ 12
+ 1
+ read-write
+
+
+ FUN_IE
+ the input enable of the pad
+ 13
+ 1
+ read-write
+
+
+ SLP_OE
+ the output enable of the pad in sleep status
+ 14
+ 1
+ read-write
+
+
+ SLP_IE
+ the input enable of the pad in sleep status
+ 15
+ 1
+ read-write
+
+
+ SLP_SEL
+ the sleep status selection signal of the pad
+ 16
+ 1
+ read-write
+
+
+ FUN_SEL
+ the functional selection signal of the pad
+ 17
+ 2
+ read-write
+
+
+ MUX_SEL
+ Ă’1Ă“ select the digital function Ă“0Ă“slection the rtc function
+ 19
+ 1
+ read-write
+
+
+ XPD
+ touch sensor power on.
+ 20
+ 1
+ read-write
+
+
+ TIE_OPT
+ default touch sensor tie option. 0: tie low 1: tie high.
+ 21
+ 1
+ read-write
+
+
+ START
+ start touch sensor.
+ 22
+ 1
+ read-write
+
+
+ DAC
+ touch sensor slope control. 3-bit for each touch panel default 100.
+ 23
+ 3
+ read-write
+
+
+ RUE
+ the pull up enable of the pad
+ 27
+ 1
+ read-write
+
+
+ RDE
+ the pull down enable of the pad
+ 28
+ 1
+ read-write
+
+
+ DRV
+ the driver strength of the pad
+ 29
+ 2
+ read-write
+
+
+ HOLD
+ hold the current value of the output when setting the hold to Ă’1Ă“
+ 31
+ 1
+ read-write
+
+
+
+
+ TOUCH_PAD8
+ 0xB4
+ 0x20
+ 0x02000000
+
+
+ TO_GPIO
+ connect the rtc pad input to digital pad input Ă“0Ă“ is availbale
+ 19
+ 1
+ read-write
+
+
+ XPD
+ touch sensor power on.
+ 20
+ 1
+ read-write
+
+
+ TIE_OPT
+ default touch sensor tie option. 0: tie low 1: tie high.
+ 21
+ 1
+ read-write
+
+
+ START
+ start touch sensor.
+ 22
+ 1
+ read-write
+
+
+ DAC
+ touch sensor slope control. 3-bit for each touch panel default 100.
+ 23
+ 3
+ read-write
+
+
+
+
+ TOUCH_PAD9
+ 0xB8
+ 0x20
+ 0x02000000
+
+
+ TO_GPIO
+ connect the rtc pad input to digital pad input Ă“0Ă“ is availbale
+ 19
+ 1
+ read-write
+
+
+ XPD
+ touch sensor power on.
+ 20
+ 1
+ read-write
+
+
+ TIE_OPT
+ default touch sensor tie option. 0: tie low 1: tie high.
+ 21
+ 1
+ read-write
+
+
+ START
+ start touch sensor.
+ 22
+ 1
+ read-write
+
+
+ DAC
+ touch sensor slope control. 3-bit for each touch panel default 100.
+ 23
+ 3
+ read-write
+
+
+
+
+ EXT_WAKEUP0
+ 0xBC
+ 0x20
+
+
+ SEL
+ select the wakeup source Ă“0Ă“ select GPIO0 Ă“1Ă“ select GPIO2 ...Ă’17Ă“ select GPIO17
+ 27
+ 5
+ read-write
+
+
+
+
+ XTL_EXT_CTR
+ 0xC0
+ 0x20
+
+
+ SEL
+ select the external xtl power source Ă“0Ă“ select GPIO0 Ă“1Ă“ select GPIO2 ...Ă’17Ă“ select GPIO17
+ 27
+ 5
+ read-write
+
+
+
+
+ SAR_I2C_IO
+ 0xC4
+ 0x20
+
+
+ SAR_DEBUG_BIT_SEL
+ 23
+ 5
+ read-write
+
+
+ SAR_I2C_SCL_SEL
+ Ă’0Ă“ using TOUCH_PAD[0] as i2c clk Ă’1Ă“ using TOUCH_PAD[2] as i2c clk
+ 28
+ 2
+ read-write
+
+
+ SAR_I2C_SDA_SEL
+ Ă’0Ă“ using TOUCH_PAD[1] as i2c sda Ă’1Ă“ using TOUCH_PAD[3] as i2c sda
+ 30
+ 2
+ read-write
+
+
+
+
+ DATE
+ 0xC8
+ 0x20
+ 0x01603160
+
+
+ IO_DATE
+ date
+ 0
+ 28
+ read-write
+
+
+
+
+
+
+ RTC_I2C
+ Peripheral RTC_I2C
+ RTC_I2C
+ 0x3FF48C00
+
+ 0x0
+ 0x3C
+ registers
+
+
+
+ SCL_LOW_PERIOD
+ 0x0
+ 0x20
+
+
+ SCL_LOW_PERIOD
+ number of cycles that scl == 0
+ 0
+ 25
+ read-write
+
+
+
+
+ CTRL
+ 0x4
+ 0x20
+
+
+ SDA_FORCE_OUT
+ SDA is push-pull (1) or open-drain (0)
+ 0
+ 1
+ read-write
+
+
+ SCL_FORCE_OUT
+ SCL is push-pull (1) or open-drain (0)
+ 1
+ 1
+ read-write
+
+
+ MS_MODE
+ Master (1) or slave (0)
+ 4
+ 1
+ read-write
+
+
+ TRANS_START
+ Force to generate start condition
+ 5
+ 1
+ read-write
+
+
+ TX_LSB_FIRST
+ Send LSB first
+ 6
+ 1
+ read-write
+
+
+ RX_LSB_FIRST
+ Receive LSB first
+ 7
+ 1
+ read-write
+
+
+
+
+ DEBUG_STATUS
+ 0x8
+ 0x20
+
+
+ ACK_VAL
+ The value of an acknowledge signal on the bus
+ 0
+ 1
+ read-write
+
+
+ SLAVE_RW
+ When working as a slave, the value of R/W bit received
+ 1
+ 1
+ read-write
+
+
+ TIMED_OUT
+ Transfer has timed out
+ 2
+ 1
+ read-write
+
+
+ ARB_LOST
+ When working as a master, lost control of I2C bus
+ 3
+ 1
+ read-write
+
+
+ BUS_BUSY
+ operation is in progress
+ 4
+ 1
+ read-write
+
+
+ SLAVE_ADDR_MATCH
+ When working as a slave, whether address was matched
+ 5
+ 1
+ read-write
+
+
+ BYTE_TRANS
+ 8 bit transmit done
+ 6
+ 1
+ read-write
+
+
+ MAIN_STATE
+ state of the main state machine
+ 25
+ 3
+ read-write
+
+
+ SCL_STATE
+ state of SCL state machine
+ 28
+ 3
+ read-write
+
+
+
+
+ TIMEOUT
+ 0xC
+ 0x20
+
+
+ TIMEOUT
+ Maximum number of FAST_CLK cycles that the transmission can take
+ 0
+ 20
+ read-write
+
+
+
+
+ SLAVE_ADDR
+ 0x10
+ 0x20
+
+
+ SLAVE_ADDR
+ local slave address
+ 0
+ 15
+ read-write
+
+
+ _10BIT
+ Set if local slave address is 10-bit
+ 31
+ 1
+ read-write
+
+
+
+
+ DATA
+ 0x1C
+ 0x20
+
+
+ INT_RAW
+ 0x20
+ 0x20
+
+
+ SLAVE_TRANS_COMPLETE_INT_RAW
+ Slave accepted 1 byte and address matched
+ 3
+ 1
+ read-write
+
+
+ ARBITRATION_LOST_INT_RAW
+ Master lost arbitration
+ 4
+ 1
+ read-write
+
+
+ MASTER_TRANS_COMPLETE_INT_RAW
+ 5
+ 1
+ read-write
+
+
+ TRANS_COMPLETE_INT_RAW
+ Stop condition has been detected interrupt raw status
+ 6
+ 1
+ read-write
+
+
+ TIME_OUT_INT_RAW
+ time out interrupt raw status
+ 7
+ 1
+ read-only
+
+
+
+
+ INT_CLR
+ 0x24
+ 0x20
+
+
+ SLAVE_TRANS_COMPLETE_INT_CLR
+ 4
+ 1
+ read-write
+
+
+ ARBITRATION_LOST_INT_CLR
+ 5
+ 1
+ read-write
+
+
+ MASTER_TRANS_COMPLETE_INT_CLR
+ 6
+ 1
+ read-write
+
+
+ TRANS_COMPLETE_INT_CLR
+ 7
+ 1
+ read-write
+
+
+ TIME_OUT_INT_CLR
+ 8
+ 1
+ write-only
+
+
+
+
+ INT_EN
+ 0x28
+ 0x20
+
+
+ INT_ST
+ 0x2C
+ 0x20
+
+
+ SDA_DUTY
+ 0x30
+ 0x20
+
+
+ SDA_DUTY
+ Number of FAST_CLK cycles SDA will switch after falling edge of SCL
+ 0
+ 20
+ read-write
+
+
+
+
+ SCL_HIGH_PERIOD
+ 0x38
+ 0x20
+
+
+ SCL_HIGH_PERIOD
+ Number of FAST_CLK cycles for SCL to be high
+ 0
+ 20
+ read-write
+
+
+
+
+ SCL_START_PERIOD
+ 0x40
+ 0x20
+
+
+ SCL_START_PERIOD
+ Number of FAST_CLK cycles to wait before generating start condition
+ 0
+ 20
+ read-write
+
+
+
+
+ SCL_STOP_PERIOD
+ 0x44
+ 0x20
+
+
+ SCL_STOP_PERIOD
+ Number of FAST_CLK cycles to wait before generating stop condition
+ 0
+ 20
+ read-write
+
+
+
+
+ CMD
+ 0x48
+ 0x20
+
+
+ VAL
+ Command content
+ 0
+ 14
+ read-write
+
+
+ DONE
+ Bit is set by HW when command is done
+ 31
+ 1
+ read-write
+
+
+
+
+
+
+ SDMMC
+ SD/MMC Host Controller
+ SDHOST
+ 0x3FF68000
+
+ 0x0
+ 0xA4
+ registers
+
+
+
+ CTRL
+ Control register
+ 0x0
+ 0x20
+
+
+ CONTROLLER_RESET
+ To reset controller, firmware should set this bit. This bit is auto-cleared after two AHB and two sdhost_cclk_in clock cycles.
+ 0
+ 1
+ read-write
+
+
+ FIFO_RESET
+ To reset FIFO, firmware should set bit to 1. This bit is auto-cleared after completion of reset operation.
+Note: FIFO pointers will be out of reset after 2 cycles of system clocks in addition to synchronization delay (2 cycles of card clock), after the fifo_reset is cleared.
+ 1
+ 1
+ read-write
+
+
+ DMA_RESET
+ To reset DMA interface, firmware should set bit to 1. This bit is auto-cleared after two AHB clocks.
+ 2
+ 1
+ read-write
+
+
+ INT_ENABLE
+ Global interrupt enable/disable bit. 0: Disable; 1: Enable.
+ 4
+ 1
+ read-write
+
+
+ READ_WAIT
+ For sending read-wait to SDIO cards.
+ 6
+ 1
+ read-write
+
+
+ SEND_IRQ_RESPONSE
+ Bit automatically clears once response is sent. To wait for MMC card interrupts, host issues CMD40 and waits for interrupt response from MMC card(s). In the meantime, if host wants SD/MMC to exit waiting for interrupt state, it can set this bit, at which time SD/MMC command state-machine sends CMD40 response on bus and returns to idle state.
+ 7
+ 1
+ read-write
+
+
+ ABORT_READ_DATA
+ After a suspend-command is issued during a read-operation, software polls the card to find when the suspend-event occurred. Once the suspend-event has occurred, software sets the bit which will reset the data state machine that is waiting for the next block of data. This bit is automatically cleared once the data state machine is reset to idle.
+ 8
+ 1
+ read-write
+
+
+ SEND_CCSD
+ When set, SD/MMC sends CCSD to the CE-ATA device. Software sets this bit only if the current command is expecting CCS (that is, RW_BLK), and if interrupts are enabled for the CE-ATA device. Once the CCSD pattern is sent to the device, SD/MMC automatically clears the SDHOST_SEND_CCSD bit. It also sets the Command Done (CD) bit in the SDHOST_RINTSTS_REG register, and generates an interrupt for the host, in case the Command Done interrupt is not masked.
+NOTE: Once the SDHOST_SEND_CCSD bit is set, it takes two card clock cycles to drive the CCSD on the CMD line. Due to this, within the boundary conditions the CCSD may be sent to the CE-ATA device, even if the device has signalled CCS.
+ 9
+ 1
+ read-write
+
+
+ SEND_AUTO_STOP_CCSD
+ Always Set SDHOST_SEND_AUTO_STOP_CCSD and SDHOST_SEND_CCSD bits together; SDHOST_SEND_AUTO_STOP_CCSD should not be set independently of send_ccsd. When set, SD/MMC automatically sends an internally-generated STOP command (CMD12) to the CE-ATA device. After sending this internally-generated STOP command, the Auto Command Done (ACD) bit in SDHOST_RINTSTS_REG is set and an interrupt is generated for the host, in case the ACD interrupt is not masked. After sending the Command Completion Signal Disable (CCSD), SD/MMC automatically clears the SDHOST_SEND_AUTO_STOP_CCSD bit.
+ 10
+ 1
+ read-write
+
+
+ CEATA_DEVICE_INTERRUPT_STATUS
+ Software should appropriately write to this bit after the power-on reset or any other reset to the CE-ATA device. After reset, the CE-ATA device's interrupt is usually disabled (nIEN = 1). If the host enables the CE-ATA device's interrupt, then software should set this bit.
+ 11
+ 1
+ read-write
+
+
+
+
+ CLKDIV
+ Clock divider configuration register
+ 0x8
+ 0x20
+
+
+ CLK_DIVIDER0
+ Clock divider0 value. Clock divisor is 2*n, where n = 0 bypasses the divider (divisor of 1). For example, a value of 1 means divided by 2*1 = 2, a value of 0xFF means divided by 2*255 = 510, and so on.
+ 0
+ 8
+ read-write
+
+
+ CLK_DIVIDER1
+ Clock divider1 value. Clock divisor is 2*n, where n = 0 bypasses the divider (divisor of 1). For example, a value of 1 means divided by 2*1 = 2, a value of 0xFF means divided by 2*255 = 510, and so on.
+ 8
+ 8
+ read-write
+
+
+ CLK_DIVIDER2
+ Clock divider2 value. Clock divisor is 2*n, where n = 0 bypasses the divider (divisor of 1). For example, a value of 1 means divided by 2*1 = 2, a value of 0xFF means divided by 2*255 = 510, and so on.
+ 16
+ 8
+ read-write
+
+
+ CLK_DIVIDER3
+ Clock divider3 value. Clock divisor is 2*n, where n = 0 bypasses the divider (divisor of 1). For example, a value of 1 means divided by 2*1 = 2, a value of 0xFF means divided by 2*255 = 510, and so on.
+ 24
+ 8
+ read-write
+
+
+
+
+ CLKSRC
+ Clock source selection register
+ 0xC
+ 0x20
+
+
+ CLKSRC
+ Clock divider source for two SD cards is supported. Each card has two bits assigned to it. For example, bit[1:0] are assigned for card 0, bit[3:2] are assigned for card 1. Card 0 maps and internally routes clock divider[0:3] outputs to cclk_out[1:0] pins, depending on bit value.
+00 : Clock divider 0;
+01 : Clock divider 1;
+10 : Clock divider 2;
+11 : Clock divider 3.
+ 0
+ 4
+ read-write
+
+
+
+
+ CLKENA
+ Clock enable register
+ 0x10
+ 0x20
+
+
+ CCLK_ENABLE
+ Clock-enable control for two SD card clocks and one MMC card clock is supported. One bit per card.
+0: Clock disabled;
+1: Clock enabled.
+ 0
+ 2
+ read-write
+
+
+ LP_ENABLE
+ Disable clock when the card is in IDLE state. One bit per card.
+0: clock disabled;
+1: clock enabled.
+ 16
+ 2
+ read-write
+
+
+
+
+ TMOUT
+ Data and response timeout configuration register
+ 0x14
+ 0x20
+ 0xFFFFFF40
+
+
+ RESPONSE_TIMEOUT
+ Response timeout value. Value is specified in terms of number of card output clocks, i.e., sdhost_cclk_out.
+ 0
+ 8
+ read-write
+
+
+ DATA_TIMEOUT
+ Value for card data read timeout. This value is also used for data starvation by host timeout. The timeout counter is started only after the card clock is stopped. This value is specified in number of card output clocks, i.e. sdhost_cclk_out of the selected card.
+NOTE: The software timer should be used if the timeout value is in the order of 100 ms. In this case, read data timeout interrupt needs to be disabled.
+ 8
+ 24
+ read-write
+
+
+
+
+ CTYPE
+ Card bus width configuration register
+ 0x18
+ 0x20
+
+
+ CARD_WIDTH4
+ One bit per card indicates if card is 1-bit or 4-bit mode.
+0: 1-bit mode;
+1: 4-bit mode.
+Bit[1:0] correspond to card[1:0] respectively.
+ 0
+ 2
+ read-write
+
+
+ CARD_WIDTH8
+ One bit per card indicates if card is in 8-bit mode.
+0: Non 8-bit mode;
+1: 8-bit mode.
+Bit[17:16] correspond to card[1:0] respectively.
+ 16
+ 2
+ read-write
+
+
+
+
+ BLKSIZ
+ Card data block size configuration register
+ 0x1C
+ 0x20
+ 0x00000200
+
+
+ BLOCK_SIZE
+ Block size.
+ 0
+ 16
+ read-write
+
+
+
+
+ BYTCNT
+ Data transfer length configuration register
+ 0x20
+ 0x20
+ 0x00000200
+
+
+ BYTE_COUNT
+ Number of bytes to be transferred, should be an integral multiple of Block Size for block transfers. For data transfers of undefined byte lengths, byte count should be set to 0. When byte count is set to 0, it is the responsibility of host to explicitly send stop/abort command to terminate data transfer.
+ 0
+ 32
+ read-write
+
+
+
+
+ INTMASK
+ SDIO interrupt mask register
+ 0x24
+ 0x20
+
+
+ INT_MASK
+ These bits used to mask unwanted interrupts. A value of 0 masks interrupt, and a value of 1 enables the interrupt.
+Bit 15 (EBE): End-bit error/no CRC error;
+Bit 14 (ACD): Auto command done;
+Bit 13 (SBE/BCI): Rx Start Bit Error;
+Bit 12 (HLE): Hardware locked write error;
+Bit 11 (FRUN): FIFO underrun/overrun error;
+Bit 10 (HTO): Data starvation-by-host timeout;
+Bit 9 (DRTO): Data read timeout;
+Bit 8 (RTO): Response timeout;
+Bit 7 (DCRC): Data CRC error;
+Bit 6 (RCRC): Response CRC error;
+Bit 5 (RXDR): Receive FIFO data request;
+Bit 4 (TXDR): Transmit FIFO data request;
+Bit 3 (DTO): Data transfer over;
+Bit 2 (CD): Command done;
+Bit 1 (RE): Response error;
+Bit 0 (CD): Card detect.
+ 0
+ 16
+ read-write
+
+
+ SDIO_INT_MASK
+ SDIO interrupt mask, one bit for each card. Bit[17:16] correspond to card[15:0] respectively. When masked, SDIO interrupt detection for that card is disabled. 0 masks an interrupt, and 1 enables an interrupt.
+ 16
+ 2
+ read-write
+
+
+
+
+ CMDARG
+ Command argument data register
+ 0x28
+ 0x20
+
+
+ CMDARG
+ Value indicates command argument to be passed to the card.
+ 0
+ 32
+ read-write
+
+
+
+
+ CMD
+ Command and boot configuration register
+ 0x2C
+ 0x20
+ 0x20000000
+
+
+ INDEX
+ Command index.
+ 0
+ 6
+ read-write
+
+
+ RESPONSE_EXPECT
+ 0: No response expected from card; 1: Response expected from card.
+ 6
+ 1
+ read-write
+
+
+ RESPONSE_LENGTH
+ 0: Short response expected from card; 1: Long response expected from card.
+ 7
+ 1
+ read-write
+
+
+ CHECK_RESPONSE_CRC
+ 0: Do not check; 1: Check response CRC.
+Some of command responses do not return valid CRC bits. Software should disable CRC checks for those commands in order to disable CRC checking by controller.
+ 8
+ 1
+ read-write
+
+
+ DATA_EXPECTED
+ 0: No data transfer expected; 1: Data transfer expected.
+ 9
+ 1
+ read-write
+
+
+ READ_WRITE
+ 0: Read from card; 1: Write to card.
+Don't care if no data is expected from card.
+ 10
+ 1
+ read-write
+
+
+ TRANSFER_MODE
+ Block data transfer command; 1: Stream data transfer command.
+Don't care if no data expected.
+ 11
+ 1
+ read-write
+
+
+ SEND_AUTO_STOP
+ 0: No stop command is sent at the end of data transfer; 1: Send stop command at the end of data transfer.
+ 12
+ 1
+ read-write
+
+
+ WAIT_PRVDATA_COMPLETE
+ 0: Send command at once, even if previous data transfer has not completed; 1: Wait for previous data transfer to complete before sending Command.
+The SDHOST_WAIT_PRVDATA_COMPLETE] = 0 option is typically used to query status of card during data transfer or to stop current data transfer. SDHOST_CARD_NUMBERr should be same as in previous command.
+ 13
+ 1
+ read-write
+
+
+ STOP_ABORT_CMD
+ 0: Neither stop nor abort command can stop current data transfer. If abort is sent to function-number currently selected or not in data-transfer mode, then bit should be set to 0; 1: Stop or abort command intended to stop current data transfer in progress.
+When open-ended or predefined data transfer is in progress, and host issues stop or abort command to stop data transfer, bit should be set so that command/data state-machines of CIU can return correctly to idle state.
+ 14
+ 1
+ read-write
+
+
+ SEND_INITIALIZATION
+ 0: Do not send initialization sequence (80 clocks of 1) before sending this command; 1: Send initialization sequence before sending this command.
+After powered on, 80 clocks must be sent to card for initialization before sending any commands to card. Bit should be set while sending first command to card so that controller will initialize clocks before sending command to card.
+ 15
+ 1
+ read-write
+
+
+ CARD_NUMBER
+ Card number in use. Represents physical slot number of card being accessed. In SD-only mode, up to two cards are supported.
+ 16
+ 5
+ read-write
+
+
+ UPDATE_CLOCK_REGISTERS_ONLY
+ 0: Normal command sequence; 1: Do not send commands, just update clock register value into card clock domain.
+Following register values are transferred into card clock domain: CLKDIV, CLRSRC, and CLKENA.
+Changes card clocks (change frequency, truncate off or on, and set low-frequency mode). This is provided in order to change clock frequency or stop clock without having to send command to cards. During normal command sequence, when sdhost_update_clock_registers_only = 0, following control registers are transferred from BIU to CIU: CMD, CMDARG, TMOUT, CTYPE, BLKSIZ, and BYTCNT. CIU uses new register values for new command sequence to card(s). When bit is set, there are no Command Done interrupts because no command is sent to SD_MMC_CEATA cards.
+ 21
+ 1
+ read-write
+
+
+ READ_CEATA_DEVICE
+ Read access flag.
+0: Host is not performing read access (RW_REG or RW_BLK)towards CE-ATA device;
+1: Host is performing read access (RW_REG or RW_BLK) towards CE-ATA device.
+Software should set this bit to indicate that CE-ATA device is being accessed for read transfer. This bit is used to disable read data timeout indication while performing CE-ATA read transfers. Maximum value of I/O transmission delay can be no less than 10 seconds. SD/MMC should not indicate read data timeout while waiting for data from CE-ATA device.
+ 22
+ 1
+ read-write
+
+
+ CCS_EXPECTED
+ Expected Command Completion Signal (CCS) configuration.
+0: Interrupts are not enabled in CE-ATA device (nIEN = 1 in ATA control register), or command does not expect CCS from device;
+1: Interrupts are enabled in CE-ATA device (nIEN = 0), and RW_BLK command expects command completion signal from CE-ATA device.
+If the command expects Command Completion Signal (CCS) from the CE-ATA device, the software should set this control bit. SD/MMC sets Data Transfer Over (DTO) bit in RINTSTS register and generates interrupt to host if Data Transfer Over interrupt is not masked.
+ 23
+ 1
+ read-write
+
+
+ USE_HOLE
+ Use Hold Register.
+0: CMD and DATA sent to card bypassing HOLD Register;
+1: CMD and DATA sent to card through the HOLD Register.
+ 29
+ 1
+ read-write
+
+
+ START_CMD
+ Start command. Once command is served by the CIU, this bit is automatically cleared. When this bit is set, host should not attempt to write to any command registers. If a write is attempted, hardware lock error is set in raw interrupt register. Once command is sent and a response is received from SD_MMC_CEATA cards, Command Done bit is set in the raw interrupt Register.
+ 31
+ 1
+ read-write
+
+
+
+
+ RESP0
+ Response data register
+ 0x30
+ 0x20
+
+
+ RESPONSE0
+ Bit[31:0] of response.
+ 0
+ 32
+ read-only
+
+
+
+
+ RESP1
+ Long response data register
+ 0x34
+ 0x20
+
+
+ RESPONSE1
+ Bit[63:32] of long response.
+ 0
+ 32
+ read-only
+
+
+
+
+ RESP2
+ Long response data register
+ 0x38
+ 0x20
+
+
+ RESPONSE2
+ Bit[95:64] of long response.
+ 0
+ 32
+ read-only
+
+
+
+
+ RESP3
+ Long response data register
+ 0x3C
+ 0x20
+
+
+ RESPONSE3
+ Bit[127:96] of long response.
+ 0
+ 32
+ read-only
+
+
+
+
+ MINTSTS
+ Masked interrupt status register
+ 0x40
+ 0x20
+
+
+ INT_STATUS_MSK
+ Interrupt enabled only if corresponding bit in interrupt mask register is set.
+Bit 15 (EBE): End-bit error/no CRC error;
+Bit 14 (ACD): Auto command done;
+Bit 13 (SBE/BCI): RX Start Bit Error;
+Bit 12 (HLE): Hardware locked write error;
+Bit 11 (FRUN): FIFO underrun/overrun error;
+Bit 10 (HTO): Data starvation by host timeout (HTO);
+Bit 9 (DTRO): Data read timeout;
+Bit 8 (RTO): Response timeout;
+Bit 7 (DCRC): Data CRC error;
+Bit 6 (RCRC): Response CRC error;
+Bit 5 (RXDR): Receive FIFO data request;
+Bit 4 (TXDR): Transmit FIFO data request;
+Bit 3 (DTO): Data transfer over;
+Bit 2 (CD): Command done;
+Bit 1 (RE): Response error;
+Bit 0 (CD): Card detect.
+ 0
+ 16
+ read-only
+
+
+ SDIO_INTERRUPT_MSK
+ Interrupt from SDIO card, one bit for each card. Bit[17:16] correspond to card1 and card0, respectively. SDIO interrupt for card is enabled only if corresponding sdhost_sdio_int_mask bit is set in Interrupt mask register (Setting mask bit enables interrupt).
+ 16
+ 2
+ read-only
+
+
+
+
+ RINTSTS
+ Raw interrupt status register
+ 0x44
+ 0x20
+
+
+ INT_STATUS_RAW
+ Setting a bit clears the corresponding interrupt and writing 0 has no effect. Bits are logged regardless of interrupt mask status.
+Bit 15 (EBE): End-bit error/no CRC error;
+Bit 14 (ACD): Auto command done;
+Bit 13 (SBE/BCI): RX Start Bit Error;
+Bit 12 (HLE): Hardware locked write error;
+Bit 11 (FRUN): FIFO underrun/overrun error;
+Bit 10 (HTO): Data starvation by host timeout (HTO);
+Bit 9 (DTRO): Data read timeout;
+Bit 8 (RTO): Response timeout;
+Bit 7 (DCRC): Data CRC error;
+Bit 6 (RCRC): Response CRC error;
+Bit 5 (RXDR): Receive FIFO data request;
+Bit 4 (TXDR): Transmit FIFO data request;
+Bit 3 (DTO): Data transfer over;
+Bit 2 (CD): Command done;
+Bit 1 (RE): Response error;
+Bit 0 (CD): Card detect.
+ 0
+ 16
+ read-write
+
+
+ SDIO_INTERRUPT_RAW
+ Interrupt from SDIO card, one bit for each card. Bit[17:16] correspond to card1 and card0, respectively. Setting a bit clears the corresponding interrupt bit and writing 0 has no effect.
+0: No SDIO interrupt from card;
+1: SDIO interrupt from card.
+ 16
+ 2
+ read-write
+
+
+
+
+ STATUS
+ SD/MMC status register
+ 0x48
+ 0x20
+ 0x00000716
+
+
+ FIFO_RX_WATERMARK
+ FIFO reached Receive watermark level, not qualified with data transfer.
+ 0
+ 1
+ read-only
+
+
+ FIFO_TX_WATERMARK
+ FIFO reached Transmit watermark level, not qualified with data transfer.
+ 1
+ 1
+ read-only
+
+
+ FIFO_EMPTY
+ FIFO is empty status.
+ 2
+ 1
+ read-only
+
+
+ FIFO_FULL
+ FIFO is full status.
+ 3
+ 1
+ read-only
+
+
+ COMMAND_FSM_STATES
+ Command FSM states.
+0: Idle;
+1: Send init sequence;
+2: Send cmd start bit;
+3: Send cmd tx bit;
+4: Send cmd index + arg;
+5: Send cmd crc7;
+6: Send cmd end bit;
+7: Receive resp start bit;
+8: Receive resp IRQ response;
+9: Receive resp tx bit;
+10: Receive resp cmd idx;
+11: Receive resp data;
+12: Receive resp crc7;
+13: Receive resp end bit;
+14: Cmd path wait NCC;
+15: Wait, cmd-to-response turnaround.
+ 4
+ 4
+ read-only
+
+
+ DATA_3_STATUS
+ Raw selected sdhost_card_data[3], checks whether card is present.
+0: card not present;
+1: card present.
+ 8
+ 1
+ read-only
+
+
+ DATA_BUSY
+ Inverted version of raw selected sdhost_card_data[0].
+0: Card data not busy;
+1: Card data busy.
+ 9
+ 1
+ read-only
+
+
+ DATA_STATE_MC_BUSY
+ Data transmit or receive state-machine is busy.
+ 10
+ 1
+ read-only
+
+
+ RESPONSE_INDEX
+ Index of previous response, including any auto-stop sent by core.
+ 11
+ 6
+ read-only
+
+
+ FIFO_COUNT
+ FIFO count, number of filled locations in FIFO.
+ 17
+ 13
+ read-only
+
+
+
+
+ FIFOTH
+ FIFO configuration register
+ 0x4C
+ 0x20
+
+
+ TX_WMARK
+ FIFO threshold watermark level when transmitting data to card. When FIFO data count is less than or equal to this number, DMA/FIFO request is raised. If Interrupt is enabled, then interrupt occurs. During end of packet, request or interrupt is generated, regardless of threshold programming.In non-DMA mode, when transmit FIFO threshold (TXDR) interrupt is enabled, then interrupt is generated instead of DMA request. During end of packet, on last interrupt, host is responsible for filling FIFO with only required remaining bytes (not before FIFO is full or after CIU completes data transfers, because FIFO may not be empty). In DMA mode, at end of packet, if last transfer is less than burst size, DMA controller does single cycles until required bytes are transferred.
+ 0
+ 12
+ read-write
+
+
+ RX_WMARK
+ FIFO threshold watermark level when receiving data to card.When FIFO data count reaches greater than this number , DMA/FIFO request is raised. During end of packet, request is generated regardless of threshold programming in order to complete any remaining data.In non-DMA mode, when receiver FIFO threshold (RXDR) interrupt is enabled, then interrupt is generated instead of DMA request.During end of packet, interrupt is not generated if threshold programming is larger than any remaining data. It is responsibility of host to read remaining bytes on seeing Data Transfer Done interrupt.In DMA mode, at end of packet, even if remaining bytes are less than threshold, DMA request does single transfers to flush out any remaining bytes before Data Transfer Done interrupt is set.
+ 16
+ 11
+ read-write
+
+
+ DMA_MULTIPLE_TRANSACTION_SIZE
+ Burst size of multiple transaction, should be programmed same as DMA controller multiple-transaction-size SDHOST_SRC/DEST_MSIZE.
+000: 1-byte transfer;
+001: 4-byte transfer;
+010: 8-byte transfer;
+011: 16-byte transfer;
+100: 32-byte transfer;
+101: 64-byte transfer;
+110: 128-byte transfer;
+111: 256-byte transfer.
+ 28
+ 3
+ read-write
+
+
+
+
+ CDETECT
+ Card detect register
+ 0x50
+ 0x20
+
+
+ CARD_DETECT_N
+ Value on sdhost_card_detect_n input ports (1 bit per card), read-only bits. 0 represents presence of card. Only NUM_CARDS number of bits are implemented.
+ 0
+ 2
+ read-only
+
+
+
+
+ WRTPRT
+ Card write protection (WP) status register
+ 0x54
+ 0x20
+
+
+ WRITE_PROTECT
+ Value on sdhost_card_write_prt input ports (1 bit per card). 1 represents write protection. Only NUM_CARDS number of bits are implemented.
+ 0
+ 2
+ read-only
+
+
+
+
+ TCBCNT
+ Transferred byte count register
+ 0x5C
+ 0x20
+
+
+ TCBCNT
+ Number of bytes transferred by CIU unit to card.
+ 0
+ 32
+ read-only
+
+
+
+
+ TBBCNT
+ Transferred byte count register
+ 0x60
+ 0x20
+
+
+ TBBCNT
+ Number of bytes transferred between Host/DMA memory and BIU FIFO.
+ 0
+ 32
+ read-only
+
+
+
+
+ DEBNCE
+ Debounce filter time configuration register
+ 0x64
+ 0x20
+
+
+ DEBOUNCE_COUNT
+ Number of host clocks (clk) used by debounce filter logic. The typical debounce time is 5 \verb+~+ 25 ms to prevent the card instability when the card is inserted or removed.
+ 0
+ 24
+ read-write
+
+
+
+
+ USRID
+ User ID (scratchpad) register
+ 0x68
+ 0x20
+
+
+ USRID
+ User identification register, value set by user. Can also be used as a scratchpad register by user.
+ 0
+ 32
+ read-write
+
+
+
+
+ VERID
+ Version ID (scratchpad) register
+ 0x6C
+ 0x20
+ 0x5432270A
+
+
+ VERSIONID
+ Hardware version register. Can also be read by fireware.
+ 0
+ 32
+ read-only
+
+
+
+
+ HCON
+ Hardware feature register
+ 0x70
+ 0x20
+ 0x03444CC3
+
+
+ CARD_TYPE
+ Hardware support SDIO and MMC.
+ 0
+ 1
+ read-only
+
+
+ CARD_NUM
+ Support card number is 2.
+ 1
+ 5
+ read-only
+
+
+ BUS_TYPE
+ Register config is APB bus.
+ 6
+ 1
+ read-only
+
+
+ DATA_WIDTH
+ Regisger data widht is 32.
+ 7
+ 3
+ read-only
+
+
+ ADDR_WIDTH
+ Register address width is 32.
+ 10
+ 6
+ read-only
+
+
+ DMA_WIDTH
+ DMA data witdth is 32.
+ 18
+ 3
+ read-only
+
+
+ RAM_INDISE
+ Inside RAM in SDMMC module.
+ 21
+ 1
+ read-only
+
+
+ HOLD
+ Have a hold regiser in data path .
+ 22
+ 1
+ read-only
+
+
+ NUM_CLK_DIV
+ Have 4 clk divider in design .
+ 24
+ 2
+ read-only
+
+
+
+
+ UHS
+ UHS-1 register
+ 0x74
+ 0x20
+
+
+ DDR
+ DDR mode selecton,1 bit for each card.
+0-Non-DDR mdoe.
+1-DDR mdoe.
+ 16
+ 2
+ read-write
+
+
+
+
+ RST_N
+ Card reset register
+ 0x78
+ 0x20
+ 0x00000001
+
+
+ CARD_RESET
+ Hardware reset.
+1: Active mode;
+0: Reset.
+These bits cause the cards to enter pre-idle state, which requires them to be re-initialized. SDHOST_RST_CARD_RESET[0] should be set to 1'b0 to reset card0, SDHOST_RST_CARD_RESET[1] should be set to 1'b0 to reset card1.
+ 0
+ 2
+ read-write
+
+
+
+
+ BMOD
+ Burst mode transfer configuration register
+ 0x80
+ 0x20
+
+
+ SWR
+ Software Reset. When set, the DMA Controller resets all its internal registers. It is automatically cleared after one clock cycle.
+ 0
+ 1
+ read-write
+
+
+ FB
+ Fixed Burst. Controls whether the AHB Master interface performs fixed burst transfers or not. When set, the AHB will use only SINGLE, INCR4, INCR8 or INCR16 during start of normal burst transfers. When reset, the AHB will use SINGLE and INCR burst transfer operations.
+ 1
+ 1
+ read-write
+
+
+ DE
+ IDMAC Enable. When set, the IDMAC is enabled.
+ 7
+ 1
+ read-write
+
+
+ PBL
+ Programmable Burst Length. These bits indicate the maximum number of beats to be performed in one IDMAC???Internal DMA Control???transaction. The IDMAC will always attempt to burst as specified in PBL each time it starts a burst transfer on the host bus. The permissible values are 1, 4, 8, 16, 32, 64, 128 and 256. This value is the mirror of MSIZE of FIFOTH register. In order to change this value, write the required value to FIFOTH register. This is an encode value as follows:
+000: 1-byte transfer;
+001: 4-byte transfer;
+010: 8-byte transfer;
+011: 16-byte transfer;
+100: 32-byte transfer;
+101: 64-byte transfer;
+110: 128-byte transfer;
+111: 256-byte transfer.
+PBL is a read-only value and is applicable only for data access, it does not apply to descriptor access.
+ 8
+ 3
+ read-write
+
+
+
+
+ PLDMND
+ Poll demand configuration register
+ 0x84
+ 0x20
+
+
+ PD
+ Poll Demand. If the OWNER bit of a descriptor is not set, the FSM goes to the Suspend state. The host needs to write any value into this register for the IDMAC FSM to resume normal descriptor fetch operation. This is a write only .
+ 0
+ 32
+ write-only
+
+
+
+
+ DBADDR
+ Descriptor base address register
+ 0x88
+ 0x20
+
+
+ DBADDR
+ Start of Descriptor List. Contains the base address of the First Descriptor. The LSB bits [1:0] are ignored and taken as all-zero by the IDMAC internally. Hence these LSB bits may be treated as read-only.
+ 0
+ 32
+ read-write
+
+
+
+
+ IDSTS
+ IDMAC status register
+ 0x8C
+ 0x20
+
+
+ TI
+ Transmit Interrupt. Indicates that data transmission is finished for a descriptor. Writing 1 clears this bit.
+ 0
+ 1
+ read-write
+
+
+ RI
+ Receive Interrupt. Indicates the completion of data reception for a descriptor. Writing 1 clears this bit.
+ 1
+ 1
+ read-write
+
+
+ FBE
+ Fatal Bus Error Interrupt. Indicates that a Bus Error occurred (IDSTS[12:10]) . When this bit is set, the DMA disables all its bus accesses. Writing 1 clears this bit.
+ 2
+ 1
+ read-write
+
+
+ DU
+ Descriptor Unavailable Interrupt. This bit is set when the descriptor is unavailable due to OWNER bit = 0 (DES0[31] = 0). Writing 1 clears this bit.
+ 4
+ 1
+ read-write
+
+
+ CES
+ Card Error Summary. Indicates the status of the transaction to/from the card, also present in RINTSTS. Indicates the logical OR of the following bits:
+EBE : End Bit Error;
+RTO : Response Timeout/Boot Ack Timeout;
+RCRC : Response CRC;
+SBE : Start Bit Error;
+DRTO : Data Read Timeout/BDS timeout;
+DCRC : Data CRC for Receive;
+RE : Response Error.
+Writing 1 clears this bit. The abort condition of the IDMAC depends on the setting of this CES bit. If the CES bit is enabled, then the IDMAC aborts on a response error.
+ 5
+ 1
+ read-write
+
+
+ NIS
+ Normal Interrupt Summary. Logical OR of the following: IDSTS[0] : Transmit Interrupt, IDSTS[1] : Receive Interrupt. Only unmasked bits affect this bit. This is a sticky bit and must be cleared each time a corresponding bit that causes NIS to be set is cleared. Writing 1 clears this bit.
+ 8
+ 1
+ read-write
+
+
+ AIS
+ Abnormal Interrupt Summary. Logical OR of the following: IDSTS[2] : Fatal Bus Interrupt, IDSTS[4] : DU bit Interrupt. Only unmasked bits affect this bit. This is a sticky bit and must be cleared each time a corresponding bit that causes AIS to be set is cleared. Writing 1 clears this bit.
+ 9
+ 1
+ read-write
+
+
+ FBE_CODE
+ Fatal Bus Error Code. Indicates the type of error that caused a Bus Error. Valid only when the Fatal Bus Error bit IDSTS[2] is set. This field does not generate an interrupt.
+001: Host Abort received during transmission;
+010: Host Abort received during reception;
+Others: Reserved.
+ 10
+ 3
+ read-write
+
+
+ FSM
+ DMAC FSM present state.
+0: DMA_IDLE (idle state);
+1: DMA_SUSPEND (suspend state);
+2: DESC_RD (descriptor reading state);
+3: DESC_CHK (descriptor checking state);
+4: DMA_RD_REQ_WAIT (read-data request waiting state);
+5: DMA_WR_REQ_WAIT (write-data request waiting state);
+6: DMA_RD (data-read state);
+7: DMA_WR (data-write state);
+8: DESC_CLOSE (descriptor close state).
+ 13
+ 4
+ read-write
+
+
+
+
+ IDINTEN
+ IDMAC interrupt enable register
+ 0x90
+ 0x20
+
+
+ TI
+ Transmit Interrupt Enable. When set with Normal Interrupt Summary Enable, Transmit Interrupt is enabled. When reset, Transmit Interrupt is disabled.
+ 0
+ 1
+ read-write
+
+
+ RI
+ Receive Interrupt Enable. When set with Normal Interrupt Summary Enable, Receive Interrupt is enabled. When reset, Receive Interrupt is disabled.
+ 1
+ 1
+ read-write
+
+
+ FBE
+ Fatal Bus Error Enable. When set with Abnormal Interrupt Summary Enable, the Fatal Bus Error Interrupt is enabled. When reset, Fatal Bus Error Enable Interrupt is disabled.
+ 2
+ 1
+ read-write
+
+
+ DU
+ Descriptor Unavailable Interrupt. When set along with Abnormal Interrupt Summary Enable, the DU interrupt is enabled.
+ 4
+ 1
+ read-write
+
+
+ CES
+ Card Error summary Interrupt Enable. When set, it enables the Card Interrupt summary.
+ 5
+ 1
+ read-write
+
+
+ NI
+ Normal Interrupt Summary Enable. When set, a normal interrupt is enabled. When reset, a normal interrupt is disabled. This bit enables the following bits:
+IDINTEN[0]: Transmit Interrupt;
+IDINTEN[1]: Receive Interrupt.
+ 8
+ 1
+ read-write
+
+
+ AI
+ Abnormal Interrupt Summary Enable. When set, an abnormal interrupt is enabled. This bit enables the following bits:
+IDINTEN[2]: Fatal Bus Error Interrupt;
+IDINTEN[4]: DU Interrupt.
+ 9
+ 1
+ read-write
+
+
+
+
+ DSCADDR
+ Host descriptor address pointer
+ 0x94
+ 0x20
+
+
+ DSCADDR
+ Host Descriptor Address Pointer, updated by IDMAC during operation and cleared on reset. This register points to the start address of the current descriptor read by the IDMAC.
+ 0
+ 32
+ read-only
+
+
+
+
+ BUFADDR
+ Host buffer address pointer register
+ 0x98
+ 0x20
+
+
+ BUFADDR
+ Host Buffer Address Pointer, updated by IDMAC during operation and cleared on reset. This register points to the current Data Buffer Address being accessed by the IDMAC.
+ 0
+ 32
+ read-only
+
+
+
+
+ CARDTHRCTL
+ Card Threshold Control register
+ 0x100
+ 0x20
+
+
+ CARDRDTHREN
+ Card read threshold enable.
+1'b0-Card read threshold disabled.
+1'b1-Card read threshold enabled.
+ 0
+ 1
+ read-write
+
+
+ CARDCLRINTEN
+ Busy clear interrupt generation:
+1'b0-Busy clear interrypt disabled.
+1'b1-Busy clear interrypt enabled.
+ 1
+ 1
+ read-write
+
+
+ CARDWRTHREN
+ Applicable when HS400 mode is enabled.
+1'b0-Card write Threshold disabled.
+1'b1-Card write Threshold enabled.
+ 2
+ 1
+ read-write
+
+
+ CARDTHRESHOLD
+ The inside FIFO size is 512,This register is applicable when SDHOST_CARDERTHREN_REG is set to 1 or SDHOST_CARDRDTHREN_REG set to 1.
+ 16
+ 16
+ read-write
+
+
+
+
+ EMMCDDR
+ eMMC DDR register
+ 0x10C
+ 0x20
+
+
+ HALFSTARTBIT
+ Control for start bit detection mechanism duration of start bit.Each bit refers to one slot.Set this bit to 1 for eMMC4.5 and above,set to 0 for SD applications.For eMMC4.5,start bit can be:
+1'b0-Full cycle.
+1'b1-less than one full cycle.
+ 0
+ 2
+ read-write
+
+
+ HS400_MODE
+ Set 1 to enable HS400 mode.
+ 31
+ 1
+ read-write
+
+
+
+
+ ENSHIFT
+ Enable Phase Shift register
+ 0x110
+ 0x20
+
+
+ ENABLE_SHIFT
+ Control for the amount of phase shift provided on the default enables in the design.Two bits assigned for each card.
+2'b00-Default phase shift.
+2'b01-Enables shifted to next immediate positive edge.
+2'b10-Enables shifted to next immediate negative edge.
+2'b11-Reserved.
+ 0
+ 4
+ read-write
+
+
+
+
+ BUFFIFO
+ CPU write and read transmit data by FIFO
+ 0x200
+ 0x20
+
+
+ BUFFIFO
+ CPU write and read transmit data by FIFO. This register points to the current Data FIFO .
+ 0
+ 32
+ read-write
+
+
+
+
+ CLK_EDGE_SEL
+ SDIO control register.
+ 0x800
+ 0x20
+ 0x00820200
+
+
+ CCLKIN_EDGE_DRV_SEL
+ It's used to select the clock phase of the output signal from phase 0, phase 90, phase 180, phase 270.
+ 0
+ 3
+ read-write
+
+
+ CCLKIN_EDGE_SAM_SEL
+ It's used to select the clock phase of the input signal from phase 0, phase 90, phase 180, phase 270.
+ 3
+ 3
+ read-write
+
+
+ CCLKIN_EDGE_SLF_SEL
+ It's used to select the clock phase of the internal signal from phase 0, phase 90, phase 180, phase 270.
+ 6
+ 3
+ read-write
+
+
+ CCLLKIN_EDGE_H
+ The high level of the divider clock. The value should be smaller than CCLKIN_EDGE_L.
+ 9
+ 4
+ read-write
+
+
+ CCLLKIN_EDGE_L
+ The low level of the divider clock. The value should be larger than CCLKIN_EDGE_H.
+ 13
+ 4
+ read-write
+
+
+ CCLLKIN_EDGE_N
+ The value should be equal to CCLKIN_EDGE_L.
+ 17
+ 4
+ read-write
+
+
+ ESDIO_MODE
+ Enable esdio mode.
+ 21
+ 1
+ read-write
+
+
+ ESD_MODE
+ Enable esd mode.
+ 22
+ 1
+ read-write
+
+
+ CCLK_EN
+ Sdio clock enable
+ 23
+ 1
+ read-write
+
+
+
+
+
+
+ SENS
+ Peripheral SENS
+ SENS
+ 0x3FF48800
+
+ 0x0
+ 0xA8
+ registers
+
+
+
+ SAR_READ_CTRL
+ 0x0
+ 0x20
+ 0x00070902
+
+
+ SAR1_CLK_DIV
+ clock divider
+ 0
+ 8
+ read-write
+
+
+ SAR1_SAMPLE_CYCLE
+ sample cycles for SAR ADC1
+ 8
+ 8
+ read-write
+
+
+ SAR1_SAMPLE_BIT
+ 00: for 9-bit width 01: for 10-bit width 10: for 11-bit width 11: for 12-bit width
+ 16
+ 2
+ read-write
+
+
+ SAR1_CLK_GATED
+ 18
+ 1
+ read-write
+
+
+ SAR1_SAMPLE_NUM
+ 19
+ 8
+ read-write
+
+
+ SAR1_DIG_FORCE
+ 1: SAR ADC1 controlled by DIG ADC1 CTRL 0: SAR ADC1 controlled by RTC ADC1 CTRL
+ 27
+ 1
+ read-write
+
+
+ SAR1_DATA_INV
+ Invert SAR ADC1 data
+ 28
+ 1
+ read-write
+
+
+
+
+ SAR_READ_STATUS1
+ 0x4
+ 0x20
+
+
+ SAR1_READER_STATUS
+ 0
+ 32
+ read-only
+
+
+
+
+ SAR_MEAS_WAIT1
+ 0x8
+ 0x20
+ 0x000A000A
+
+
+ SAR_AMP_WAIT1
+ 0
+ 16
+ read-write
+
+
+ SAR_AMP_WAIT2
+ 16
+ 16
+ read-write
+
+
+
+
+ SAR_MEAS_WAIT2
+ 0xC
+ 0x20
+ 0x0020000A
+
+
+ FORCE_XPD_SAR_SW
+ 0
+ 1
+ read-write
+
+
+ SAR_AMP_WAIT3
+ 0
+ 16
+ read-write
+
+
+ FORCE_XPD_AMP
+ 16
+ 2
+ read-write
+
+
+ FORCE_XPD_SAR
+ 18
+ 2
+ read-write
+
+
+ SAR2_RSTB_WAIT
+ 20
+ 8
+ read-write
+
+
+
+
+ SAR_MEAS_CTRL
+ 0x10
+ 0x20
+ 0x0707338F
+
+
+ XPD_SAR_AMP_FSM
+ 0
+ 4
+ read-write
+
+
+ AMP_RST_FB_FSM
+ 4
+ 4
+ read-write
+
+
+ AMP_SHORT_REF_FSM
+ 8
+ 4
+ read-write
+
+
+ AMP_SHORT_REF_GND_FSM
+ 12
+ 4
+ read-write
+
+
+ XPD_SAR_FSM
+ 16
+ 4
+ read-write
+
+
+ SAR_RSTB_FSM
+ 20
+ 4
+ read-write
+
+
+ SAR2_XPD_WAIT
+ 24
+ 8
+ read-write
+
+
+
+
+ SAR_READ_STATUS2
+ 0x14
+ 0x20
+
+
+ SAR2_READER_STATUS
+ 0
+ 32
+ read-only
+
+
+
+
+ ULP_CP_SLEEP_CYC0
+ 0x18
+ 0x20
+ 0x000000C8
+
+
+ SLEEP_CYCLES_S0
+ sleep cycles for ULP-coprocessor timer
+ 0
+ 32
+ read-write
+
+
+
+
+ ULP_CP_SLEEP_CYC1
+ 0x1C
+ 0x20
+ 0x00000064
+
+
+ SLEEP_CYCLES_S1
+ 0
+ 32
+ read-write
+
+
+
+
+ ULP_CP_SLEEP_CYC2
+ 0x20
+ 0x20
+ 0x00000032
+
+
+ SLEEP_CYCLES_S2
+ 0
+ 32
+ read-write
+
+
+
+
+ ULP_CP_SLEEP_CYC3
+ 0x24
+ 0x20
+ 0x00000028
+
+
+ SLEEP_CYCLES_S3
+ 0
+ 32
+ read-write
+
+
+
+
+ ULP_CP_SLEEP_CYC4
+ 0x28
+ 0x20
+ 0x00000014
+
+
+ SLEEP_CYCLES_S4
+ 0
+ 32
+ read-write
+
+
+
+
+ SAR_START_FORCE
+ 0x2C
+ 0x20
+ 0x0000000F
+
+
+ SAR1_BIT_WIDTH
+ 00: 9 bit 01: 10 bits 10: 11bits 11: 12bits
+ 0
+ 2
+ read-write
+
+
+ SAR2_BIT_WIDTH
+ 00: 9 bit 01: 10 bits 10: 11bits 11: 12bits
+ 2
+ 2
+ read-write
+
+
+ SAR2_EN_TEST
+ SAR2_EN_TEST only active when reg_sar2_dig_force = 0
+ 4
+ 1
+ read-write
+
+
+ SAR2_PWDET_CCT
+ SAR2_PWDET_CCT PA power detector capacitance tuning.
+ 5
+ 3
+ read-write
+
+
+ ULP_CP_FORCE_START_TOP
+ 1: ULP-coprocessor is started by SW 0: ULP-coprocessor is started by timer
+ 8
+ 1
+ read-write
+
+
+ ULP_CP_START_TOP
+ Write 1 to start ULP-coprocessor only active when reg_ulp_cp_force_start_top = 1
+ 9
+ 1
+ read-write
+
+
+ SARCLK_EN
+ 10
+ 1
+ read-write
+
+
+ PC_INIT
+ initialized PC for ULP-coprocessor
+ 11
+ 11
+ read-write
+
+
+ SAR2_STOP
+ stop SAR ADC2 conversion
+ 22
+ 1
+ read-write
+
+
+ SAR1_STOP
+ stop SAR ADC1 conversion
+ 23
+ 1
+ read-write
+
+
+ SAR2_PWDET_EN
+ N/A
+ 24
+ 1
+ read-write
+
+
+
+
+ SAR_MEM_WR_CTRL
+ 0x30
+ 0x20
+ 0x00100200
+
+
+ MEM_WR_ADDR_INIT
+ 0
+ 11
+ read-write
+
+
+ MEM_WR_ADDR_SIZE
+ 11
+ 11
+ read-write
+
+
+ RTC_MEM_WR_OFFST_CLR
+ 22
+ 1
+ write-only
+
+
+
+
+ SAR_ATTEN1
+ 0x34
+ 0x20
+ 0xFFFFFFFF
+
+
+ SAR1_ATTEN
+ 2-bit attenuation for each pad 11:1dB 10:6dB 01:3dB 00:0dB
+ 0
+ 32
+ read-write
+
+
+
+
+ SAR_ATTEN2
+ 0x38
+ 0x20
+ 0xFFFFFFFF
+
+
+ SAR2_ATTEN
+ 2-bit attenuation for each pad 11:1dB 10:6dB 01:3dB 00:0dB
+ 0
+ 32
+ read-write
+
+
+
+
+ SAR_SLAVE_ADDR1
+ 0x3C
+ 0x20
+
+
+ I2C_SLAVE_ADDR1
+ 0
+ 11
+ read-write
+
+
+ I2C_SLAVE_ADDR0
+ 11
+ 11
+ read-write
+
+
+ MEAS_STATUS
+ 22
+ 8
+ read-only
+
+
+
+
+ SAR_SLAVE_ADDR2
+ 0x40
+ 0x20
+
+
+ I2C_SLAVE_ADDR3
+ 0
+ 11
+ read-write
+
+
+ I2C_SLAVE_ADDR2
+ 11
+ 11
+ read-write
+
+
+
+
+ SAR_SLAVE_ADDR3
+ 0x44
+ 0x20
+
+
+ I2C_SLAVE_ADDR5
+ 0
+ 11
+ read-write
+
+
+ I2C_SLAVE_ADDR4
+ 11
+ 11
+ read-write
+
+
+ TSENS_OUT
+ temperature sensor data out
+ 22
+ 8
+ read-only
+
+
+ TSENS_RDY_OUT
+ indicate temperature sensor out ready
+ 30
+ 1
+ read-only
+
+
+
+
+ SAR_SLAVE_ADDR4
+ 0x48
+ 0x20
+
+
+ I2C_SLAVE_ADDR7
+ 0
+ 11
+ read-write
+
+
+ I2C_SLAVE_ADDR6
+ 11
+ 11
+ read-write
+
+
+ I2C_RDATA
+ I2C read data
+ 22
+ 8
+ read-only
+
+
+ I2C_DONE
+ indicate I2C done
+ 30
+ 1
+ read-only
+
+
+
+
+ SAR_TSENS_CTRL
+ 0x4C
+ 0x20
+ 0x00066002
+
+
+ TSENS_XPD_WAIT
+ 0
+ 12
+ read-write
+
+
+ TSENS_XPD_FORCE
+ 12
+ 1
+ read-write
+
+
+ TSENS_CLK_INV
+ 13
+ 1
+ read-write
+
+
+ TSENS_CLK_GATED
+ 14
+ 1
+ read-write
+
+
+ TSENS_IN_INV
+ invert temperature sensor data
+ 15
+ 1
+ read-write
+
+
+ TSENS_CLK_DIV
+ temperature sensor clock divider
+ 16
+ 8
+ read-write
+
+
+ TSENS_POWER_UP
+ temperature sensor power up
+ 24
+ 1
+ read-write
+
+
+ TSENS_POWER_UP_FORCE
+ 1: dump out & power up controlled by SW 0: by FSM
+ 25
+ 1
+ read-write
+
+
+ TSENS_DUMP_OUT
+ temperature sensor dump out only active when reg_tsens_power_up_force = 1
+ 26
+ 1
+ read-write
+
+
+
+
+ SAR_I2C_CTRL
+ 0x50
+ 0x20
+
+
+ SAR_I2C_CTRL
+ I2C control data only active when reg_sar_i2c_start_force = 1
+ 0
+ 28
+ read-write
+
+
+ SAR_I2C_START
+ start I2C only active when reg_sar_i2c_start_force = 1
+ 28
+ 1
+ read-write
+
+
+ SAR_I2C_START_FORCE
+ 1: I2C started by SW 0: I2C started by FSM
+ 29
+ 1
+ read-write
+
+
+
+
+ SAR_MEAS_START1
+ 0x54
+ 0x20
+
+
+ MEAS1_DATA_SAR
+ SAR ADC1 data
+ 0
+ 16
+ read-only
+
+
+ MEAS1_DONE_SAR
+ SAR ADC1 conversion done indication
+ 16
+ 1
+ read-only
+
+
+ MEAS1_START_SAR
+ SAR ADC1 controller (in RTC) starts conversion only active when reg_meas1_start_force = 1
+ 17
+ 1
+ read-write
+
+
+ MEAS1_START_FORCE
+ 1: SAR ADC1 controller (in RTC) is started by SW 0: SAR ADC1 controller is started by ULP-coprocessor
+ 18
+ 1
+ read-write
+
+
+ SAR1_EN_PAD
+ SAR ADC1 pad enable bitmap only active when reg_sar1_en_pad_force = 1
+ 19
+ 12
+ read-write
+
+
+ SAR1_EN_PAD_FORCE
+ 1: SAR ADC1 pad enable bitmap is controlled by SW 0: SAR ADC1 pad enable bitmap is controlled by ULP-coprocessor
+ 31
+ 1
+ read-write
+
+
+
+
+ SAR_TOUCH_CTRL1
+ 0x58
+ 0x20
+ 0x02041000
+
+
+ TOUCH_MEAS_DELAY
+ the meas length (in 8MHz)
+ 0
+ 16
+ read-write
+
+
+ TOUCH_XPD_WAIT
+ the waiting cycles (in 8MHz) between TOUCH_START and TOUCH_XPD
+ 16
+ 8
+ read-write
+
+
+ TOUCH_OUT_SEL
+ 1: when the counter is greater then the threshold the touch pad is considered as "touched" 0: when the counter is less than the threshold the touch pad is considered as "touched"
+ 24
+ 1
+ read-write
+
+
+ TOUCH_OUT_1EN
+ 1: wakeup interrupt is generated if SET1 is "touched" 0: wakeup interrupt is generated only if SET1 & SET2 is both "touched"
+ 25
+ 1
+ read-write
+
+
+ XPD_HALL_FORCE
+ 1: XPD HALL is controlled by SW. 0: XPD HALL is controlled by FSM in ULP-coprocessor
+ 26
+ 1
+ read-write
+
+
+ HALL_PHASE_FORCE
+ 1: HALL PHASE is controlled by SW 0: HALL PHASE is controlled by FSM in ULP-coprocessor
+ 27
+ 1
+ read-write
+
+
+
+
+ SAR_TOUCH_THRES1
+ 0x5C
+ 0x20
+
+
+ TOUCH_OUT_TH1
+ the threshold for touch pad 1
+ 0
+ 16
+ read-write
+
+
+ TOUCH_OUT_TH0
+ the threshold for touch pad 0
+ 16
+ 16
+ read-write
+
+
+
+
+ SAR_TOUCH_THRES2
+ 0x60
+ 0x20
+
+
+ TOUCH_OUT_TH3
+ the threshold for touch pad 3
+ 0
+ 16
+ read-write
+
+
+ TOUCH_OUT_TH2
+ the threshold for touch pad 2
+ 16
+ 16
+ read-write
+
+
+
+
+ SAR_TOUCH_THRES3
+ 0x64
+ 0x20
+
+
+ TOUCH_OUT_TH5
+ the threshold for touch pad 5
+ 0
+ 16
+ read-write
+
+
+ TOUCH_OUT_TH4
+ the threshold for touch pad 4
+ 16
+ 16
+ read-write
+
+
+
+
+ SAR_TOUCH_THRES4
+ 0x68
+ 0x20
+
+
+ TOUCH_OUT_TH7
+ the threshold for touch pad 7
+ 0
+ 16
+ read-write
+
+
+ TOUCH_OUT_TH6
+ the threshold for touch pad 6
+ 16
+ 16
+ read-write
+
+
+
+
+ SAR_TOUCH_THRES5
+ 0x6C
+ 0x20
+
+
+ TOUCH_OUT_TH9
+ the threshold for touch pad 9
+ 0
+ 16
+ read-write
+
+
+ TOUCH_OUT_TH8
+ the threshold for touch pad 8
+ 16
+ 16
+ read-write
+
+
+
+
+ SAR_TOUCH_OUT1
+ 0x70
+ 0x20
+
+
+ TOUCH_MEAS_OUT1
+ the counter for touch pad 1
+ 0
+ 16
+ read-only
+
+
+ TOUCH_MEAS_OUT0
+ the counter for touch pad 0
+ 16
+ 16
+ read-only
+
+
+
+
+ SAR_TOUCH_OUT2
+ 0x74
+ 0x20
+
+
+ TOUCH_MEAS_OUT3
+ the counter for touch pad 3
+ 0
+ 16
+ read-only
+
+
+ TOUCH_MEAS_OUT2
+ the counter for touch pad 2
+ 16
+ 16
+ read-only
+
+
+
+
+ SAR_TOUCH_OUT3
+ 0x78
+ 0x20
+
+
+ TOUCH_MEAS_OUT5
+ the counter for touch pad 5
+ 0
+ 16
+ read-only
+
+
+ TOUCH_MEAS_OUT4
+ the counter for touch pad 4
+ 16
+ 16
+ read-only
+
+
+
+
+ SAR_TOUCH_OUT4
+ 0x7C
+ 0x20
+
+
+ TOUCH_MEAS_OUT7
+ the counter for touch pad 7
+ 0
+ 16
+ read-only
+
+
+ TOUCH_MEAS_OUT6
+ the counter for touch pad 6
+ 16
+ 16
+ read-only
+
+
+
+
+ SAR_TOUCH_OUT5
+ 0x80
+ 0x20
+
+
+ TOUCH_MEAS_OUT9
+ the counter for touch pad 9
+ 0
+ 16
+ read-only
+
+
+ TOUCH_MEAS_OUT8
+ the counter for touch pad 8
+ 16
+ 16
+ read-only
+
+
+
+
+ SAR_TOUCH_CTRL2
+ 0x84
+ 0x20
+ 0x00400800
+
+
+ TOUCH_MEAS_EN
+ 10-bit register to indicate which pads are "touched"
+ 0
+ 10
+ read-only
+
+
+ TOUCH_MEAS_DONE
+ fsm set 1 to indicate touch touch meas is done
+ 10
+ 1
+ read-only
+
+
+ TOUCH_START_FSM_EN
+ 1: TOUCH_START & TOUCH_XPD is controlled by touch fsm 0: TOUCH_START & TOUCH_XPD is controlled by registers
+ 11
+ 1
+ read-write
+
+
+ TOUCH_START_EN
+ 1: start touch fsm valid when reg_touch_start_force is set
+ 12
+ 1
+ read-write
+
+
+ TOUCH_START_FORCE
+ 1: to start touch fsm by SW 0: to start touch fsm by timer
+ 13
+ 1
+ read-write
+
+
+ TOUCH_SLEEP_CYCLES
+ sleep cycles for timer
+ 14
+ 16
+ read-write
+
+
+ TOUCH_MEAS_EN_CLR
+ to clear reg_touch_meas_en
+ 30
+ 1
+ write-only
+
+
+
+
+ SAR_TOUCH_ENABLE
+ 0x8C
+ 0x20
+ 0x3FFFFFFF
+
+
+ TOUCH_PAD_WORKEN
+ Bitmap defining the working set during the measurement.
+ 0
+ 10
+ read-write
+
+
+ TOUCH_PAD_OUTEN2
+ Bitmap defining SET2 for generating wakeup interrupt. SET2 is "touched" only if at least one of touch pad in SET2 is "touched".
+ 10
+ 10
+ read-write
+
+
+ TOUCH_PAD_OUTEN1
+ Bitmap defining SET1 for generating wakeup interrupt. SET1 is "touched" only if at least one of touch pad in SET1 is "touched".
+ 20
+ 10
+ read-write
+
+
+
+
+ SAR_READ_CTRL2
+ 0x90
+ 0x20
+ 0x00070902
+
+
+ SAR2_CLK_DIV
+ clock divider
+ 0
+ 8
+ read-write
+
+
+ SAR2_SAMPLE_CYCLE
+ sample cycles for SAR ADC2
+ 8
+ 8
+ read-write
+
+
+ SAR2_SAMPLE_BIT
+ 00: for 9-bit width 01: for 10-bit width 10: for 11-bit width 11: for 12-bit width
+ 16
+ 2
+ read-write
+
+
+ SAR2_CLK_GATED
+ 18
+ 1
+ read-write
+
+
+ SAR2_SAMPLE_NUM
+ 19
+ 8
+ read-write
+
+
+ SAR2_PWDET_FORCE
+ 27
+ 1
+ read-write
+
+
+ SAR2_DIG_FORCE
+ 1: SAR ADC2 controlled by DIG ADC2 CTRL or PWDET CTRL 0: SAR ADC2 controlled by RTC ADC2 CTRL
+ 28
+ 1
+ read-write
+
+
+ SAR2_DATA_INV
+ Invert SAR ADC2 data
+ 29
+ 1
+ read-write
+
+
+
+
+ SAR_MEAS_START2
+ 0x94
+ 0x20
+
+
+ MEAS2_DATA_SAR
+ SAR ADC2 data
+ 0
+ 16
+ read-only
+
+
+ MEAS2_DONE_SAR
+ SAR ADC2 conversion done indication
+ 16
+ 1
+ read-only
+
+
+ MEAS2_START_SAR
+ SAR ADC2 controller (in RTC) starts conversion only active when reg_meas2_start_force = 1
+ 17
+ 1
+ read-write
+
+
+ MEAS2_START_FORCE
+ 1: SAR ADC2 controller (in RTC) is started by SW 0: SAR ADC2 controller is started by ULP-coprocessor
+ 18
+ 1
+ read-write
+
+
+ SAR2_EN_PAD
+ SAR ADC2 pad enable bitmap only active when reg_sar2_en_pad_force = 1
+ 19
+ 12
+ read-write
+
+
+ SAR2_EN_PAD_FORCE
+ 1: SAR ADC2 pad enable bitmap is controlled by SW 0: SAR ADC2 pad enable bitmap is controlled by ULP-coprocessor
+ 31
+ 1
+ read-write
+
+
+
+
+ SAR_DAC_CTRL1
+ 0x98
+ 0x20
+
+
+ SW_FSTEP
+ frequency step for CW generator can be used to adjust the frequency
+ 0
+ 16
+ read-write
+
+
+ SW_TONE_EN
+ 1: enable CW generator 0: disable CW generator
+ 16
+ 1
+ read-write
+
+
+ DEBUG_BIT_SEL
+ 17
+ 5
+ read-write
+
+
+ DAC_DIG_FORCE
+ 1: DAC1 & DAC2 use DMA 0: DAC1 & DAC2 do not use DMA
+ 22
+ 1
+ read-write
+
+
+ DAC_CLK_FORCE_LOW
+ 1: force PDAC_CLK to low
+ 23
+ 1
+ read-write
+
+
+ DAC_CLK_FORCE_HIGH
+ 1: force PDAC_CLK to high
+ 24
+ 1
+ read-write
+
+
+ DAC_CLK_INV
+ 1: invert PDAC_CLK
+ 25
+ 1
+ read-write
+
+
+
+
+ SAR_DAC_CTRL2
+ 0x9C
+ 0x20
+ 0x03000000
+
+
+ DAC_DC1
+ DC offset for DAC1 CW generator
+ 0
+ 8
+ read-write
+
+
+ DAC_DC2
+ DC offset for DAC2 CW generator
+ 8
+ 8
+ read-write
+
+
+ DAC_SCALE1
+ 00: no scale 01: scale to 1/2 10: scale to 1/4 scale to 1/8
+ 16
+ 2
+ read-write
+
+
+ DAC_SCALE2
+ 00: no scale 01: scale to 1/2 10: scale to 1/4 scale to 1/8
+ 18
+ 2
+ read-write
+
+
+ DAC_INV1
+ 00: do not invert any bits 01: invert all bits 10: invert MSB 11: invert all bits except MSB
+ 20
+ 2
+ read-write
+
+
+ DAC_INV2
+ 00: do not invert any bits 01: invert all bits 10: invert MSB 11: invert all bits except MSB
+ 22
+ 2
+ read-write
+
+
+ DAC_CW_EN1
+ 1: to select CW generator as source to PDAC1_DAC[7:0] 0: to select register reg_pdac1_dac[7:0] as source to PDAC1_DAC[7:0]
+ 24
+ 1
+ read-write
+
+
+ DAC_CW_EN2
+ 1: to select CW generator as source to PDAC2_DAC[7:0] 0: to select register reg_pdac2_dac[7:0] as source to PDAC2_DAC[7:0]
+ 25
+ 1
+ read-write
+
+
+
+
+ SAR_MEAS_CTRL2
+ 0xA0
+ 0x20
+ 0x00000003
+
+
+ SAR1_DAC_XPD_FSM
+ 0
+ 4
+ read-write
+
+
+ SAR1_DAC_XPD_FSM_IDLE
+ 4
+ 1
+ read-write
+
+
+ XPD_SAR_AMP_FSM_IDLE
+ 5
+ 1
+ read-write
+
+
+ AMP_RST_FB_FSM_IDLE
+ 6
+ 1
+ read-write
+
+
+ AMP_SHORT_REF_FSM_IDLE
+ 7
+ 1
+ read-write
+
+
+ AMP_SHORT_REF_GND_FSM_IDLE
+ 8
+ 1
+ read-write
+
+
+ XPD_SAR_FSM_IDLE
+ 9
+ 1
+ read-write
+
+
+ SAR_RSTB_FSM_IDLE
+ 10
+ 1
+ read-write
+
+
+ SAR2_RSTB_FORCE
+ 11
+ 2
+ read-write
+
+
+ AMP_RST_FB_FORCE
+ 13
+ 2
+ read-write
+
+
+ AMP_SHORT_REF_FORCE
+ 15
+ 2
+ read-write
+
+
+ AMP_SHORT_REF_GND_FORCE
+ 17
+ 2
+ read-write
+
+
+
+
+ SAR_NOUSE
+ 0xF8
+ 0x20
+
+
+ SAR_NOUSE
+ 0
+ 32
+ read-write
+
+
+
+
+ SARDATE
+ 0xFC
+ 0x20
+ 0x01605180
+
+
+ SAR_DATE
+ 0
+ 28
+ read-write
+
+
+
+
+
+
+ SHA
+ SHA (Secure Hash Algorithm) Accelerator
+ SHA
+ 0x3FF03000
+
+ 0x0
+ 0xC0
+ registers
+
+
+
+ 32
+ 0x4
+ TEXT_%s
+ 0x0
+ 0x20
+
+
+ TEXT
+ SHA Message block and hash result register.
+ 0
+ 8
+ read-write
+
+
+
+
+ SHA1_START
+ 0x80
+ 0x20
+
+
+ SHA1_START
+ Write 1 to start an SHA-1 operation on the first message block.
+ 0
+ 1
+ write-only
+
+
+
+
+ SHA1_CONTINUE
+ 0x80
+ 0x20
+
+
+ SHA1_CONTINUE
+ Write 1 to continue the SHA-1 operation with subsequent blocks.
+ 0
+ 1
+ write-only
+
+
+
+
+ SHA1_LOAD
+ 0x88
+ 0x20
+
+
+ SHA1_LOAD
+ Write 1 to finish the SHA-1 operation to calculate the final message hash.
+ 0
+ 1
+ write-only
+
+
+
+
+ SHA1_BUSY
+ 0x8C
+ 0x20
+
+
+ SHA1_BUSY
+ SHA-1 operation status: 1 if the SHA accelerator is processing data, 0 if it is idle.
+ 0
+ 1
+ write-only
+
+
+
+
+ SHA256_START
+ 0x90
+ 0x20
+
+
+ SHA256_START
+ Write 1 to start an SHA-256 operation on the first message block.
+ 0
+ 1
+ write-only
+
+
+
+
+ SHA256_LOAD
+ 0x90
+ 0x20
+
+
+ SHA256_LOAD
+ Write 1 to finish the SHA-256 operation to calculate the final message hash.
+ 0
+ 1
+ write-only
+
+
+
+
+ SHA256_CONTINUE
+ 0x94
+ 0x20
+
+
+ SHA256_CONTINUE
+ Write 1 to continue the SHA-256 operation with subsequent blocks.
+ 0
+ 1
+ write-only
+
+
+
+
+ SHA256_BUSY
+ 0x9C
+ 0x20
+
+
+ SHA256_BUSY
+ SHA-256 operation status: 1 if the SHA accelerator is processing data, 0 if it is idle.
+ 0
+ 1
+ read-only
+
+
+
+
+ SHA384_START
+ 0xA0
+ 0x20
+
+
+ SHA384_START
+ Write 1 to start an SHA-384 operation on the first message block.
+ 0
+ 1
+ write-only
+
+
+
+
+ SHA384_CONTINUE
+ 0xA4
+ 0x20
+
+
+ SHA384_CONTINUE
+ Write 1 to continue the SHA-384 operation with subsequent blocks.
+ 0
+ 1
+ write-only
+
+
+
+
+ SHA384_LOAD
+ 0xA8
+ 0x20
+
+
+ SHA384_LOAD
+ Write 1 to finish the SHA-384 operation to calculate the final message hash.
+ 0
+ 1
+ write-only
+
+
+
+
+ SHA384_BUSY
+ 0xAC
+ 0x20
+
+
+ SHA384_BUSY
+ SHA-384 operation status: 1 if the SHA accelerator is processing data, 0 if it is idle.
+ 0
+ 1
+ read-only
+
+
+
+
+ SHA512_START
+ 0xB0
+ 0x20
+
+
+ SHA512_START
+ Write 1 to start an SHA-512 operation on the first message block.
+ 0
+ 1
+ write-only
+
+
+
+
+ SHA512_CONTINUE
+ 0xB4
+ 0x20
+
+
+ SHA512_CONTINUE
+ Write 1 to continue the SHA-512 operation with subsequent blocks.
+ 0
+ 1
+ write-only
+
+
+
+
+ SHA512_LOAD
+ 0xB8
+ 0x20
+
+
+ SHA512_LOAD
+ Write 1 to finish the SHA-512 operation to calculate the final message hash.
+ 0
+ 1
+ write-only
+
+
+
+
+ SHA512_BUSY
+ 0xBC
+ 0x20
+
+
+ SHA512_BUSY
+ SHA-512 operation status: 1 if the SHA accelerator is processing data, 0 if it is idle.
+ 0
+ 1
+ read-only
+
+
+
+
+
+
+ SLC
+ Peripheral SLC
+ SLC
+ 0x3FF58000
+
+ 0x0
+ 0x14C
+ registers
+
+
+
+ CONF0
+ 0x0
+ 0x20
+ 0xFF3CFF30
+
+
+ SLC0_TX_RST
+ 0
+ 1
+ read-write
+
+
+ SLC0_RX_RST
+ 1
+ 1
+ read-write
+
+
+ AHBM_FIFO_RST
+ 2
+ 1
+ read-write
+
+
+ AHBM_RST
+ 3
+ 1
+ read-write
+
+
+ SLC0_TX_LOOP_TEST
+ 4
+ 1
+ read-write
+
+
+ SLC0_RX_LOOP_TEST
+ 5
+ 1
+ read-write
+
+
+ SLC0_RX_AUTO_WRBACK
+ 6
+ 1
+ read-write
+
+
+ SLC0_RX_NO_RESTART_CLR
+ 7
+ 1
+ read-write
+
+
+ SLC0_RXDSCR_BURST_EN
+ 8
+ 1
+ read-write
+
+
+ SLC0_RXDATA_BURST_EN
+ 9
+ 1
+ read-write
+
+
+ SLC0_RXLINK_AUTO_RET
+ 10
+ 1
+ read-write
+
+
+ SLC0_TXLINK_AUTO_RET
+ 11
+ 1
+ read-write
+
+
+ SLC0_TXDSCR_BURST_EN
+ 12
+ 1
+ read-write
+
+
+ SLC0_TXDATA_BURST_EN
+ 13
+ 1
+ read-write
+
+
+ SLC0_TOKEN_AUTO_CLR
+ 14
+ 1
+ read-write
+
+
+ SLC0_TOKEN_SEL
+ 15
+ 1
+ read-write
+
+
+ SLC1_TX_RST
+ 16
+ 1
+ read-write
+
+
+ SLC1_RX_RST
+ 17
+ 1
+ read-write
+
+
+ SLC0_WR_RETRY_MASK_EN
+ 18
+ 1
+ read-write
+
+
+ SLC1_WR_RETRY_MASK_EN
+ 19
+ 1
+ read-write
+
+
+ SLC1_TX_LOOP_TEST
+ 20
+ 1
+ read-write
+
+
+ SLC1_RX_LOOP_TEST
+ 21
+ 1
+ read-write
+
+
+ SLC1_RX_AUTO_WRBACK
+ 22
+ 1
+ read-write
+
+
+ SLC1_RX_NO_RESTART_CLR
+ 23
+ 1
+ read-write
+
+
+ SLC1_RXDSCR_BURST_EN
+ 24
+ 1
+ read-write
+
+
+ SLC1_RXDATA_BURST_EN
+ 25
+ 1
+ read-write
+
+
+ SLC1_RXLINK_AUTO_RET
+ 26
+ 1
+ read-write
+
+
+ SLC1_TXLINK_AUTO_RET
+ 27
+ 1
+ read-write
+
+
+ SLC1_TXDSCR_BURST_EN
+ 28
+ 1
+ read-write
+
+
+ SLC1_TXDATA_BURST_EN
+ 29
+ 1
+ read-write
+
+
+ SLC1_TOKEN_AUTO_CLR
+ 30
+ 1
+ read-write
+
+
+ SLC1_TOKEN_SEL
+ 31
+ 1
+ read-write
+
+
+
+
+ _0INT_RAW
+ 0x4
+ 0x20
+
+
+ FRHOST_BIT0_INT_RAW
+ 0
+ 1
+ read-only
+
+
+ FRHOST_BIT1_INT_RAW
+ 1
+ 1
+ read-only
+
+
+ FRHOST_BIT2_INT_RAW
+ 2
+ 1
+ read-only
+
+
+ FRHOST_BIT3_INT_RAW
+ 3
+ 1
+ read-only
+
+
+ FRHOST_BIT4_INT_RAW
+ 4
+ 1
+ read-only
+
+
+ FRHOST_BIT5_INT_RAW
+ 5
+ 1
+ read-only
+
+
+ FRHOST_BIT6_INT_RAW
+ 6
+ 1
+ read-only
+
+
+ FRHOST_BIT7_INT_RAW
+ 7
+ 1
+ read-only
+
+
+ SLC0_RX_START_INT_RAW
+ 8
+ 1
+ read-only
+
+
+ SLC0_TX_START_INT_RAW
+ 9
+ 1
+ read-only
+
+
+ SLC0_RX_UDF_INT_RAW
+ 10
+ 1
+ read-only
+
+
+ SLC0_TX_OVF_INT_RAW
+ 11
+ 1
+ read-only
+
+
+ SLC0_TOKEN0_1TO0_INT_RAW
+ 12
+ 1
+ read-only
+
+
+ SLC0_TOKEN1_1TO0_INT_RAW
+ 13
+ 1
+ read-only
+
+
+ SLC0_TX_DONE_INT_RAW
+ 14
+ 1
+ read-only
+
+
+ SLC0_TX_SUC_EOF_INT_RAW
+ 15
+ 1
+ read-only
+
+
+ SLC0_RX_DONE_INT_RAW
+ 16
+ 1
+ read-only
+
+
+ SLC0_RX_EOF_INT_RAW
+ 17
+ 1
+ read-only
+
+
+ SLC0_TOHOST_INT_RAW
+ 18
+ 1
+ read-only
+
+
+ SLC0_TX_DSCR_ERR_INT_RAW
+ 19
+ 1
+ read-only
+
+
+ SLC0_RX_DSCR_ERR_INT_RAW
+ 20
+ 1
+ read-only
+
+
+ SLC0_TX_DSCR_EMPTY_INT_RAW
+ 21
+ 1
+ read-only
+
+
+ SLC0_HOST_RD_ACK_INT_RAW
+ 22
+ 1
+ read-only
+
+
+ SLC0_WR_RETRY_DONE_INT_RAW
+ 23
+ 1
+ read-only
+
+
+ SLC0_TX_ERR_EOF_INT_RAW
+ 24
+ 1
+ read-only
+
+
+ CMD_DTC_INT_RAW
+ 25
+ 1
+ read-only
+
+
+ SLC0_RX_QUICK_EOF_INT_RAW
+ 26
+ 1
+ read-only
+
+
+
+
+ _0INT_ST
+ 0x8
+ 0x20
+
+
+ FRHOST_BIT0_INT_ST
+ 0
+ 1
+ read-only
+
+
+ FRHOST_BIT1_INT_ST
+ 1
+ 1
+ read-only
+
+
+ FRHOST_BIT2_INT_ST
+ 2
+ 1
+ read-only
+
+
+ FRHOST_BIT3_INT_ST
+ 3
+ 1
+ read-only
+
+
+ FRHOST_BIT4_INT_ST
+ 4
+ 1
+ read-only
+
+
+ FRHOST_BIT5_INT_ST
+ 5
+ 1
+ read-only
+
+
+ FRHOST_BIT6_INT_ST
+ 6
+ 1
+ read-only
+
+
+ FRHOST_BIT7_INT_ST
+ 7
+ 1
+ read-only
+
+
+ SLC0_RX_START_INT_ST
+ 8
+ 1
+ read-only
+
+
+ SLC0_TX_START_INT_ST
+ 9
+ 1
+ read-only
+
+
+ SLC0_RX_UDF_INT_ST
+ 10
+ 1
+ read-only
+
+
+ SLC0_TX_OVF_INT_ST
+ 11
+ 1
+ read-only
+
+
+ SLC0_TOKEN0_1TO0_INT_ST
+ 12
+ 1
+ read-only
+
+
+ SLC0_TOKEN1_1TO0_INT_ST
+ 13
+ 1
+ read-only
+
+
+ SLC0_TX_DONE_INT_ST
+ 14
+ 1
+ read-only
+
+
+ SLC0_TX_SUC_EOF_INT_ST
+ 15
+ 1
+ read-only
+
+
+ SLC0_RX_DONE_INT_ST
+ 16
+ 1
+ read-only
+
+
+ SLC0_RX_EOF_INT_ST
+ 17
+ 1
+ read-only
+
+
+ SLC0_TOHOST_INT_ST
+ 18
+ 1
+ read-only
+
+
+ SLC0_TX_DSCR_ERR_INT_ST
+ 19
+ 1
+ read-only
+
+
+ SLC0_RX_DSCR_ERR_INT_ST
+ 20
+ 1
+ read-only
+
+
+ SLC0_TX_DSCR_EMPTY_INT_ST
+ 21
+ 1
+ read-only
+
+
+ SLC0_HOST_RD_ACK_INT_ST
+ 22
+ 1
+ read-only
+
+
+ SLC0_WR_RETRY_DONE_INT_ST
+ 23
+ 1
+ read-only
+
+
+ SLC0_TX_ERR_EOF_INT_ST
+ 24
+ 1
+ read-only
+
+
+ CMD_DTC_INT_ST
+ 25
+ 1
+ read-only
+
+
+ SLC0_RX_QUICK_EOF_INT_ST
+ 26
+ 1
+ read-only
+
+
+
+
+ _0INT_ENA
+ 0xC
+ 0x20
+
+
+ FRHOST_BIT0_INT_ENA
+ 0
+ 1
+ read-write
+
+
+ FRHOST_BIT1_INT_ENA
+ 1
+ 1
+ read-write
+
+
+ FRHOST_BIT2_INT_ENA
+ 2
+ 1
+ read-write
+
+
+ FRHOST_BIT3_INT_ENA
+ 3
+ 1
+ read-write
+
+
+ FRHOST_BIT4_INT_ENA
+ 4
+ 1
+ read-write
+
+
+ FRHOST_BIT5_INT_ENA
+ 5
+ 1
+ read-write
+
+
+ FRHOST_BIT6_INT_ENA
+ 6
+ 1
+ read-write
+
+
+ FRHOST_BIT7_INT_ENA
+ 7
+ 1
+ read-write
+
+
+ SLC0_RX_START_INT_ENA
+ 8
+ 1
+ read-write
+
+
+ SLC0_TX_START_INT_ENA
+ 9
+ 1
+ read-write
+
+
+ SLC0_RX_UDF_INT_ENA
+ 10
+ 1
+ read-write
+
+
+ SLC0_TX_OVF_INT_ENA
+ 11
+ 1
+ read-write
+
+
+ SLC0_TOKEN0_1TO0_INT_ENA
+ 12
+ 1
+ read-write
+
+
+ SLC0_TOKEN1_1TO0_INT_ENA
+ 13
+ 1
+ read-write
+
+
+ SLC0_TX_DONE_INT_ENA
+ 14
+ 1
+ read-write
+
+
+ SLC0_TX_SUC_EOF_INT_ENA
+ 15
+ 1
+ read-write
+
+
+ SLC0_RX_DONE_INT_ENA
+ 16
+ 1
+ read-write
+
+
+ SLC0_RX_EOF_INT_ENA
+ 17
+ 1
+ read-write
+
+
+ SLC0_TOHOST_INT_ENA
+ 18
+ 1
+ read-write
+
+
+ SLC0_TX_DSCR_ERR_INT_ENA
+ 19
+ 1
+ read-write
+
+
+ SLC0_RX_DSCR_ERR_INT_ENA
+ 20
+ 1
+ read-write
+
+
+ SLC0_TX_DSCR_EMPTY_INT_ENA
+ 21
+ 1
+ read-write
+
+
+ SLC0_HOST_RD_ACK_INT_ENA
+ 22
+ 1
+ read-write
+
+
+ SLC0_WR_RETRY_DONE_INT_ENA
+ 23
+ 1
+ read-write
+
+
+ SLC0_TX_ERR_EOF_INT_ENA
+ 24
+ 1
+ read-write
+
+
+ CMD_DTC_INT_ENA
+ 25
+ 1
+ read-write
+
+
+ SLC0_RX_QUICK_EOF_INT_ENA
+ 26
+ 1
+ read-write
+
+
+
+
+ _0INT_CLR
+ 0x10
+ 0x20
+
+
+ FRHOST_BIT0_INT_CLR
+ 0
+ 1
+ write-only
+
+
+ FRHOST_BIT1_INT_CLR
+ 1
+ 1
+ write-only
+
+
+ FRHOST_BIT2_INT_CLR
+ 2
+ 1
+ write-only
+
+
+ FRHOST_BIT3_INT_CLR
+ 3
+ 1
+ write-only
+
+
+ FRHOST_BIT4_INT_CLR
+ 4
+ 1
+ write-only
+
+
+ FRHOST_BIT5_INT_CLR
+ 5
+ 1
+ write-only
+
+
+ FRHOST_BIT6_INT_CLR
+ 6
+ 1
+ write-only
+
+
+ FRHOST_BIT7_INT_CLR
+ 7
+ 1
+ write-only
+
+
+ SLC0_RX_START_INT_CLR
+ 8
+ 1
+ write-only
+
+
+ SLC0_TX_START_INT_CLR
+ 9
+ 1
+ write-only
+
+
+ SLC0_RX_UDF_INT_CLR
+ 10
+ 1
+ write-only
+
+
+ SLC0_TX_OVF_INT_CLR
+ 11
+ 1
+ write-only
+
+
+ SLC0_TOKEN0_1TO0_INT_CLR
+ 12
+ 1
+ write-only
+
+
+ SLC0_TOKEN1_1TO0_INT_CLR
+ 13
+ 1
+ write-only
+
+
+ SLC0_TX_DONE_INT_CLR
+ 14
+ 1
+ write-only
+
+
+ SLC0_TX_SUC_EOF_INT_CLR
+ 15
+ 1
+ write-only
+
+
+ SLC0_RX_DONE_INT_CLR
+ 16
+ 1
+ write-only
+
+
+ SLC0_RX_EOF_INT_CLR
+ 17
+ 1
+ write-only
+
+
+ SLC0_TOHOST_INT_CLR
+ 18
+ 1
+ write-only
+
+
+ SLC0_TX_DSCR_ERR_INT_CLR
+ 19
+ 1
+ write-only
+
+
+ SLC0_RX_DSCR_ERR_INT_CLR
+ 20
+ 1
+ write-only
+
+
+ SLC0_TX_DSCR_EMPTY_INT_CLR
+ 21
+ 1
+ write-only
+
+
+ SLC0_HOST_RD_ACK_INT_CLR
+ 22
+ 1
+ write-only
+
+
+ SLC0_WR_RETRY_DONE_INT_CLR
+ 23
+ 1
+ write-only
+
+
+ SLC0_TX_ERR_EOF_INT_CLR
+ 24
+ 1
+ write-only
+
+
+ CMD_DTC_INT_CLR
+ 25
+ 1
+ write-only
+
+
+ SLC0_RX_QUICK_EOF_INT_CLR
+ 26
+ 1
+ write-only
+
+
+
+
+ _1INT_RAW
+ 0x14
+ 0x20
+
+
+ FRHOST_BIT8_INT_RAW
+ 0
+ 1
+ read-only
+
+
+ FRHOST_BIT9_INT_RAW
+ 1
+ 1
+ read-only
+
+
+ FRHOST_BIT10_INT_RAW
+ 2
+ 1
+ read-only
+
+
+ FRHOST_BIT11_INT_RAW
+ 3
+ 1
+ read-only
+
+
+ FRHOST_BIT12_INT_RAW
+ 4
+ 1
+ read-only
+
+
+ FRHOST_BIT13_INT_RAW
+ 5
+ 1
+ read-only
+
+
+ FRHOST_BIT14_INT_RAW
+ 6
+ 1
+ read-only
+
+
+ FRHOST_BIT15_INT_RAW
+ 7
+ 1
+ read-only
+
+
+ SLC1_RX_START_INT_RAW
+ 8
+ 1
+ read-only
+
+
+ SLC1_TX_START_INT_RAW
+ 9
+ 1
+ read-only
+
+
+ SLC1_RX_UDF_INT_RAW
+ 10
+ 1
+ read-only
+
+
+ SLC1_TX_OVF_INT_RAW
+ 11
+ 1
+ read-only
+
+
+ SLC1_TOKEN0_1TO0_INT_RAW
+ 12
+ 1
+ read-only
+
+
+ SLC1_TOKEN1_1TO0_INT_RAW
+ 13
+ 1
+ read-only
+
+
+ SLC1_TX_DONE_INT_RAW
+ 14
+ 1
+ read-only
+
+
+ SLC1_TX_SUC_EOF_INT_RAW
+ 15
+ 1
+ read-only
+
+
+ SLC1_RX_DONE_INT_RAW
+ 16
+ 1
+ read-only
+
+
+ SLC1_RX_EOF_INT_RAW
+ 17
+ 1
+ read-only
+
+
+ SLC1_TOHOST_INT_RAW
+ 18
+ 1
+ read-only
+
+
+ SLC1_TX_DSCR_ERR_INT_RAW
+ 19
+ 1
+ read-only
+
+
+ SLC1_RX_DSCR_ERR_INT_RAW
+ 20
+ 1
+ read-only
+
+
+ SLC1_TX_DSCR_EMPTY_INT_RAW
+ 21
+ 1
+ read-only
+
+
+ SLC1_HOST_RD_ACK_INT_RAW
+ 22
+ 1
+ read-only
+
+
+ SLC1_WR_RETRY_DONE_INT_RAW
+ 23
+ 1
+ read-only
+
+
+ SLC1_TX_ERR_EOF_INT_RAW
+ 24
+ 1
+ read-only
+
+
+
+
+ _1INT_ST
+ 0x18
+ 0x20
+
+
+ FRHOST_BIT8_INT_ST
+ 0
+ 1
+ read-only
+
+
+ FRHOST_BIT9_INT_ST
+ 1
+ 1
+ read-only
+
+
+ FRHOST_BIT10_INT_ST
+ 2
+ 1
+ read-only
+
+
+ FRHOST_BIT11_INT_ST
+ 3
+ 1
+ read-only
+
+
+ FRHOST_BIT12_INT_ST
+ 4
+ 1
+ read-only
+
+
+ FRHOST_BIT13_INT_ST
+ 5
+ 1
+ read-only
+
+
+ FRHOST_BIT14_INT_ST
+ 6
+ 1
+ read-only
+
+
+ FRHOST_BIT15_INT_ST
+ 7
+ 1
+ read-only
+
+
+ SLC1_RX_START_INT_ST
+ 8
+ 1
+ read-only
+
+
+ SLC1_TX_START_INT_ST
+ 9
+ 1
+ read-only
+
+
+ SLC1_RX_UDF_INT_ST
+ 10
+ 1
+ read-only
+
+
+ SLC1_TX_OVF_INT_ST
+ 11
+ 1
+ read-only
+
+
+ SLC1_TOKEN0_1TO0_INT_ST
+ 12
+ 1
+ read-only
+
+
+ SLC1_TOKEN1_1TO0_INT_ST
+ 13
+ 1
+ read-only
+
+
+ SLC1_TX_DONE_INT_ST
+ 14
+ 1
+ read-only
+
+
+ SLC1_TX_SUC_EOF_INT_ST
+ 15
+ 1
+ read-only
+
+
+ SLC1_RX_DONE_INT_ST
+ 16
+ 1
+ read-only
+
+
+ SLC1_RX_EOF_INT_ST
+ 17
+ 1
+ read-only
+
+
+ SLC1_TOHOST_INT_ST
+ 18
+ 1
+ read-only
+
+
+ SLC1_TX_DSCR_ERR_INT_ST
+ 19
+ 1
+ read-only
+
+
+ SLC1_RX_DSCR_ERR_INT_ST
+ 20
+ 1
+ read-only
+
+
+ SLC1_TX_DSCR_EMPTY_INT_ST
+ 21
+ 1
+ read-only
+
+
+ SLC1_HOST_RD_ACK_INT_ST
+ 22
+ 1
+ read-only
+
+
+ SLC1_WR_RETRY_DONE_INT_ST
+ 23
+ 1
+ read-only
+
+
+ SLC1_TX_ERR_EOF_INT_ST
+ 24
+ 1
+ read-only
+
+
+
+
+ _1INT_ENA
+ 0x1C
+ 0x20
+
+
+ FRHOST_BIT8_INT_ENA
+ 0
+ 1
+ read-write
+
+
+ FRHOST_BIT9_INT_ENA
+ 1
+ 1
+ read-write
+
+
+ FRHOST_BIT10_INT_ENA
+ 2
+ 1
+ read-write
+
+
+ FRHOST_BIT11_INT_ENA
+ 3
+ 1
+ read-write
+
+
+ FRHOST_BIT12_INT_ENA
+ 4
+ 1
+ read-write
+
+
+ FRHOST_BIT13_INT_ENA
+ 5
+ 1
+ read-write
+
+
+ FRHOST_BIT14_INT_ENA
+ 6
+ 1
+ read-write
+
+
+ FRHOST_BIT15_INT_ENA
+ 7
+ 1
+ read-write
+
+
+ SLC1_RX_START_INT_ENA
+ 8
+ 1
+ read-write
+
+
+ SLC1_TX_START_INT_ENA
+ 9
+ 1
+ read-write
+
+
+ SLC1_RX_UDF_INT_ENA
+ 10
+ 1
+ read-write
+
+
+ SLC1_TX_OVF_INT_ENA
+ 11
+ 1
+ read-write
+
+
+ SLC1_TOKEN0_1TO0_INT_ENA
+ 12
+ 1
+ read-write
+
+
+ SLC1_TOKEN1_1TO0_INT_ENA
+ 13
+ 1
+ read-write
+
+
+ SLC1_TX_DONE_INT_ENA
+ 14
+ 1
+ read-write
+
+
+ SLC1_TX_SUC_EOF_INT_ENA
+ 15
+ 1
+ read-write
+
+
+ SLC1_RX_DONE_INT_ENA
+ 16
+ 1
+ read-write
+
+
+ SLC1_RX_EOF_INT_ENA
+ 17
+ 1
+ read-write
+
+
+ SLC1_TOHOST_INT_ENA
+ 18
+ 1
+ read-write
+
+
+ SLC1_TX_DSCR_ERR_INT_ENA
+ 19
+ 1
+ read-write
+
+
+ SLC1_RX_DSCR_ERR_INT_ENA
+ 20
+ 1
+ read-write
+
+
+ SLC1_TX_DSCR_EMPTY_INT_ENA
+ 21
+ 1
+ read-write
+
+
+ SLC1_HOST_RD_ACK_INT_ENA
+ 22
+ 1
+ read-write
+
+
+ SLC1_WR_RETRY_DONE_INT_ENA
+ 23
+ 1
+ read-write
+
+
+ SLC1_TX_ERR_EOF_INT_ENA
+ 24
+ 1
+ read-write
+
+
+
+
+ _1INT_CLR
+ 0x20
+ 0x20
+
+
+ FRHOST_BIT8_INT_CLR
+ 0
+ 1
+ write-only
+
+
+ FRHOST_BIT9_INT_CLR
+ 1
+ 1
+ write-only
+
+
+ FRHOST_BIT10_INT_CLR
+ 2
+ 1
+ write-only
+
+
+ FRHOST_BIT11_INT_CLR
+ 3
+ 1
+ write-only
+
+
+ FRHOST_BIT12_INT_CLR
+ 4
+ 1
+ write-only
+
+
+ FRHOST_BIT13_INT_CLR
+ 5
+ 1
+ write-only
+
+
+ FRHOST_BIT14_INT_CLR
+ 6
+ 1
+ write-only
+
+
+ FRHOST_BIT15_INT_CLR
+ 7
+ 1
+ write-only
+
+
+ SLC1_RX_START_INT_CLR
+ 8
+ 1
+ write-only
+
+
+ SLC1_TX_START_INT_CLR
+ 9
+ 1
+ write-only
+
+
+ SLC1_RX_UDF_INT_CLR
+ 10
+ 1
+ write-only
+
+
+ SLC1_TX_OVF_INT_CLR
+ 11
+ 1
+ write-only
+
+
+ SLC1_TOKEN0_1TO0_INT_CLR
+ 12
+ 1
+ write-only
+
+
+ SLC1_TOKEN1_1TO0_INT_CLR
+ 13
+ 1
+ write-only
+
+
+ SLC1_TX_DONE_INT_CLR
+ 14
+ 1
+ write-only
+
+
+ SLC1_TX_SUC_EOF_INT_CLR
+ 15
+ 1
+ write-only
+
+
+ SLC1_RX_DONE_INT_CLR
+ 16
+ 1
+ write-only
+
+
+ SLC1_RX_EOF_INT_CLR
+ 17
+ 1
+ write-only
+
+
+ SLC1_TOHOST_INT_CLR
+ 18
+ 1
+ write-only
+
+
+ SLC1_TX_DSCR_ERR_INT_CLR
+ 19
+ 1
+ write-only
+
+
+ SLC1_RX_DSCR_ERR_INT_CLR
+ 20
+ 1
+ write-only
+
+
+ SLC1_TX_DSCR_EMPTY_INT_CLR
+ 21
+ 1
+ write-only
+
+
+ SLC1_HOST_RD_ACK_INT_CLR
+ 22
+ 1
+ write-only
+
+
+ SLC1_WR_RETRY_DONE_INT_CLR
+ 23
+ 1
+ write-only
+
+
+ SLC1_TX_ERR_EOF_INT_CLR
+ 24
+ 1
+ write-only
+
+
+
+
+ RX_STATUS
+ 0x24
+ 0x20
+ 0x00020002
+
+
+ SLC0_RX_FULL
+ 0
+ 1
+ read-only
+
+
+ SLC0_RX_EMPTY
+ 1
+ 1
+ read-only
+
+
+ SLC1_RX_FULL
+ 16
+ 1
+ read-only
+
+
+ SLC1_RX_EMPTY
+ 17
+ 1
+ read-only
+
+
+
+
+ _0RXFIFO_PUSH
+ 0x28
+ 0x20
+
+
+ SLC0_RXFIFO_WDATA
+ 0
+ 9
+ read-write
+
+
+ SLC0_RXFIFO_PUSH
+ 16
+ 1
+ read-write
+
+
+
+
+ _1RXFIFO_PUSH
+ 0x2C
+ 0x20
+
+
+ SLC1_RXFIFO_WDATA
+ 0
+ 9
+ read-write
+
+
+ SLC1_RXFIFO_PUSH
+ 16
+ 1
+ read-write
+
+
+
+
+ TX_STATUS
+ 0x30
+ 0x20
+ 0x00020002
+
+
+ SLC0_TX_FULL
+ 0
+ 1
+ read-only
+
+
+ SLC0_TX_EMPTY
+ 1
+ 1
+ read-only
+
+
+ SLC1_TX_FULL
+ 16
+ 1
+ read-only
+
+
+ SLC1_TX_EMPTY
+ 17
+ 1
+ read-only
+
+
+
+
+ _0TXFIFO_POP
+ 0x34
+ 0x20
+
+
+ SLC0_TXFIFO_RDATA
+ 0
+ 11
+ read-only
+
+
+ SLC0_TXFIFO_POP
+ 16
+ 1
+ read-write
+
+
+
+
+ _1TXFIFO_POP
+ 0x38
+ 0x20
+
+
+ SLC1_TXFIFO_RDATA
+ 0
+ 11
+ read-only
+
+
+ SLC1_TXFIFO_POP
+ 16
+ 1
+ read-write
+
+
+
+
+ _0RX_LINK
+ 0x3C
+ 0x20
+
+
+ SLC0_RXLINK_ADDR
+ 0
+ 20
+ read-write
+
+
+ SLC0_RXLINK_STOP
+ 28
+ 1
+ read-write
+
+
+ SLC0_RXLINK_START
+ 29
+ 1
+ read-write
+
+
+ SLC0_RXLINK_RESTART
+ 30
+ 1
+ read-write
+
+
+ SLC0_RXLINK_PARK
+ 31
+ 1
+ read-only
+
+
+
+
+ _0TX_LINK
+ 0x40
+ 0x20
+
+
+ SLC0_TXLINK_ADDR
+ 0
+ 20
+ read-write
+
+
+ SLC0_TXLINK_STOP
+ 28
+ 1
+ read-write
+
+
+ SLC0_TXLINK_START
+ 29
+ 1
+ read-write
+
+
+ SLC0_TXLINK_RESTART
+ 30
+ 1
+ read-write
+
+
+ SLC0_TXLINK_PARK
+ 31
+ 1
+ read-only
+
+
+
+
+ _1RX_LINK
+ 0x44
+ 0x20
+ 0x00100000
+
+
+ SLC1_RXLINK_ADDR
+ 0
+ 20
+ read-write
+
+
+ SLC1_BT_PACKET
+ 20
+ 1
+ read-write
+
+
+ SLC1_RXLINK_STOP
+ 28
+ 1
+ read-write
+
+
+ SLC1_RXLINK_START
+ 29
+ 1
+ read-write
+
+
+ SLC1_RXLINK_RESTART
+ 30
+ 1
+ read-write
+
+
+ SLC1_RXLINK_PARK
+ 31
+ 1
+ read-only
+
+
+
+
+ _1TX_LINK
+ 0x48
+ 0x20
+
+
+ SLC1_TXLINK_ADDR
+ 0
+ 20
+ read-write
+
+
+ SLC1_TXLINK_STOP
+ 28
+ 1
+ read-write
+
+
+ SLC1_TXLINK_START
+ 29
+ 1
+ read-write
+
+
+ SLC1_TXLINK_RESTART
+ 30
+ 1
+ read-write
+
+
+ SLC1_TXLINK_PARK
+ 31
+ 1
+ read-only
+
+
+
+
+ INTVEC_TOHOST
+ 0x4C
+ 0x20
+
+
+ SLC0_TOHOST_INTVEC
+ 0
+ 8
+ write-only
+
+
+ SLC1_TOHOST_INTVEC
+ 16
+ 8
+ write-only
+
+
+
+
+ _0TOKEN0
+ 0x50
+ 0x20
+
+
+ SLC0_TOKEN0_WDATA
+ 0
+ 12
+ write-only
+
+
+ SLC0_TOKEN0_WR
+ 12
+ 1
+ write-only
+
+
+ SLC0_TOKEN0_INC
+ 13
+ 1
+ write-only
+
+
+ SLC0_TOKEN0_INC_MORE
+ 14
+ 1
+ write-only
+
+
+ SLC0_TOKEN0
+ 16
+ 12
+ read-only
+
+
+
+
+ _0TOKEN1
+ 0x54
+ 0x20
+
+
+ SLC0_TOKEN1_WDATA
+ 0
+ 12
+ write-only
+
+
+ SLC0_TOKEN1_WR
+ 12
+ 1
+ write-only
+
+
+ SLC0_TOKEN1_INC
+ 13
+ 1
+ write-only
+
+
+ SLC0_TOKEN1_INC_MORE
+ 14
+ 1
+ write-only
+
+
+ SLC0_TOKEN1
+ 16
+ 12
+ read-only
+
+
+
+
+ _1TOKEN0
+ 0x58
+ 0x20
+
+
+ SLC1_TOKEN0_WDATA
+ 0
+ 12
+ write-only
+
+
+ SLC1_TOKEN0_WR
+ 12
+ 1
+ write-only
+
+
+ SLC1_TOKEN0_INC
+ 13
+ 1
+ write-only
+
+
+ SLC1_TOKEN0_INC_MORE
+ 14
+ 1
+ write-only
+
+
+ SLC1_TOKEN0
+ 16
+ 12
+ read-only
+
+
+
+
+ _1TOKEN1
+ 0x5C
+ 0x20
+
+
+ SLC1_TOKEN1_WDATA
+ 0
+ 12
+ write-only
+
+
+ SLC1_TOKEN1_WR
+ 12
+ 1
+ write-only
+
+
+ SLC1_TOKEN1_INC
+ 13
+ 1
+ write-only
+
+
+ SLC1_TOKEN1_INC_MORE
+ 14
+ 1
+ write-only
+
+
+ SLC1_TOKEN1
+ 16
+ 12
+ read-only
+
+
+
+
+ CONF1
+ 0x60
+ 0x20
+ 0x00300078
+
+
+ SLC0_CHECK_OWNER
+ 0
+ 1
+ read-write
+
+
+ SLC0_TX_CHECK_SUM_EN
+ 1
+ 1
+ read-write
+
+
+ SLC0_RX_CHECK_SUM_EN
+ 2
+ 1
+ read-write
+
+
+ CMD_HOLD_EN
+ 3
+ 1
+ read-write
+
+
+ SLC0_LEN_AUTO_CLR
+ 4
+ 1
+ read-write
+
+
+ SLC0_TX_STITCH_EN
+ 5
+ 1
+ read-write
+
+
+ SLC0_RX_STITCH_EN
+ 6
+ 1
+ read-write
+
+
+ SLC1_CHECK_OWNER
+ 16
+ 1
+ read-write
+
+
+ SLC1_TX_CHECK_SUM_EN
+ 17
+ 1
+ read-write
+
+
+ SLC1_RX_CHECK_SUM_EN
+ 18
+ 1
+ read-write
+
+
+ HOST_INT_LEVEL_SEL
+ 19
+ 1
+ read-write
+
+
+ SLC1_TX_STITCH_EN
+ 20
+ 1
+ read-write
+
+
+ SLC1_RX_STITCH_EN
+ 21
+ 1
+ read-write
+
+
+ CLK_EN
+ 22
+ 1
+ read-write
+
+
+
+
+ _0_STATE0
+ 0x64
+ 0x20
+
+
+ SLC0_STATE0
+ 0
+ 32
+ read-only
+
+
+
+
+ _0_STATE1
+ 0x68
+ 0x20
+
+
+ SLC0_STATE1
+ 0
+ 32
+ read-only
+
+
+
+
+ _1_STATE0
+ 0x6C
+ 0x20
+
+
+ SLC1_STATE0
+ 0
+ 32
+ read-only
+
+
+
+
+ _1_STATE1
+ 0x70
+ 0x20
+
+
+ SLC1_STATE1
+ 0
+ 32
+ read-only
+
+
+
+
+ BRIDGE_CONF
+ 0x74
+ 0x20
+ 0x000A7720
+
+
+ TXEOF_ENA
+ 0
+ 6
+ read-write
+
+
+ FIFO_MAP_ENA
+ 8
+ 4
+ read-write
+
+
+ SLC0_TX_DUMMY_MODE
+ 12
+ 1
+ read-write
+
+
+ HDA_MAP_128K
+ 13
+ 1
+ read-write
+
+
+ SLC1_TX_DUMMY_MODE
+ 14
+ 1
+ read-write
+
+
+ TX_PUSH_IDLE_NUM
+ 16
+ 16
+ read-write
+
+
+
+
+ _0_TO_EOF_DES_ADDR
+ 0x78
+ 0x20
+
+
+ SLC0_TO_EOF_DES_ADDR
+ 0
+ 32
+ read-only
+
+
+
+
+ _0_TX_EOF_DES_ADDR
+ 0x7C
+ 0x20
+
+
+ SLC0_TX_SUC_EOF_DES_ADDR
+ 0
+ 32
+ read-only
+
+
+
+
+ _0_TO_EOF_BFR_DES_ADDR
+ 0x80
+ 0x20
+
+
+ SLC0_TO_EOF_BFR_DES_ADDR
+ 0
+ 32
+ read-only
+
+
+
+
+ _1_TO_EOF_DES_ADDR
+ 0x84
+ 0x20
+
+
+ SLC1_TO_EOF_DES_ADDR
+ 0
+ 32
+ read-only
+
+
+
+
+ _1_TX_EOF_DES_ADDR
+ 0x88
+ 0x20
+
+
+ SLC1_TX_SUC_EOF_DES_ADDR
+ 0
+ 32
+ read-only
+
+
+
+
+ _1_TO_EOF_BFR_DES_ADDR
+ 0x8C
+ 0x20
+
+
+ SLC1_TO_EOF_BFR_DES_ADDR
+ 0
+ 32
+ read-only
+
+
+
+
+ AHB_TEST
+ 0x90
+ 0x20
+
+
+ AHB_TESTMODE
+ 0
+ 3
+ read-write
+
+
+ AHB_TESTADDR
+ 4
+ 2
+ read-write
+
+
+
+
+ SDIO_ST
+ 0x94
+ 0x20
+
+
+ CMD_ST
+ 0
+ 3
+ read-only
+
+
+ FUNC_ST
+ 4
+ 4
+ read-only
+
+
+ SDIO_WAKEUP
+ 8
+ 1
+ read-only
+
+
+ BUS_ST
+ 12
+ 3
+ read-only
+
+
+ FUNC1_ACC_STATE
+ 16
+ 5
+ read-only
+
+
+ FUNC2_ACC_STATE
+ 24
+ 5
+ read-only
+
+
+
+
+ RX_DSCR_CONF
+ 0x98
+ 0x20
+ 0x101B101A
+
+
+ SLC0_TOKEN_NO_REPLACE
+ 0
+ 1
+ read-write
+
+
+ SLC0_INFOR_NO_REPLACE
+ 1
+ 1
+ read-write
+
+
+ SLC0_RX_FILL_MODE
+ 2
+ 1
+ read-write
+
+
+ SLC0_RX_EOF_MODE
+ 3
+ 1
+ read-write
+
+
+ SLC0_RX_FILL_EN
+ 4
+ 1
+ read-write
+
+
+ SLC0_RD_RETRY_THRESHOLD
+ 5
+ 11
+ read-write
+
+
+ SLC1_TOKEN_NO_REPLACE
+ 16
+ 1
+ read-write
+
+
+ SLC1_INFOR_NO_REPLACE
+ 17
+ 1
+ read-write
+
+
+ SLC1_RX_FILL_MODE
+ 18
+ 1
+ read-write
+
+
+ SLC1_RX_EOF_MODE
+ 19
+ 1
+ read-write
+
+
+ SLC1_RX_FILL_EN
+ 20
+ 1
+ read-write
+
+
+ SLC1_RD_RETRY_THRESHOLD
+ 21
+ 11
+ read-write
+
+
+
+
+ _0_TXLINK_DSCR
+ 0x9C
+ 0x20
+
+
+ SLC0_TXLINK_DSCR
+ 0
+ 32
+ read-only
+
+
+
+
+ _0_TXLINK_DSCR_BF0
+ 0xA0
+ 0x20
+
+
+ SLC0_TXLINK_DSCR_BF0
+ 0
+ 32
+ read-only
+
+
+
+
+ _0_TXLINK_DSCR_BF1
+ 0xA4
+ 0x20
+
+
+ SLC0_TXLINK_DSCR_BF1
+ 0
+ 32
+ read-only
+
+
+
+
+ _0_RXLINK_DSCR
+ 0xA8
+ 0x20
+
+
+ SLC0_RXLINK_DSCR
+ 0
+ 32
+ read-only
+
+
+
+
+ _0_RXLINK_DSCR_BF0
+ 0xAC
+ 0x20
+
+
+ SLC0_RXLINK_DSCR_BF0
+ 0
+ 32
+ read-only
+
+
+
+
+ _0_RXLINK_DSCR_BF1
+ 0xB0
+ 0x20
+
+
+ SLC0_RXLINK_DSCR_BF1
+ 0
+ 32
+ read-only
+
+
+
+
+ _1_TXLINK_DSCR
+ 0xB4
+ 0x20
+
+
+ SLC1_TXLINK_DSCR
+ 0
+ 32
+ read-only
+
+
+
+
+ _1_TXLINK_DSCR_BF0
+ 0xB8
+ 0x20
+
+
+ SLC1_TXLINK_DSCR_BF0
+ 0
+ 32
+ read-only
+
+
+
+
+ _1_TXLINK_DSCR_BF1
+ 0xBC
+ 0x20
+
+
+ SLC1_TXLINK_DSCR_BF1
+ 0
+ 32
+ read-only
+
+
+
+
+ _1_RXLINK_DSCR
+ 0xC0
+ 0x20
+
+
+ SLC1_RXLINK_DSCR
+ 0
+ 32
+ read-only
+
+
+
+
+ _1_RXLINK_DSCR_BF0
+ 0xC4
+ 0x20
+
+
+ SLC1_RXLINK_DSCR_BF0
+ 0
+ 32
+ read-only
+
+
+
+
+ _1_RXLINK_DSCR_BF1
+ 0xC8
+ 0x20
+
+
+ SLC1_RXLINK_DSCR_BF1
+ 0
+ 32
+ read-only
+
+
+
+
+ _0_TX_ERREOF_DES_ADDR
+ 0xCC
+ 0x20
+
+
+ SLC0_TX_ERR_EOF_DES_ADDR
+ 0
+ 32
+ read-only
+
+
+
+
+ _1_TX_ERREOF_DES_ADDR
+ 0xD0
+ 0x20
+
+
+ SLC1_TX_ERR_EOF_DES_ADDR
+ 0
+ 32
+ read-only
+
+
+
+
+ TOKEN_LAT
+ 0xD4
+ 0x20
+
+
+ SLC0_TOKEN
+ 0
+ 12
+ read-only
+
+
+ SLC1_TOKEN
+ 16
+ 12
+ read-only
+
+
+
+
+ TX_DSCR_CONF
+ 0xD8
+ 0x20
+ 0x00000080
+
+
+ WR_RETRY_THRESHOLD
+ 0
+ 11
+ read-write
+
+
+
+
+ CMD_INFOR0
+ 0xDC
+ 0x20
+
+
+ CMD_CONTENT0
+ 0
+ 32
+ read-only
+
+
+
+
+ CMD_INFOR1
+ 0xE0
+ 0x20
+
+
+ CMD_CONTENT1
+ 0
+ 32
+ read-only
+
+
+
+
+ _0_LEN_CONF
+ 0xE4
+ 0x20
+
+
+ SLC0_LEN_WDATA
+ 0
+ 20
+ write-only
+
+
+ SLC0_LEN_WR
+ 20
+ 1
+ write-only
+
+
+ SLC0_LEN_INC
+ 21
+ 1
+ write-only
+
+
+ SLC0_LEN_INC_MORE
+ 22
+ 1
+ write-only
+
+
+ SLC0_RX_PACKET_LOAD_EN
+ 23
+ 1
+ read-write
+
+
+ SLC0_TX_PACKET_LOAD_EN
+ 24
+ 1
+ read-write
+
+
+ SLC0_RX_GET_USED_DSCR
+ 25
+ 1
+ write-only
+
+
+ SLC0_TX_GET_USED_DSCR
+ 26
+ 1
+ write-only
+
+
+ SLC0_RX_NEW_PKT_IND
+ 27
+ 1
+ read-only
+
+
+ SLC0_TX_NEW_PKT_IND
+ 28
+ 1
+ read-only
+
+
+
+
+ _0_LENGTH
+ 0xE8
+ 0x20
+
+
+ SLC0_LEN
+ 0
+ 20
+ read-only
+
+
+
+
+ _0_TXPKT_H_DSCR
+ 0xEC
+ 0x20
+
+
+ SLC0_TX_PKT_H_DSCR_ADDR
+ 0
+ 32
+ read-write
+
+
+
+
+ _0_TXPKT_E_DSCR
+ 0xF0
+ 0x20
+
+
+ SLC0_TX_PKT_E_DSCR_ADDR
+ 0
+ 32
+ read-write
+
+
+
+
+ _0_RXPKT_H_DSCR
+ 0xF4
+ 0x20
+
+
+ SLC0_RX_PKT_H_DSCR_ADDR
+ 0
+ 32
+ read-write
+
+
+
+
+ _0_RXPKT_E_DSCR
+ 0xF8
+ 0x20
+
+
+ SLC0_RX_PKT_E_DSCR_ADDR
+ 0
+ 32
+ read-write
+
+
+
+
+ _0_TXPKTU_H_DSCR
+ 0xFC
+ 0x20
+
+
+ SLC0_TX_PKT_START_DSCR_ADDR
+ 0
+ 32
+ read-only
+
+
+
+
+ _0_TXPKTU_E_DSCR
+ 0x100
+ 0x20
+
+
+ SLC0_TX_PKT_END_DSCR_ADDR
+ 0
+ 32
+ read-only
+
+
+
+
+ _0_RXPKTU_H_DSCR
+ 0x104
+ 0x20
+
+
+ SLC0_RX_PKT_START_DSCR_ADDR
+ 0
+ 32
+ read-only
+
+
+
+
+ _0_RXPKTU_E_DSCR
+ 0x108
+ 0x20
+
+
+ SLC0_RX_PKT_END_DSCR_ADDR
+ 0
+ 32
+ read-only
+
+
+
+
+ SEQ_POSITION
+ 0x114
+ 0x20
+ 0x00000509
+
+
+ SLC0_SEQ_POSITION
+ 0
+ 8
+ read-write
+
+
+ SLC1_SEQ_POSITION
+ 8
+ 8
+ read-write
+
+
+
+
+ _0_DSCR_REC_CONF
+ 0x118
+ 0x20
+ 0x000003FF
+
+
+ SLC0_RX_DSCR_REC_LIM
+ 0
+ 10
+ read-write
+
+
+
+
+ SDIO_CRC_ST0
+ 0x11C
+ 0x20
+
+
+ DAT0_CRC_ERR_CNT
+ 0
+ 8
+ read-only
+
+
+ DAT1_CRC_ERR_CNT
+ 8
+ 8
+ read-only
+
+
+ DAT2_CRC_ERR_CNT
+ 16
+ 8
+ read-only
+
+
+ DAT3_CRC_ERR_CNT
+ 24
+ 8
+ read-only
+
+
+
+
+ SDIO_CRC_ST1
+ 0x120
+ 0x20
+
+
+ CMD_CRC_ERR_CNT
+ 0
+ 8
+ read-only
+
+
+ ERR_CNT_CLR
+ 31
+ 1
+ read-write
+
+
+
+
+ _0_EOF_START_DES
+ 0x124
+ 0x20
+
+
+ SLC0_EOF_START_DES_ADDR
+ 0
+ 32
+ read-only
+
+
+
+
+ _0_PUSH_DSCR_ADDR
+ 0x128
+ 0x20
+
+
+ SLC0_RX_PUSH_DSCR_ADDR
+ 0
+ 32
+ read-only
+
+
+
+
+ _0_DONE_DSCR_ADDR
+ 0x12C
+ 0x20
+
+
+ SLC0_RX_DONE_DSCR_ADDR
+ 0
+ 32
+ read-only
+
+
+
+
+ _0_SUB_START_DES
+ 0x130
+ 0x20
+
+
+ SLC0_SUB_PAC_START_DSCR_ADDR
+ 0
+ 32
+ read-only
+
+
+
+
+ _0_DSCR_CNT
+ 0x134
+ 0x20
+
+
+ SLC0_RX_DSCR_CNT_LAT
+ 0
+ 10
+ read-only
+
+
+ SLC0_RX_GET_EOF_OCC
+ 16
+ 1
+ read-only
+
+
+
+
+ _0_LEN_LIM_CONF
+ 0x138
+ 0x20
+ 0x00005400
+
+
+ SLC0_LEN_LIM
+ 0
+ 20
+ read-write
+
+
+
+
+ _0INT_ST1
+ 0x13C
+ 0x20
+
+
+ FRHOST_BIT0_INT_ST1
+ 0
+ 1
+ read-only
+
+
+ FRHOST_BIT1_INT_ST1
+ 1
+ 1
+ read-only
+
+
+ FRHOST_BIT2_INT_ST1
+ 2
+ 1
+ read-only
+
+
+ FRHOST_BIT3_INT_ST1
+ 3
+ 1
+ read-only
+
+
+ FRHOST_BIT4_INT_ST1
+ 4
+ 1
+ read-only
+
+
+ FRHOST_BIT5_INT_ST1
+ 5
+ 1
+ read-only
+
+
+ FRHOST_BIT6_INT_ST1
+ 6
+ 1
+ read-only
+
+
+ FRHOST_BIT7_INT_ST1
+ 7
+ 1
+ read-only
+
+
+ SLC0_RX_START_INT_ST1
+ 8
+ 1
+ read-only
+
+
+ SLC0_TX_START_INT_ST1
+ 9
+ 1
+ read-only
+
+
+ SLC0_RX_UDF_INT_ST1
+ 10
+ 1
+ read-only
+
+
+ SLC0_TX_OVF_INT_ST1
+ 11
+ 1
+ read-only
+
+
+ SLC0_TOKEN0_1TO0_INT_ST1
+ 12
+ 1
+ read-only
+
+
+ SLC0_TOKEN1_1TO0_INT_ST1
+ 13
+ 1
+ read-only
+
+
+ SLC0_TX_DONE_INT_ST1
+ 14
+ 1
+ read-only
+
+
+ SLC0_TX_SUC_EOF_INT_ST1
+ 15
+ 1
+ read-only
+
+
+ SLC0_RX_DONE_INT_ST1
+ 16
+ 1
+ read-only
+
+
+ SLC0_RX_EOF_INT_ST1
+ 17
+ 1
+ read-only
+
+
+ SLC0_TOHOST_INT_ST1
+ 18
+ 1
+ read-only
+
+
+ SLC0_TX_DSCR_ERR_INT_ST1
+ 19
+ 1
+ read-only
+
+
+ SLC0_RX_DSCR_ERR_INT_ST1
+ 20
+ 1
+ read-only
+
+
+ SLC0_TX_DSCR_EMPTY_INT_ST1
+ 21
+ 1
+ read-only
+
+
+ SLC0_HOST_RD_ACK_INT_ST1
+ 22
+ 1
+ read-only
+
+
+ SLC0_WR_RETRY_DONE_INT_ST1
+ 23
+ 1
+ read-only
+
+
+ SLC0_TX_ERR_EOF_INT_ST1
+ 24
+ 1
+ read-only
+
+
+ CMD_DTC_INT_ST1
+ 25
+ 1
+ read-only
+
+
+ SLC0_RX_QUICK_EOF_INT_ST1
+ 26
+ 1
+ read-only
+
+
+
+
+ _0INT_ENA1
+ 0x140
+ 0x20
+
+
+ FRHOST_BIT0_INT_ENA1
+ 0
+ 1
+ read-write
+
+
+ FRHOST_BIT1_INT_ENA1
+ 1
+ 1
+ read-write
+
+
+ FRHOST_BIT2_INT_ENA1
+ 2
+ 1
+ read-write
+
+
+ FRHOST_BIT3_INT_ENA1
+ 3
+ 1
+ read-write
+
+
+ FRHOST_BIT4_INT_ENA1
+ 4
+ 1
+ read-write
+
+
+ FRHOST_BIT5_INT_ENA1
+ 5
+ 1
+ read-write
+
+
+ FRHOST_BIT6_INT_ENA1
+ 6
+ 1
+ read-write
+
+
+ FRHOST_BIT7_INT_ENA1
+ 7
+ 1
+ read-write
+
+
+ SLC0_RX_START_INT_ENA1
+ 8
+ 1
+ read-write
+
+
+ SLC0_TX_START_INT_ENA1
+ 9
+ 1
+ read-write
+
+
+ SLC0_RX_UDF_INT_ENA1
+ 10
+ 1
+ read-write
+
+
+ SLC0_TX_OVF_INT_ENA1
+ 11
+ 1
+ read-write
+
+
+ SLC0_TOKEN0_1TO0_INT_ENA1
+ 12
+ 1
+ read-write
+
+
+ SLC0_TOKEN1_1TO0_INT_ENA1
+ 13
+ 1
+ read-write
+
+
+ SLC0_TX_DONE_INT_ENA1
+ 14
+ 1
+ read-write
+
+
+ SLC0_TX_SUC_EOF_INT_ENA1
+ 15
+ 1
+ read-write
+
+
+ SLC0_RX_DONE_INT_ENA1
+ 16
+ 1
+ read-write
+
+
+ SLC0_RX_EOF_INT_ENA1
+ 17
+ 1
+ read-write
+
+
+ SLC0_TOHOST_INT_ENA1
+ 18
+ 1
+ read-write
+
+
+ SLC0_TX_DSCR_ERR_INT_ENA1
+ 19
+ 1
+ read-write
+
+
+ SLC0_RX_DSCR_ERR_INT_ENA1
+ 20
+ 1
+ read-write
+
+
+ SLC0_TX_DSCR_EMPTY_INT_ENA1
+ 21
+ 1
+ read-write
+
+
+ SLC0_HOST_RD_ACK_INT_ENA1
+ 22
+ 1
+ read-write
+
+
+ SLC0_WR_RETRY_DONE_INT_ENA1
+ 23
+ 1
+ read-write
+
+
+ SLC0_TX_ERR_EOF_INT_ENA1
+ 24
+ 1
+ read-write
+
+
+ CMD_DTC_INT_ENA1
+ 25
+ 1
+ read-write
+
+
+ SLC0_RX_QUICK_EOF_INT_ENA1
+ 26
+ 1
+ read-write
+
+
+
+
+ _1INT_ST1
+ 0x144
+ 0x20
+
+
+ FRHOST_BIT8_INT_ST1
+ 0
+ 1
+ read-only
+
+
+ FRHOST_BIT9_INT_ST1
+ 1
+ 1
+ read-only
+
+
+ FRHOST_BIT10_INT_ST1
+ 2
+ 1
+ read-only
+
+
+ FRHOST_BIT11_INT_ST1
+ 3
+ 1
+ read-only
+
+
+ FRHOST_BIT12_INT_ST1
+ 4
+ 1
+ read-only
+
+
+ FRHOST_BIT13_INT_ST1
+ 5
+ 1
+ read-only
+
+
+ FRHOST_BIT14_INT_ST1
+ 6
+ 1
+ read-only
+
+
+ FRHOST_BIT15_INT_ST1
+ 7
+ 1
+ read-only
+
+
+ SLC1_RX_START_INT_ST1
+ 8
+ 1
+ read-only
+
+
+ SLC1_TX_START_INT_ST1
+ 9
+ 1
+ read-only
+
+
+ SLC1_RX_UDF_INT_ST1
+ 10
+ 1
+ read-only
+
+
+ SLC1_TX_OVF_INT_ST1
+ 11
+ 1
+ read-only
+
+
+ SLC1_TOKEN0_1TO0_INT_ST1
+ 12
+ 1
+ read-only
+
+
+ SLC1_TOKEN1_1TO0_INT_ST1
+ 13
+ 1
+ read-only
+
+
+ SLC1_TX_DONE_INT_ST1
+ 14
+ 1
+ read-only
+
+
+ SLC1_TX_SUC_EOF_INT_ST1
+ 15
+ 1
+ read-only
+
+
+ SLC1_RX_DONE_INT_ST1
+ 16
+ 1
+ read-only
+
+
+ SLC1_RX_EOF_INT_ST1
+ 17
+ 1
+ read-only
+
+
+ SLC1_TOHOST_INT_ST1
+ 18
+ 1
+ read-only
+
+
+ SLC1_TX_DSCR_ERR_INT_ST1
+ 19
+ 1
+ read-only
+
+
+ SLC1_RX_DSCR_ERR_INT_ST1
+ 20
+ 1
+ read-only
+
+
+ SLC1_TX_DSCR_EMPTY_INT_ST1
+ 21
+ 1
+ read-only
+
+
+ SLC1_HOST_RD_ACK_INT_ST1
+ 22
+ 1
+ read-only
+
+
+ SLC1_WR_RETRY_DONE_INT_ST1
+ 23
+ 1
+ read-only
+
+
+ SLC1_TX_ERR_EOF_INT_ST1
+ 24
+ 1
+ read-only
+
+
+
+
+ _1INT_ENA1
+ 0x148
+ 0x20
+
+
+ FRHOST_BIT8_INT_ENA1
+ 0
+ 1
+ read-write
+
+
+ FRHOST_BIT9_INT_ENA1
+ 1
+ 1
+ read-write
+
+
+ FRHOST_BIT10_INT_ENA1
+ 2
+ 1
+ read-write
+
+
+ FRHOST_BIT11_INT_ENA1
+ 3
+ 1
+ read-write
+
+
+ FRHOST_BIT12_INT_ENA1
+ 4
+ 1
+ read-write
+
+
+ FRHOST_BIT13_INT_ENA1
+ 5
+ 1
+ read-write
+
+
+ FRHOST_BIT14_INT_ENA1
+ 6
+ 1
+ read-write
+
+
+ FRHOST_BIT15_INT_ENA1
+ 7
+ 1
+ read-write
+
+
+ SLC1_RX_START_INT_ENA1
+ 8
+ 1
+ read-write
+
+
+ SLC1_TX_START_INT_ENA1
+ 9
+ 1
+ read-write
+
+
+ SLC1_RX_UDF_INT_ENA1
+ 10
+ 1
+ read-write
+
+
+ SLC1_TX_OVF_INT_ENA1
+ 11
+ 1
+ read-write
+
+
+ SLC1_TOKEN0_1TO0_INT_ENA1
+ 12
+ 1
+ read-write
+
+
+ SLC1_TOKEN1_1TO0_INT_ENA1
+ 13
+ 1
+ read-write
+
+
+ SLC1_TX_DONE_INT_ENA1
+ 14
+ 1
+ read-write
+
+
+ SLC1_TX_SUC_EOF_INT_ENA1
+ 15
+ 1
+ read-write
+
+
+ SLC1_RX_DONE_INT_ENA1
+ 16
+ 1
+ read-write
+
+
+ SLC1_RX_EOF_INT_ENA1
+ 17
+ 1
+ read-write
+
+
+ SLC1_TOHOST_INT_ENA1
+ 18
+ 1
+ read-write
+
+
+ SLC1_TX_DSCR_ERR_INT_ENA1
+ 19
+ 1
+ read-write
+
+
+ SLC1_RX_DSCR_ERR_INT_ENA1
+ 20
+ 1
+ read-write
+
+
+ SLC1_TX_DSCR_EMPTY_INT_ENA1
+ 21
+ 1
+ read-write
+
+
+ SLC1_HOST_RD_ACK_INT_ENA1
+ 22
+ 1
+ read-write
+
+
+ SLC1_WR_RETRY_DONE_INT_ENA1
+ 23
+ 1
+ read-write
+
+
+ SLC1_TX_ERR_EOF_INT_ENA1
+ 24
+ 1
+ read-write
+
+
+
+
+ DATE
+ 0x1F8
+ 0x20
+ 0x16022500
+
+
+ DATE
+ 0
+ 32
+ read-write
+
+
+
+
+ ID
+ 0x1FC
+ 0x20
+ 0x00000100
+
+
+ ID
+ 0
+ 32
+ read-write
+
+
+
+
+
+
+ SLCHOST
+ Peripheral SLCHOST
+ SLCHOST
+ 0x3FF55000
+
+ 0x0
+ 0x104
+ registers
+
+
+
+ HOST_SLCHOST_FUNC2_0
+ 0x10
+ 0x20
+
+
+ HOST_SLC_FUNC2_INT
+ 24
+ 1
+ read-write
+
+
+
+
+ HOST_SLCHOST_FUNC2_1
+ 0x14
+ 0x20
+
+
+ HOST_SLC_FUNC2_INT_EN
+ 0
+ 1
+ read-write
+
+
+
+
+ HOST_SLCHOST_FUNC2_2
+ 0x20
+ 0x20
+ 0x00000001
+
+
+ HOST_SLC_FUNC1_MDSTAT
+ 0
+ 1
+ read-write
+
+
+
+
+ HOST_SLCHOST_GPIO_STATUS0
+ 0x34
+ 0x20
+
+
+ HOST_GPIO_SDIO_INT0
+ 0
+ 32
+ read-only
+
+
+
+
+ HOST_SLCHOST_GPIO_STATUS1
+ 0x38
+ 0x20
+
+
+ HOST_GPIO_SDIO_INT1
+ 0
+ 8
+ read-only
+
+
+
+
+ HOST_SLCHOST_GPIO_IN0
+ 0x3C
+ 0x20
+
+
+ HOST_GPIO_SDIO_IN0
+ 0
+ 32
+ read-only
+
+
+
+
+ HOST_SLCHOST_GPIO_IN1
+ 0x40
+ 0x20
+
+
+ HOST_GPIO_SDIO_IN1
+ 0
+ 8
+ read-only
+
+
+
+
+ HOST_SLC0HOST_TOKEN_RDATA
+ 0x44
+ 0x20
+
+
+ HOST_SLC0_TOKEN0
+ 0
+ 12
+ read-only
+
+
+ HOST_SLC0_RX_PF_VALID
+ 12
+ 1
+ read-only
+
+
+ HOST_HOSTSLC0_TOKEN1
+ 16
+ 12
+ read-only
+
+
+ HOST_SLC0_RX_PF_EOF
+ 28
+ 4
+ read-only
+
+
+
+
+ HOST_SLC0_HOST_PF
+ 0x48
+ 0x20
+
+
+ HOST_SLC0_PF_DATA
+ 0
+ 32
+ read-only
+
+
+
+
+ HOST_SLC1_HOST_PF
+ 0x4C
+ 0x20
+
+
+ HOST_SLC1_PF_DATA
+ 0
+ 32
+ read-only
+
+
+
+
+ HOST_SLC0HOST_INT_RAW
+ 0x50
+ 0x20
+
+
+ HOST_SLC0_TOHOST_BIT0_INT_RAW
+ 0
+ 1
+ read-only
+
+
+ HOST_SLC0_TOHOST_BIT1_INT_RAW
+ 1
+ 1
+ read-only
+
+
+ HOST_SLC0_TOHOST_BIT2_INT_RAW
+ 2
+ 1
+ read-only
+
+
+ HOST_SLC0_TOHOST_BIT3_INT_RAW
+ 3
+ 1
+ read-only
+
+
+ HOST_SLC0_TOHOST_BIT4_INT_RAW
+ 4
+ 1
+ read-only
+
+
+ HOST_SLC0_TOHOST_BIT5_INT_RAW
+ 5
+ 1
+ read-only
+
+
+ HOST_SLC0_TOHOST_BIT6_INT_RAW
+ 6
+ 1
+ read-only
+
+
+ HOST_SLC0_TOHOST_BIT7_INT_RAW
+ 7
+ 1
+ read-only
+
+
+ HOST_SLC0_TOKEN0_1TO0_INT_RAW
+ 8
+ 1
+ read-only
+
+
+ HOST_SLC0_TOKEN1_1TO0_INT_RAW
+ 9
+ 1
+ read-only
+
+
+ HOST_SLC0_TOKEN0_0TO1_INT_RAW
+ 10
+ 1
+ read-only
+
+
+ HOST_SLC0_TOKEN1_0TO1_INT_RAW
+ 11
+ 1
+ read-only
+
+
+ HOST_SLC0HOST_RX_SOF_INT_RAW
+ 12
+ 1
+ read-only
+
+
+ HOST_SLC0HOST_RX_EOF_INT_RAW
+ 13
+ 1
+ read-only
+
+
+ HOST_SLC0HOST_RX_START_INT_RAW
+ 14
+ 1
+ read-only
+
+
+ HOST_SLC0HOST_TX_START_INT_RAW
+ 15
+ 1
+ read-only
+
+
+ HOST_SLC0_RX_UDF_INT_RAW
+ 16
+ 1
+ read-only
+
+
+ HOST_SLC0_TX_OVF_INT_RAW
+ 17
+ 1
+ read-only
+
+
+ HOST_SLC0_RX_PF_VALID_INT_RAW
+ 18
+ 1
+ read-only
+
+
+ HOST_SLC0_EXT_BIT0_INT_RAW
+ 19
+ 1
+ read-only
+
+
+ HOST_SLC0_EXT_BIT1_INT_RAW
+ 20
+ 1
+ read-only
+
+
+ HOST_SLC0_EXT_BIT2_INT_RAW
+ 21
+ 1
+ read-only
+
+
+ HOST_SLC0_EXT_BIT3_INT_RAW
+ 22
+ 1
+ read-only
+
+
+ HOST_SLC0_RX_NEW_PACKET_INT_RAW
+ 23
+ 1
+ read-only
+
+
+ HOST_SLC0_HOST_RD_RETRY_INT_RAW
+ 24
+ 1
+ read-only
+
+
+ HOST_GPIO_SDIO_INT_RAW
+ 25
+ 1
+ read-only
+
+
+
+
+ HOST_SLC1HOST_INT_RAW
+ 0x54
+ 0x20
+
+
+ HOST_SLC1_TOHOST_BIT0_INT_RAW
+ 0
+ 1
+ read-only
+
+
+ HOST_SLC1_TOHOST_BIT1_INT_RAW
+ 1
+ 1
+ read-only
+
+
+ HOST_SLC1_TOHOST_BIT2_INT_RAW
+ 2
+ 1
+ read-only
+
+
+ HOST_SLC1_TOHOST_BIT3_INT_RAW
+ 3
+ 1
+ read-only
+
+
+ HOST_SLC1_TOHOST_BIT4_INT_RAW
+ 4
+ 1
+ read-only
+
+
+ HOST_SLC1_TOHOST_BIT5_INT_RAW
+ 5
+ 1
+ read-only
+
+
+ HOST_SLC1_TOHOST_BIT6_INT_RAW
+ 6
+ 1
+ read-only
+
+
+ HOST_SLC1_TOHOST_BIT7_INT_RAW
+ 7
+ 1
+ read-only
+
+
+ HOST_SLC1_TOKEN0_1TO0_INT_RAW
+ 8
+ 1
+ read-only
+
+
+ HOST_SLC1_TOKEN1_1TO0_INT_RAW
+ 9
+ 1
+ read-only
+
+
+ HOST_SLC1_TOKEN0_0TO1_INT_RAW
+ 10
+ 1
+ read-only
+
+
+ HOST_SLC1_TOKEN1_0TO1_INT_RAW
+ 11
+ 1
+ read-only
+
+
+ HOST_SLC1HOST_RX_SOF_INT_RAW
+ 12
+ 1
+ read-only
+
+
+ HOST_SLC1HOST_RX_EOF_INT_RAW
+ 13
+ 1
+ read-only
+
+
+ HOST_SLC1HOST_RX_START_INT_RAW
+ 14
+ 1
+ read-only
+
+
+ HOST_SLC1HOST_TX_START_INT_RAW
+ 15
+ 1
+ read-only
+
+
+ HOST_SLC1_RX_UDF_INT_RAW
+ 16
+ 1
+ read-only
+
+
+ HOST_SLC1_TX_OVF_INT_RAW
+ 17
+ 1
+ read-only
+
+
+ HOST_SLC1_RX_PF_VALID_INT_RAW
+ 18
+ 1
+ read-only
+
+
+ HOST_SLC1_EXT_BIT0_INT_RAW
+ 19
+ 1
+ read-only
+
+
+ HOST_SLC1_EXT_BIT1_INT_RAW
+ 20
+ 1
+ read-only
+
+
+ HOST_SLC1_EXT_BIT2_INT_RAW
+ 21
+ 1
+ read-only
+
+
+ HOST_SLC1_EXT_BIT3_INT_RAW
+ 22
+ 1
+ read-only
+
+
+ HOST_SLC1_WIFI_RX_NEW_PACKET_INT_RAW
+ 23
+ 1
+ read-only
+
+
+ HOST_SLC1_HOST_RD_RETRY_INT_RAW
+ 24
+ 1
+ read-only
+
+
+ HOST_SLC1_BT_RX_NEW_PACKET_INT_RAW
+ 25
+ 1
+ read-only
+
+
+
+
+ HOST_SLC0HOST_INT_ST
+ 0x58
+ 0x20
+
+
+ HOST_SLC0_TOHOST_BIT0_INT_ST
+ 0
+ 1
+ read-only
+
+
+ HOST_SLC0_TOHOST_BIT1_INT_ST
+ 1
+ 1
+ read-only
+
+
+ HOST_SLC0_TOHOST_BIT2_INT_ST
+ 2
+ 1
+ read-only
+
+
+ HOST_SLC0_TOHOST_BIT3_INT_ST
+ 3
+ 1
+ read-only
+
+
+ HOST_SLC0_TOHOST_BIT4_INT_ST
+ 4
+ 1
+ read-only
+
+
+ HOST_SLC0_TOHOST_BIT5_INT_ST
+ 5
+ 1
+ read-only
+
+
+ HOST_SLC0_TOHOST_BIT6_INT_ST
+ 6
+ 1
+ read-only
+
+
+ HOST_SLC0_TOHOST_BIT7_INT_ST
+ 7
+ 1
+ read-only
+
+
+ HOST_SLC0_TOKEN0_1TO0_INT_ST
+ 8
+ 1
+ read-only
+
+
+ HOST_SLC0_TOKEN1_1TO0_INT_ST
+ 9
+ 1
+ read-only
+
+
+ HOST_SLC0_TOKEN0_0TO1_INT_ST
+ 10
+ 1
+ read-only
+
+
+ HOST_SLC0_TOKEN1_0TO1_INT_ST
+ 11
+ 1
+ read-only
+
+
+ HOST_SLC0HOST_RX_SOF_INT_ST
+ 12
+ 1
+ read-only
+
+
+ HOST_SLC0HOST_RX_EOF_INT_ST
+ 13
+ 1
+ read-only
+
+
+ HOST_SLC0HOST_RX_START_INT_ST
+ 14
+ 1
+ read-only
+
+
+ HOST_SLC0HOST_TX_START_INT_ST
+ 15
+ 1
+ read-only
+
+
+ HOST_SLC0_RX_UDF_INT_ST
+ 16
+ 1
+ read-only
+
+
+ HOST_SLC0_TX_OVF_INT_ST
+ 17
+ 1
+ read-only
+
+
+ HOST_SLC0_RX_PF_VALID_INT_ST
+ 18
+ 1
+ read-only
+
+
+ HOST_SLC0_EXT_BIT0_INT_ST
+ 19
+ 1
+ read-only
+
+
+ HOST_SLC0_EXT_BIT1_INT_ST
+ 20
+ 1
+ read-only
+
+
+ HOST_SLC0_EXT_BIT2_INT_ST
+ 21
+ 1
+ read-only
+
+
+ HOST_SLC0_EXT_BIT3_INT_ST
+ 22
+ 1
+ read-only
+
+
+ HOST_SLC0_RX_NEW_PACKET_INT_ST
+ 23
+ 1
+ read-only
+
+
+ HOST_SLC0_HOST_RD_RETRY_INT_ST
+ 24
+ 1
+ read-only
+
+
+ HOST_GPIO_SDIO_INT_ST
+ 25
+ 1
+ read-only
+
+
+
+
+ HOST_SLC1HOST_INT_ST
+ 0x5C
+ 0x20
+
+
+ HOST_SLC1_TOHOST_BIT0_INT_ST
+ 0
+ 1
+ read-only
+
+
+ HOST_SLC1_TOHOST_BIT1_INT_ST
+ 1
+ 1
+ read-only
+
+
+ HOST_SLC1_TOHOST_BIT2_INT_ST
+ 2
+ 1
+ read-only
+
+
+ HOST_SLC1_TOHOST_BIT3_INT_ST
+ 3
+ 1
+ read-only
+
+
+ HOST_SLC1_TOHOST_BIT4_INT_ST
+ 4
+ 1
+ read-only
+
+
+ HOST_SLC1_TOHOST_BIT5_INT_ST
+ 5
+ 1
+ read-only
+
+
+ HOST_SLC1_TOHOST_BIT6_INT_ST
+ 6
+ 1
+ read-only
+
+
+ HOST_SLC1_TOHOST_BIT7_INT_ST
+ 7
+ 1
+ read-only
+
+
+ HOST_SLC1_TOKEN0_1TO0_INT_ST
+ 8
+ 1
+ read-only
+
+
+ HOST_SLC1_TOKEN1_1TO0_INT_ST
+ 9
+ 1
+ read-only
+
+
+ HOST_SLC1_TOKEN0_0TO1_INT_ST
+ 10
+ 1
+ read-only
+
+
+ HOST_SLC1_TOKEN1_0TO1_INT_ST
+ 11
+ 1
+ read-only
+
+
+ HOST_SLC1HOST_RX_SOF_INT_ST
+ 12
+ 1
+ read-only
+
+
+ HOST_SLC1HOST_RX_EOF_INT_ST
+ 13
+ 1
+ read-only
+
+
+ HOST_SLC1HOST_RX_START_INT_ST
+ 14
+ 1
+ read-only
+
+
+ HOST_SLC1HOST_TX_START_INT_ST
+ 15
+ 1
+ read-only
+
+
+ HOST_SLC1_RX_UDF_INT_ST
+ 16
+ 1
+ read-only
+
+
+ HOST_SLC1_TX_OVF_INT_ST
+ 17
+ 1
+ read-only
+
+
+ HOST_SLC1_RX_PF_VALID_INT_ST
+ 18
+ 1
+ read-only
+
+
+ HOST_SLC1_EXT_BIT0_INT_ST
+ 19
+ 1
+ read-only
+
+
+ HOST_SLC1_EXT_BIT1_INT_ST
+ 20
+ 1
+ read-only
+
+
+ HOST_SLC1_EXT_BIT2_INT_ST
+ 21
+ 1
+ read-only
+
+
+ HOST_SLC1_EXT_BIT3_INT_ST
+ 22
+ 1
+ read-only
+
+
+ HOST_SLC1_WIFI_RX_NEW_PACKET_INT_ST
+ 23
+ 1
+ read-only
+
+
+ HOST_SLC1_HOST_RD_RETRY_INT_ST
+ 24
+ 1
+ read-only
+
+
+ HOST_SLC1_BT_RX_NEW_PACKET_INT_ST
+ 25
+ 1
+ read-only
+
+
+
+
+ HOST_SLCHOST_PKT_LEN
+ 0x60
+ 0x20
+
+
+ HOST_HOSTSLC0_LEN
+ 0
+ 20
+ read-only
+
+
+ HOST_HOSTSLC0_LEN_CHECK
+ 20
+ 12
+ read-only
+
+
+
+
+ HOST_SLCHOST_STATE_W0
+ 0x64
+ 0x20
+
+
+ HOST_SLCHOST_STATE0
+ 0
+ 8
+ read-only
+
+
+ HOST_SLCHOST_STATE1
+ 8
+ 8
+ read-only
+
+
+ HOST_SLCHOST_STATE2
+ 16
+ 8
+ read-only
+
+
+ HOST_SLCHOST_STATE3
+ 24
+ 8
+ read-only
+
+
+
+
+ HOST_SLCHOST_STATE_W1
+ 0x68
+ 0x20
+
+
+ HOST_SLCHOST_STATE4
+ 0
+ 8
+ read-only
+
+
+ HOST_SLCHOST_STATE5
+ 8
+ 8
+ read-only
+
+
+ HOST_SLCHOST_STATE6
+ 16
+ 8
+ read-only
+
+
+ HOST_SLCHOST_STATE7
+ 24
+ 8
+ read-only
+
+
+
+
+ HOST_SLCHOST_CONF_W0
+ 0x6C
+ 0x20
+
+
+ HOST_SLCHOST_CONF0
+ 0
+ 8
+ read-write
+
+
+ HOST_SLCHOST_CONF1
+ 8
+ 8
+ read-write
+
+
+ HOST_SLCHOST_CONF2
+ 16
+ 8
+ read-write
+
+
+ HOST_SLCHOST_CONF3
+ 24
+ 8
+ read-write
+
+
+
+
+ HOST_SLCHOST_CONF_W1
+ 0x70
+ 0x20
+
+
+ HOST_SLCHOST_CONF4
+ 0
+ 8
+ read-write
+
+
+ HOST_SLCHOST_CONF5
+ 8
+ 8
+ read-write
+
+
+ HOST_SLCHOST_CONF6
+ 16
+ 8
+ read-write
+
+
+ HOST_SLCHOST_CONF7
+ 24
+ 8
+ read-write
+
+
+
+
+ HOST_SLCHOST_CONF_W2
+ 0x74
+ 0x20
+
+
+ HOST_SLCHOST_CONF8
+ 0
+ 8
+ read-write
+
+
+ HOST_SLCHOST_CONF9
+ 8
+ 8
+ read-write
+
+
+ HOST_SLCHOST_CONF10
+ 16
+ 8
+ read-write
+
+
+ HOST_SLCHOST_CONF11
+ 24
+ 8
+ read-write
+
+
+
+
+ HOST_SLCHOST_CONF_W3
+ 0x78
+ 0x20
+ 0x000000C0
+
+
+ HOST_SLCHOST_CONF12
+ 0
+ 8
+ read-write
+
+
+ HOST_SLCHOST_CONF13
+ 8
+ 8
+ read-write
+
+
+ HOST_SLCHOST_CONF14
+ 16
+ 8
+ read-write
+
+
+ HOST_SLCHOST_CONF15
+ 24
+ 8
+ read-write
+
+
+
+
+ HOST_SLCHOST_CONF_W4
+ 0x7C
+ 0x20
+ 0x000001FF
+
+
+ HOST_SLCHOST_CONF16
+ SLC timeout value
+ 0
+ 8
+ read-write
+
+
+ HOST_SLCHOST_CONF17
+ SLC timeout enable
+ 8
+ 8
+ read-write
+
+
+ HOST_SLCHOST_CONF18
+ 16
+ 8
+ read-write
+
+
+ HOST_SLCHOST_CONF19
+ Interrupt to target CPU
+ 24
+ 8
+ read-write
+
+
+
+
+ HOST_SLCHOST_CONF_W5
+ 0x80
+ 0x20
+
+
+ HOST_SLCHOST_CONF20
+ 0
+ 8
+ read-write
+
+
+ HOST_SLCHOST_CONF21
+ 8
+ 8
+ read-write
+
+
+ HOST_SLCHOST_CONF22
+ 16
+ 8
+ read-write
+
+
+ HOST_SLCHOST_CONF23
+ 24
+ 8
+ read-write
+
+
+
+
+ HOST_SLCHOST_WIN_CMD
+ 0x84
+ 0x20
+
+
+ HOST_SLCHOST_CONF_W6
+ 0x88
+ 0x20
+
+
+ HOST_SLCHOST_CONF24
+ 0
+ 8
+ read-write
+
+
+ HOST_SLCHOST_CONF25
+ 8
+ 8
+ read-write
+
+
+ HOST_SLCHOST_CONF26
+ 16
+ 8
+ read-write
+
+
+ HOST_SLCHOST_CONF27
+ 24
+ 8
+ read-write
+
+
+
+
+ HOST_SLCHOST_CONF_W7
+ 0x8C
+ 0x20
+
+
+ HOST_SLCHOST_CONF28
+ 0
+ 8
+ read-write
+
+
+ HOST_SLCHOST_CONF29
+ 8
+ 8
+ read-write
+
+
+ HOST_SLCHOST_CONF30
+ 16
+ 8
+ read-write
+
+
+ HOST_SLCHOST_CONF31
+ 24
+ 8
+ read-write
+
+
+
+
+ HOST_SLCHOST_PKT_LEN0
+ 0x90
+ 0x20
+
+
+ HOST_HOSTSLC0_LEN0
+ 0
+ 20
+ read-only
+
+
+
+
+ HOST_SLCHOST_PKT_LEN1
+ 0x94
+ 0x20
+
+
+ HOST_HOSTSLC0_LEN1
+ 0
+ 20
+ read-only
+
+
+
+
+ HOST_SLCHOST_PKT_LEN2
+ 0x98
+ 0x20
+
+
+ HOST_HOSTSLC0_LEN2
+ 0
+ 20
+ read-only
+
+
+
+
+ HOST_SLCHOST_CONF_W8
+ 0x9C
+ 0x20
+
+
+ HOST_SLCHOST_CONF32
+ 0
+ 8
+ read-write
+
+
+ HOST_SLCHOST_CONF33
+ 8
+ 8
+ read-write
+
+
+ HOST_SLCHOST_CONF34
+ 16
+ 8
+ read-write
+
+
+ HOST_SLCHOST_CONF35
+ 24
+ 8
+ read-write
+
+
+
+
+ HOST_SLCHOST_CONF_W9
+ 0xA0
+ 0x20
+
+
+ HOST_SLCHOST_CONF36
+ 0
+ 8
+ read-write
+
+
+ HOST_SLCHOST_CONF37
+ 8
+ 8
+ read-write
+
+
+ HOST_SLCHOST_CONF38
+ 16
+ 8
+ read-write
+
+
+ HOST_SLCHOST_CONF39
+ 24
+ 8
+ read-write
+
+
+
+
+ HOST_SLCHOST_CONF_W10
+ 0xA4
+ 0x20
+
+
+ HOST_SLCHOST_CONF40
+ 0
+ 8
+ read-write
+
+
+ HOST_SLCHOST_CONF41
+ 8
+ 8
+ read-write
+
+
+ HOST_SLCHOST_CONF42
+ 16
+ 8
+ read-write
+
+
+ HOST_SLCHOST_CONF43
+ 24
+ 8
+ read-write
+
+
+
+
+ HOST_SLCHOST_CONF_W11
+ 0xA8
+ 0x20
+
+
+ HOST_SLCHOST_CONF44
+ 0
+ 8
+ read-write
+
+
+ HOST_SLCHOST_CONF45
+ 8
+ 8
+ read-write
+
+
+ HOST_SLCHOST_CONF46
+ 16
+ 8
+ read-write
+
+
+ HOST_SLCHOST_CONF47
+ 24
+ 8
+ read-write
+
+
+
+
+ HOST_SLCHOST_CONF_W12
+ 0xAC
+ 0x20
+
+
+ HOST_SLCHOST_CONF48
+ 0
+ 8
+ read-write
+
+
+ HOST_SLCHOST_CONF49
+ 8
+ 8
+ read-write
+
+
+ HOST_SLCHOST_CONF50
+ 16
+ 8
+ read-write
+
+
+ HOST_SLCHOST_CONF51
+ 24
+ 8
+ read-write
+
+
+
+
+ HOST_SLCHOST_CONF_W13
+ 0xB0
+ 0x20
+
+
+ HOST_SLCHOST_CONF52
+ 0
+ 8
+ read-write
+
+
+ HOST_SLCHOST_CONF53
+ 8
+ 8
+ read-write
+
+
+ HOST_SLCHOST_CONF54
+ 16
+ 8
+ read-write
+
+
+ HOST_SLCHOST_CONF55
+ 24
+ 8
+ read-write
+
+
+
+
+ HOST_SLCHOST_CONF_W14
+ 0xB4
+ 0x20
+
+
+ HOST_SLCHOST_CONF56
+ 0
+ 8
+ read-write
+
+
+ HOST_SLCHOST_CONF57
+ 8
+ 8
+ read-write
+
+
+ HOST_SLCHOST_CONF58
+ 16
+ 8
+ read-write
+
+
+ HOST_SLCHOST_CONF59
+ 24
+ 8
+ read-write
+
+
+
+
+ HOST_SLCHOST_CONF_W15
+ 0xB8
+ 0x20
+
+
+ HOST_SLCHOST_CONF60
+ 0
+ 8
+ read-write
+
+
+ HOST_SLCHOST_CONF61
+ 8
+ 8
+ read-write
+
+
+ HOST_SLCHOST_CONF62
+ 16
+ 8
+ read-write
+
+
+ HOST_SLCHOST_CONF63
+ 24
+ 8
+ read-write
+
+
+
+
+ HOST_SLCHOST_CHECK_SUM0
+ 0xBC
+ 0x20
+
+
+ HOST_SLCHOST_CHECK_SUM0
+ 0
+ 32
+ read-only
+
+
+
+
+ HOST_SLCHOST_CHECK_SUM1
+ 0xC0
+ 0x20
+
+
+ HOST_SLCHOST_CHECK_SUM1
+ 0
+ 32
+ read-only
+
+
+
+
+ HOST_SLC1HOST_TOKEN_RDATA
+ 0xC4
+ 0x20
+
+
+ HOST_SLC1_TOKEN0
+ 0
+ 12
+ read-only
+
+
+ HOST_SLC1_RX_PF_VALID
+ 12
+ 1
+ read-only
+
+
+ HOST_HOSTSLC1_TOKEN1
+ 16
+ 12
+ read-only
+
+
+ HOST_SLC1_RX_PF_EOF
+ 28
+ 4
+ read-only
+
+
+
+
+ HOST_SLC0HOST_TOKEN_WDATA
+ 0xC8
+ 0x20
+
+
+ HOST_SLC0HOST_TOKEN0_WD
+ 0
+ 12
+ read-write
+
+
+ HOST_SLC0HOST_TOKEN1_WD
+ 16
+ 12
+ read-write
+
+
+
+
+ HOST_SLC1HOST_TOKEN_WDATA
+ 0xCC
+ 0x20
+
+
+ HOST_SLC1HOST_TOKEN0_WD
+ 0
+ 12
+ read-write
+
+
+ HOST_SLC1HOST_TOKEN1_WD
+ 16
+ 12
+ read-write
+
+
+
+
+ HOST_SLCHOST_TOKEN_CON
+ 0xD0
+ 0x20
+
+
+ HOST_SLC0HOST_TOKEN0_DEC
+ 0
+ 1
+ write-only
+
+
+ HOST_SLC0HOST_TOKEN1_DEC
+ 1
+ 1
+ write-only
+
+
+ HOST_SLC0HOST_TOKEN0_WR
+ 2
+ 1
+ write-only
+
+
+ HOST_SLC0HOST_TOKEN1_WR
+ 3
+ 1
+ write-only
+
+
+ HOST_SLC1HOST_TOKEN0_DEC
+ 4
+ 1
+ write-only
+
+
+ HOST_SLC1HOST_TOKEN1_DEC
+ 5
+ 1
+ write-only
+
+
+ HOST_SLC1HOST_TOKEN0_WR
+ 6
+ 1
+ write-only
+
+
+ HOST_SLC1HOST_TOKEN1_WR
+ 7
+ 1
+ write-only
+
+
+ HOST_SLC0HOST_LEN_WR
+ 8
+ 1
+ write-only
+
+
+
+
+ HOST_SLC0HOST_INT_CLR
+ 0xD4
+ 0x20
+
+
+ HOST_SLC0_TOHOST_BIT0_INT_CLR
+ 0
+ 1
+ write-only
+
+
+ HOST_SLC0_TOHOST_BIT1_INT_CLR
+ 1
+ 1
+ write-only
+
+
+ HOST_SLC0_TOHOST_BIT2_INT_CLR
+ 2
+ 1
+ write-only
+
+
+ HOST_SLC0_TOHOST_BIT3_INT_CLR
+ 3
+ 1
+ write-only
+
+
+ HOST_SLC0_TOHOST_BIT4_INT_CLR
+ 4
+ 1
+ write-only
+
+
+ HOST_SLC0_TOHOST_BIT5_INT_CLR
+ 5
+ 1
+ write-only
+
+
+ HOST_SLC0_TOHOST_BIT6_INT_CLR
+ 6
+ 1
+ write-only
+
+
+ HOST_SLC0_TOHOST_BIT7_INT_CLR
+ 7
+ 1
+ write-only
+
+
+ HOST_SLC0_TOKEN0_1TO0_INT_CLR
+ 8
+ 1
+ write-only
+
+
+ HOST_SLC0_TOKEN1_1TO0_INT_CLR
+ 9
+ 1
+ write-only
+
+
+ HOST_SLC0_TOKEN0_0TO1_INT_CLR
+ 10
+ 1
+ write-only
+
+
+ HOST_SLC0_TOKEN1_0TO1_INT_CLR
+ 11
+ 1
+ write-only
+
+
+ HOST_SLC0HOST_RX_SOF_INT_CLR
+ 12
+ 1
+ write-only
+
+
+ HOST_SLC0HOST_RX_EOF_INT_CLR
+ 13
+ 1
+ write-only
+
+
+ HOST_SLC0HOST_RX_START_INT_CLR
+ 14
+ 1
+ write-only
+
+
+ HOST_SLC0HOST_TX_START_INT_CLR
+ 15
+ 1
+ write-only
+
+
+ HOST_SLC0_RX_UDF_INT_CLR
+ 16
+ 1
+ write-only
+
+
+ HOST_SLC0_TX_OVF_INT_CLR
+ 17
+ 1
+ write-only
+
+
+ HOST_SLC0_RX_PF_VALID_INT_CLR
+ 18
+ 1
+ write-only
+
+
+ HOST_SLC0_EXT_BIT0_INT_CLR
+ 19
+ 1
+ write-only
+
+
+ HOST_SLC0_EXT_BIT1_INT_CLR
+ 20
+ 1
+ write-only
+
+
+ HOST_SLC0_EXT_BIT2_INT_CLR
+ 21
+ 1
+ write-only
+
+
+ HOST_SLC0_EXT_BIT3_INT_CLR
+ 22
+ 1
+ write-only
+
+
+ HOST_SLC0_RX_NEW_PACKET_INT_CLR
+ 23
+ 1
+ write-only
+
+
+ HOST_SLC0_HOST_RD_RETRY_INT_CLR
+ 24
+ 1
+ write-only
+
+
+ HOST_GPIO_SDIO_INT_CLR
+ 25
+ 1
+ write-only
+
+
+
+
+ HOST_SLC1HOST_INT_CLR
+ 0xD8
+ 0x20
+
+
+ HOST_SLC1_TOHOST_BIT0_INT_CLR
+ 0
+ 1
+ write-only
+
+
+ HOST_SLC1_TOHOST_BIT1_INT_CLR
+ 1
+ 1
+ write-only
+
+
+ HOST_SLC1_TOHOST_BIT2_INT_CLR
+ 2
+ 1
+ write-only
+
+
+ HOST_SLC1_TOHOST_BIT3_INT_CLR
+ 3
+ 1
+ write-only
+
+
+ HOST_SLC1_TOHOST_BIT4_INT_CLR
+ 4
+ 1
+ write-only
+
+
+ HOST_SLC1_TOHOST_BIT5_INT_CLR
+ 5
+ 1
+ write-only
+
+
+ HOST_SLC1_TOHOST_BIT6_INT_CLR
+ 6
+ 1
+ write-only
+
+
+ HOST_SLC1_TOHOST_BIT7_INT_CLR
+ 7
+ 1
+ write-only
+
+
+ HOST_SLC1_TOKEN0_1TO0_INT_CLR
+ 8
+ 1
+ write-only
+
+
+ HOST_SLC1_TOKEN1_1TO0_INT_CLR
+ 9
+ 1
+ write-only
+
+
+ HOST_SLC1_TOKEN0_0TO1_INT_CLR
+ 10
+ 1
+ write-only
+
+
+ HOST_SLC1_TOKEN1_0TO1_INT_CLR
+ 11
+ 1
+ write-only
+
+
+ HOST_SLC1HOST_RX_SOF_INT_CLR
+ 12
+ 1
+ write-only
+
+
+ HOST_SLC1HOST_RX_EOF_INT_CLR
+ 13
+ 1
+ write-only
+
+
+ HOST_SLC1HOST_RX_START_INT_CLR
+ 14
+ 1
+ write-only
+
+
+ HOST_SLC1HOST_TX_START_INT_CLR
+ 15
+ 1
+ write-only
+
+
+ HOST_SLC1_RX_UDF_INT_CLR
+ 16
+ 1
+ write-only
+
+
+ HOST_SLC1_TX_OVF_INT_CLR
+ 17
+ 1
+ write-only
+
+
+ HOST_SLC1_RX_PF_VALID_INT_CLR
+ 18
+ 1
+ write-only
+
+
+ HOST_SLC1_EXT_BIT0_INT_CLR
+ 19
+ 1
+ write-only
+
+
+ HOST_SLC1_EXT_BIT1_INT_CLR
+ 20
+ 1
+ write-only
+
+
+ HOST_SLC1_EXT_BIT2_INT_CLR
+ 21
+ 1
+ write-only
+
+
+ HOST_SLC1_EXT_BIT3_INT_CLR
+ 22
+ 1
+ write-only
+
+
+ HOST_SLC1_WIFI_RX_NEW_PACKET_INT_CLR
+ 23
+ 1
+ write-only
+
+
+ HOST_SLC1_HOST_RD_RETRY_INT_CLR
+ 24
+ 1
+ write-only
+
+
+ HOST_SLC1_BT_RX_NEW_PACKET_INT_CLR
+ 25
+ 1
+ write-only
+
+
+
+
+ HOST_SLC0HOST_FUNC1_INT_ENA
+ 0xDC
+ 0x20
+
+
+ HOST_FN1_SLC0_TOHOST_BIT0_INT_ENA
+ 0
+ 1
+ read-write
+
+
+ HOST_FN1_SLC0_TOHOST_BIT1_INT_ENA
+ 1
+ 1
+ read-write
+
+
+ HOST_FN1_SLC0_TOHOST_BIT2_INT_ENA
+ 2
+ 1
+ read-write
+
+
+ HOST_FN1_SLC0_TOHOST_BIT3_INT_ENA
+ 3
+ 1
+ read-write
+
+
+ HOST_FN1_SLC0_TOHOST_BIT4_INT_ENA
+ 4
+ 1
+ read-write
+
+
+ HOST_FN1_SLC0_TOHOST_BIT5_INT_ENA
+ 5
+ 1
+ read-write
+
+
+ HOST_FN1_SLC0_TOHOST_BIT6_INT_ENA
+ 6
+ 1
+ read-write
+
+
+ HOST_FN1_SLC0_TOHOST_BIT7_INT_ENA
+ 7
+ 1
+ read-write
+
+
+ HOST_FN1_SLC0_TOKEN0_1TO0_INT_ENA
+ 8
+ 1
+ read-write
+
+
+ HOST_FN1_SLC0_TOKEN1_1TO0_INT_ENA
+ 9
+ 1
+ read-write
+
+
+ HOST_FN1_SLC0_TOKEN0_0TO1_INT_ENA
+ 10
+ 1
+ read-write
+
+
+ HOST_FN1_SLC0_TOKEN1_0TO1_INT_ENA
+ 11
+ 1
+ read-write
+
+
+ HOST_FN1_SLC0HOST_RX_SOF_INT_ENA
+ 12
+ 1
+ read-write
+
+
+ HOST_FN1_SLC0HOST_RX_EOF_INT_ENA
+ 13
+ 1
+ read-write
+
+
+ HOST_FN1_SLC0HOST_RX_START_INT_ENA
+ 14
+ 1
+ read-write
+
+
+ HOST_FN1_SLC0HOST_TX_START_INT_ENA
+ 15
+ 1
+ read-write
+
+
+ HOST_FN1_SLC0_RX_UDF_INT_ENA
+ 16
+ 1
+ read-write
+
+
+ HOST_FN1_SLC0_TX_OVF_INT_ENA
+ 17
+ 1
+ read-write
+
+
+ HOST_FN1_SLC0_RX_PF_VALID_INT_ENA
+ 18
+ 1
+ read-write
+
+
+ HOST_FN1_SLC0_EXT_BIT0_INT_ENA
+ 19
+ 1
+ read-write
+
+
+ HOST_FN1_SLC0_EXT_BIT1_INT_ENA
+ 20
+ 1
+ read-write
+
+
+ HOST_FN1_SLC0_EXT_BIT2_INT_ENA
+ 21
+ 1
+ read-write
+
+
+ HOST_FN1_SLC0_EXT_BIT3_INT_ENA
+ 22
+ 1
+ read-write
+
+
+ HOST_FN1_SLC0_RX_NEW_PACKET_INT_ENA
+ 23
+ 1
+ read-write
+
+
+ HOST_FN1_SLC0_HOST_RD_RETRY_INT_ENA
+ 24
+ 1
+ read-write
+
+
+ HOST_FN1_GPIO_SDIO_INT_ENA
+ 25
+ 1
+ read-write
+
+
+
+
+ HOST_SLC1HOST_FUNC1_INT_ENA
+ 0xE0
+ 0x20
+
+
+ HOST_FN1_SLC1_TOHOST_BIT0_INT_ENA
+ 0
+ 1
+ read-write
+
+
+ HOST_FN1_SLC1_TOHOST_BIT1_INT_ENA
+ 1
+ 1
+ read-write
+
+
+ HOST_FN1_SLC1_TOHOST_BIT2_INT_ENA
+ 2
+ 1
+ read-write
+
+
+ HOST_FN1_SLC1_TOHOST_BIT3_INT_ENA
+ 3
+ 1
+ read-write
+
+
+ HOST_FN1_SLC1_TOHOST_BIT4_INT_ENA
+ 4
+ 1
+ read-write
+
+
+ HOST_FN1_SLC1_TOHOST_BIT5_INT_ENA
+ 5
+ 1
+ read-write
+
+
+ HOST_FN1_SLC1_TOHOST_BIT6_INT_ENA
+ 6
+ 1
+ read-write
+
+
+ HOST_FN1_SLC1_TOHOST_BIT7_INT_ENA
+ 7
+ 1
+ read-write
+
+
+ HOST_FN1_SLC1_TOKEN0_1TO0_INT_ENA
+ 8
+ 1
+ read-write
+
+
+ HOST_FN1_SLC1_TOKEN1_1TO0_INT_ENA
+ 9
+ 1
+ read-write
+
+
+ HOST_FN1_SLC1_TOKEN0_0TO1_INT_ENA
+ 10
+ 1
+ read-write
+
+
+ HOST_FN1_SLC1_TOKEN1_0TO1_INT_ENA
+ 11
+ 1
+ read-write
+
+
+ HOST_FN1_SLC1HOST_RX_SOF_INT_ENA
+ 12
+ 1
+ read-write
+
+
+ HOST_FN1_SLC1HOST_RX_EOF_INT_ENA
+ 13
+ 1
+ read-write
+
+
+ HOST_FN1_SLC1HOST_RX_START_INT_ENA
+ 14
+ 1
+ read-write
+
+
+ HOST_FN1_SLC1HOST_TX_START_INT_ENA
+ 15
+ 1
+ read-write
+
+
+ HOST_FN1_SLC1_RX_UDF_INT_ENA
+ 16
+ 1
+ read-write
+
+
+ HOST_FN1_SLC1_TX_OVF_INT_ENA
+ 17
+ 1
+ read-write
+
+
+ HOST_FN1_SLC1_RX_PF_VALID_INT_ENA
+ 18
+ 1
+ read-write
+
+
+ HOST_FN1_SLC1_EXT_BIT0_INT_ENA
+ 19
+ 1
+ read-write
+
+
+ HOST_FN1_SLC1_EXT_BIT1_INT_ENA
+ 20
+ 1
+ read-write
+
+
+ HOST_FN1_SLC1_EXT_BIT2_INT_ENA
+ 21
+ 1
+ read-write
+
+
+ HOST_FN1_SLC1_EXT_BIT3_INT_ENA
+ 22
+ 1
+ read-write
+
+
+ HOST_FN1_SLC1_WIFI_RX_NEW_PACKET_INT_ENA
+ 23
+ 1
+ read-write
+
+
+ HOST_FN1_SLC1_HOST_RD_RETRY_INT_ENA
+ 24
+ 1
+ read-write
+
+
+ HOST_FN1_SLC1_BT_RX_NEW_PACKET_INT_ENA
+ 25
+ 1
+ read-write
+
+
+
+
+ HOST_SLC0HOST_FUNC2_INT_ENA
+ 0xE4
+ 0x20
+
+
+ HOST_FN2_SLC0_TOHOST_BIT0_INT_ENA
+ 0
+ 1
+ read-write
+
+
+ HOST_FN2_SLC0_TOHOST_BIT1_INT_ENA
+ 1
+ 1
+ read-write
+
+
+ HOST_FN2_SLC0_TOHOST_BIT2_INT_ENA
+ 2
+ 1
+ read-write
+
+
+ HOST_FN2_SLC0_TOHOST_BIT3_INT_ENA
+ 3
+ 1
+ read-write
+
+
+ HOST_FN2_SLC0_TOHOST_BIT4_INT_ENA
+ 4
+ 1
+ read-write
+
+
+ HOST_FN2_SLC0_TOHOST_BIT5_INT_ENA
+ 5
+ 1
+ read-write
+
+
+ HOST_FN2_SLC0_TOHOST_BIT6_INT_ENA
+ 6
+ 1
+ read-write
+
+
+ HOST_FN2_SLC0_TOHOST_BIT7_INT_ENA
+ 7
+ 1
+ read-write
+
+
+ HOST_FN2_SLC0_TOKEN0_1TO0_INT_ENA
+ 8
+ 1
+ read-write
+
+
+ HOST_FN2_SLC0_TOKEN1_1TO0_INT_ENA
+ 9
+ 1
+ read-write
+
+
+ HOST_FN2_SLC0_TOKEN0_0TO1_INT_ENA
+ 10
+ 1
+ read-write
+
+
+ HOST_FN2_SLC0_TOKEN1_0TO1_INT_ENA
+ 11
+ 1
+ read-write
+
+
+ HOST_FN2_SLC0HOST_RX_SOF_INT_ENA
+ 12
+ 1
+ read-write
+
+
+ HOST_FN2_SLC0HOST_RX_EOF_INT_ENA
+ 13
+ 1
+ read-write
+
+
+ HOST_FN2_SLC0HOST_RX_START_INT_ENA
+ 14
+ 1
+ read-write
+
+
+ HOST_FN2_SLC0HOST_TX_START_INT_ENA
+ 15
+ 1
+ read-write
+
+
+ HOST_FN2_SLC0_RX_UDF_INT_ENA
+ 16
+ 1
+ read-write
+
+
+ HOST_FN2_SLC0_TX_OVF_INT_ENA
+ 17
+ 1
+ read-write
+
+
+ HOST_FN2_SLC0_RX_PF_VALID_INT_ENA
+ 18
+ 1
+ read-write
+
+
+ HOST_FN2_SLC0_EXT_BIT0_INT_ENA
+ 19
+ 1
+ read-write
+
+
+ HOST_FN2_SLC0_EXT_BIT1_INT_ENA
+ 20
+ 1
+ read-write
+
+
+ HOST_FN2_SLC0_EXT_BIT2_INT_ENA
+ 21
+ 1
+ read-write
+
+
+ HOST_FN2_SLC0_EXT_BIT3_INT_ENA
+ 22
+ 1
+ read-write
+
+
+ HOST_FN2_SLC0_RX_NEW_PACKET_INT_ENA
+ 23
+ 1
+ read-write
+
+
+ HOST_FN2_SLC0_HOST_RD_RETRY_INT_ENA
+ 24
+ 1
+ read-write
+
+
+ HOST_FN2_GPIO_SDIO_INT_ENA
+ 25
+ 1
+ read-write
+
+
+
+
+ HOST_SLC1HOST_FUNC2_INT_ENA
+ 0xE8
+ 0x20
+
+
+ HOST_FN2_SLC1_TOHOST_BIT0_INT_ENA
+ 0
+ 1
+ read-write
+
+
+ HOST_FN2_SLC1_TOHOST_BIT1_INT_ENA
+ 1
+ 1
+ read-write
+
+
+ HOST_FN2_SLC1_TOHOST_BIT2_INT_ENA
+ 2
+ 1
+ read-write
+
+
+ HOST_FN2_SLC1_TOHOST_BIT3_INT_ENA
+ 3
+ 1
+ read-write
+
+
+ HOST_FN2_SLC1_TOHOST_BIT4_INT_ENA
+ 4
+ 1
+ read-write
+
+
+ HOST_FN2_SLC1_TOHOST_BIT5_INT_ENA
+ 5
+ 1
+ read-write
+
+
+ HOST_FN2_SLC1_TOHOST_BIT6_INT_ENA
+ 6
+ 1
+ read-write
+
+
+ HOST_FN2_SLC1_TOHOST_BIT7_INT_ENA
+ 7
+ 1
+ read-write
+
+
+ HOST_FN2_SLC1_TOKEN0_1TO0_INT_ENA
+ 8
+ 1
+ read-write
+
+
+ HOST_FN2_SLC1_TOKEN1_1TO0_INT_ENA
+ 9
+ 1
+ read-write
+
+
+ HOST_FN2_SLC1_TOKEN0_0TO1_INT_ENA
+ 10
+ 1
+ read-write
+
+
+ HOST_FN2_SLC1_TOKEN1_0TO1_INT_ENA
+ 11
+ 1
+ read-write
+
+
+ HOST_FN2_SLC1HOST_RX_SOF_INT_ENA
+ 12
+ 1
+ read-write
+
+
+ HOST_FN2_SLC1HOST_RX_EOF_INT_ENA
+ 13
+ 1
+ read-write
+
+
+ HOST_FN2_SLC1HOST_RX_START_INT_ENA
+ 14
+ 1
+ read-write
+
+
+ HOST_FN2_SLC1HOST_TX_START_INT_ENA
+ 15
+ 1
+ read-write
+
+
+ HOST_FN2_SLC1_RX_UDF_INT_ENA
+ 16
+ 1
+ read-write
+
+
+ HOST_FN2_SLC1_TX_OVF_INT_ENA
+ 17
+ 1
+ read-write
+
+
+ HOST_FN2_SLC1_RX_PF_VALID_INT_ENA
+ 18
+ 1
+ read-write
+
+
+ HOST_FN2_SLC1_EXT_BIT0_INT_ENA
+ 19
+ 1
+ read-write
+
+
+ HOST_FN2_SLC1_EXT_BIT1_INT_ENA
+ 20
+ 1
+ read-write
+
+
+ HOST_FN2_SLC1_EXT_BIT2_INT_ENA
+ 21
+ 1
+ read-write
+
+
+ HOST_FN2_SLC1_EXT_BIT3_INT_ENA
+ 22
+ 1
+ read-write
+
+
+ HOST_FN2_SLC1_WIFI_RX_NEW_PACKET_INT_ENA
+ 23
+ 1
+ read-write
+
+
+ HOST_FN2_SLC1_HOST_RD_RETRY_INT_ENA
+ 24
+ 1
+ read-write
+
+
+ HOST_FN2_SLC1_BT_RX_NEW_PACKET_INT_ENA
+ 25
+ 1
+ read-write
+
+
+
+
+ HOST_SLC0HOST_INT_ENA
+ 0xEC
+ 0x20
+
+
+ HOST_SLC0_TOHOST_BIT0_INT_ENA
+ 0
+ 1
+ read-write
+
+
+ HOST_SLC0_TOHOST_BIT1_INT_ENA
+ 1
+ 1
+ read-write
+
+
+ HOST_SLC0_TOHOST_BIT2_INT_ENA
+ 2
+ 1
+ read-write
+
+
+ HOST_SLC0_TOHOST_BIT3_INT_ENA
+ 3
+ 1
+ read-write
+
+
+ HOST_SLC0_TOHOST_BIT4_INT_ENA
+ 4
+ 1
+ read-write
+
+
+ HOST_SLC0_TOHOST_BIT5_INT_ENA
+ 5
+ 1
+ read-write
+
+
+ HOST_SLC0_TOHOST_BIT6_INT_ENA
+ 6
+ 1
+ read-write
+
+
+ HOST_SLC0_TOHOST_BIT7_INT_ENA
+ 7
+ 1
+ read-write
+
+
+ HOST_SLC0_TOKEN0_1TO0_INT_ENA
+ 8
+ 1
+ read-write
+
+
+ HOST_SLC0_TOKEN1_1TO0_INT_ENA
+ 9
+ 1
+ read-write
+
+
+ HOST_SLC0_TOKEN0_0TO1_INT_ENA
+ 10
+ 1
+ read-write
+
+
+ HOST_SLC0_TOKEN1_0TO1_INT_ENA
+ 11
+ 1
+ read-write
+
+
+ HOST_SLC0HOST_RX_SOF_INT_ENA
+ 12
+ 1
+ read-write
+
+
+ HOST_SLC0HOST_RX_EOF_INT_ENA
+ 13
+ 1
+ read-write
+
+
+ HOST_SLC0HOST_RX_START_INT_ENA
+ 14
+ 1
+ read-write
+
+
+ HOST_SLC0HOST_TX_START_INT_ENA
+ 15
+ 1
+ read-write
+
+
+ HOST_SLC0_RX_UDF_INT_ENA
+ 16
+ 1
+ read-write
+
+
+ HOST_SLC0_TX_OVF_INT_ENA
+ 17
+ 1
+ read-write
+
+
+ HOST_SLC0_RX_PF_VALID_INT_ENA
+ 18
+ 1
+ read-write
+
+
+ HOST_SLC0_EXT_BIT0_INT_ENA
+ 19
+ 1
+ read-write
+
+
+ HOST_SLC0_EXT_BIT1_INT_ENA
+ 20
+ 1
+ read-write
+
+
+ HOST_SLC0_EXT_BIT2_INT_ENA
+ 21
+ 1
+ read-write
+
+
+ HOST_SLC0_EXT_BIT3_INT_ENA
+ 22
+ 1
+ read-write
+
+
+ HOST_SLC0_RX_NEW_PACKET_INT_ENA
+ 23
+ 1
+ read-write
+
+
+ HOST_SLC0_HOST_RD_RETRY_INT_ENA
+ 24
+ 1
+ read-write
+
+
+ HOST_GPIO_SDIO_INT_ENA
+ 25
+ 1
+ read-write
+
+
+
+
+ HOST_SLC1HOST_INT_ENA
+ 0xF0
+ 0x20
+
+
+ HOST_SLC1_TOHOST_BIT0_INT_ENA
+ 0
+ 1
+ read-write
+
+
+ HOST_SLC1_TOHOST_BIT1_INT_ENA
+ 1
+ 1
+ read-write
+
+
+ HOST_SLC1_TOHOST_BIT2_INT_ENA
+ 2
+ 1
+ read-write
+
+
+ HOST_SLC1_TOHOST_BIT3_INT_ENA
+ 3
+ 1
+ read-write
+
+
+ HOST_SLC1_TOHOST_BIT4_INT_ENA
+ 4
+ 1
+ read-write
+
+
+ HOST_SLC1_TOHOST_BIT5_INT_ENA
+ 5
+ 1
+ read-write
+
+
+ HOST_SLC1_TOHOST_BIT6_INT_ENA
+ 6
+ 1
+ read-write
+
+
+ HOST_SLC1_TOHOST_BIT7_INT_ENA
+ 7
+ 1
+ read-write
+
+
+ HOST_SLC1_TOKEN0_1TO0_INT_ENA
+ 8
+ 1
+ read-write
+
+
+ HOST_SLC1_TOKEN1_1TO0_INT_ENA
+ 9
+ 1
+ read-write
+
+
+ HOST_SLC1_TOKEN0_0TO1_INT_ENA
+ 10
+ 1
+ read-write
+
+
+ HOST_SLC1_TOKEN1_0TO1_INT_ENA
+ 11
+ 1
+ read-write
+
+
+ HOST_SLC1HOST_RX_SOF_INT_ENA
+ 12
+ 1
+ read-write
+
+
+ HOST_SLC1HOST_RX_EOF_INT_ENA
+ 13
+ 1
+ read-write
+
+
+ HOST_SLC1HOST_RX_START_INT_ENA
+ 14
+ 1
+ read-write
+
+
+ HOST_SLC1HOST_TX_START_INT_ENA
+ 15
+ 1
+ read-write
+
+
+ HOST_SLC1_RX_UDF_INT_ENA
+ 16
+ 1
+ read-write
+
+
+ HOST_SLC1_TX_OVF_INT_ENA
+ 17
+ 1
+ read-write
+
+
+ HOST_SLC1_RX_PF_VALID_INT_ENA
+ 18
+ 1
+ read-write
+
+
+ HOST_SLC1_EXT_BIT0_INT_ENA
+ 19
+ 1
+ read-write
+
+
+ HOST_SLC1_EXT_BIT1_INT_ENA
+ 20
+ 1
+ read-write
+
+
+ HOST_SLC1_EXT_BIT2_INT_ENA
+ 21
+ 1
+ read-write
+
+
+ HOST_SLC1_EXT_BIT3_INT_ENA
+ 22
+ 1
+ read-write
+
+
+ HOST_SLC1_WIFI_RX_NEW_PACKET_INT_ENA
+ 23
+ 1
+ read-write
+
+
+ HOST_SLC1_HOST_RD_RETRY_INT_ENA
+ 24
+ 1
+ read-write
+
+
+ HOST_SLC1_BT_RX_NEW_PACKET_INT_ENA
+ 25
+ 1
+ read-write
+
+
+
+
+ HOST_SLC0HOST_RX_INFOR
+ 0xF4
+ 0x20
+
+
+ HOST_SLC0HOST_RX_INFOR
+ 0
+ 20
+ read-write
+
+
+
+
+ HOST_SLC1HOST_RX_INFOR
+ 0xF8
+ 0x20
+
+
+ HOST_SLC1HOST_RX_INFOR
+ 0
+ 20
+ read-write
+
+
+
+
+ HOST_SLC0HOST_LEN_WD
+ 0xFC
+ 0x20
+
+
+ HOST_SLC0HOST_LEN_WD
+ 0
+ 32
+ read-write
+
+
+
+
+ HOST_SLC_APBWIN_WDATA
+ 0x100
+ 0x20
+
+
+ HOST_SLC_APBWIN_WDATA
+ 0
+ 32
+ read-write
+
+
+
+
+ HOST_SLC_APBWIN_CONF
+ 0x104
+ 0x20
+
+
+ HOST_SLC_APBWIN_ADDR
+ 0
+ 28
+ read-write
+
+
+ HOST_SLC_APBWIN_WR
+ 28
+ 1
+ read-write
+
+
+ HOST_SLC_APBWIN_START
+ 29
+ 1
+ read-write
+
+
+
+
+ HOST_SLC_APBWIN_RDATA
+ 0x108
+ 0x20
+
+
+ HOST_SLC_APBWIN_RDATA
+ 0
+ 32
+ read-only
+
+
+
+
+ HOST_SLCHOST_RDCLR0
+ 0x10C
+ 0x20
+ 0x0003C044
+
+
+ HOST_SLCHOST_SLC0_BIT7_CLRADDR
+ 0
+ 9
+ read-write
+
+
+ HOST_SLCHOST_SLC0_BIT6_CLRADDR
+ 9
+ 9
+ read-write
+
+
+
+
+ HOST_SLCHOST_RDCLR1
+ 0x110
+ 0x20
+ 0x0003C1E0
+
+
+ HOST_SLCHOST_SLC1_BIT7_CLRADDR
+ 0
+ 9
+ read-write
+
+
+ HOST_SLCHOST_SLC1_BIT6_CLRADDR
+ 9
+ 9
+ read-write
+
+
+
+
+ HOST_SLC0HOST_INT_ENA1
+ 0x114
+ 0x20
+
+
+ HOST_SLC0_TOHOST_BIT0_INT_ENA1
+ 0
+ 1
+ read-write
+
+
+ HOST_SLC0_TOHOST_BIT1_INT_ENA1
+ 1
+ 1
+ read-write
+
+
+ HOST_SLC0_TOHOST_BIT2_INT_ENA1
+ 2
+ 1
+ read-write
+
+
+ HOST_SLC0_TOHOST_BIT3_INT_ENA1
+ 3
+ 1
+ read-write
+
+
+ HOST_SLC0_TOHOST_BIT4_INT_ENA1
+ 4
+ 1
+ read-write
+
+
+ HOST_SLC0_TOHOST_BIT5_INT_ENA1
+ 5
+ 1
+ read-write
+
+
+ HOST_SLC0_TOHOST_BIT6_INT_ENA1
+ 6
+ 1
+ read-write
+
+
+ HOST_SLC0_TOHOST_BIT7_INT_ENA1
+ 7
+ 1
+ read-write
+
+
+ HOST_SLC0_TOKEN0_1TO0_INT_ENA1
+ 8
+ 1
+ read-write
+
+
+ HOST_SLC0_TOKEN1_1TO0_INT_ENA1
+ 9
+ 1
+ read-write
+
+
+ HOST_SLC0_TOKEN0_0TO1_INT_ENA1
+ 10
+ 1
+ read-write
+
+
+ HOST_SLC0_TOKEN1_0TO1_INT_ENA1
+ 11
+ 1
+ read-write
+
+
+ HOST_SLC0HOST_RX_SOF_INT_ENA1
+ 12
+ 1
+ read-write
+
+
+ HOST_SLC0HOST_RX_EOF_INT_ENA1
+ 13
+ 1
+ read-write
+
+
+ HOST_SLC0HOST_RX_START_INT_ENA1
+ 14
+ 1
+ read-write
+
+
+ HOST_SLC0HOST_TX_START_INT_ENA1
+ 15
+ 1
+ read-write
+
+
+ HOST_SLC0_RX_UDF_INT_ENA1
+ 16
+ 1
+ read-write
+
+
+ HOST_SLC0_TX_OVF_INT_ENA1
+ 17
+ 1
+ read-write
+
+
+ HOST_SLC0_RX_PF_VALID_INT_ENA1
+ 18
+ 1
+ read-write
+
+
+ HOST_SLC0_EXT_BIT0_INT_ENA1
+ 19
+ 1
+ read-write
+
+
+ HOST_SLC0_EXT_BIT1_INT_ENA1
+ 20
+ 1
+ read-write
+
+
+ HOST_SLC0_EXT_BIT2_INT_ENA1
+ 21
+ 1
+ read-write
+
+
+ HOST_SLC0_EXT_BIT3_INT_ENA1
+ 22
+ 1
+ read-write
+
+
+ HOST_SLC0_RX_NEW_PACKET_INT_ENA1
+ 23
+ 1
+ read-write
+
+
+ HOST_SLC0_HOST_RD_RETRY_INT_ENA1
+ 24
+ 1
+ read-write
+
+
+ HOST_GPIO_SDIO_INT_ENA1
+ 25
+ 1
+ read-write
+
+
+
+
+ HOST_SLC1HOST_INT_ENA1
+ 0x118
+ 0x20
+
+
+ HOST_SLC1_TOHOST_BIT0_INT_ENA1
+ 0
+ 1
+ read-write
+
+
+ HOST_SLC1_TOHOST_BIT1_INT_ENA1
+ 1
+ 1
+ read-write
+
+
+ HOST_SLC1_TOHOST_BIT2_INT_ENA1
+ 2
+ 1
+ read-write
+
+
+ HOST_SLC1_TOHOST_BIT3_INT_ENA1
+ 3
+ 1
+ read-write
+
+
+ HOST_SLC1_TOHOST_BIT4_INT_ENA1
+ 4
+ 1
+ read-write
+
+
+ HOST_SLC1_TOHOST_BIT5_INT_ENA1
+ 5
+ 1
+ read-write
+
+
+ HOST_SLC1_TOHOST_BIT6_INT_ENA1
+ 6
+ 1
+ read-write
+
+
+ HOST_SLC1_TOHOST_BIT7_INT_ENA1
+ 7
+ 1
+ read-write
+
+
+ HOST_SLC1_TOKEN0_1TO0_INT_ENA1
+ 8
+ 1
+ read-write
+
+
+ HOST_SLC1_TOKEN1_1TO0_INT_ENA1
+ 9
+ 1
+ read-write
+
+
+ HOST_SLC1_TOKEN0_0TO1_INT_ENA1
+ 10
+ 1
+ read-write
+
+
+ HOST_SLC1_TOKEN1_0TO1_INT_ENA1
+ 11
+ 1
+ read-write
+
+
+ HOST_SLC1HOST_RX_SOF_INT_ENA1
+ 12
+ 1
+ read-write
+
+
+ HOST_SLC1HOST_RX_EOF_INT_ENA1
+ 13
+ 1
+ read-write
+
+
+ HOST_SLC1HOST_RX_START_INT_ENA1
+ 14
+ 1
+ read-write
+
+
+ HOST_SLC1HOST_TX_START_INT_ENA1
+ 15
+ 1
+ read-write
+
+
+ HOST_SLC1_RX_UDF_INT_ENA1
+ 16
+ 1
+ read-write
+
+
+ HOST_SLC1_TX_OVF_INT_ENA1
+ 17
+ 1
+ read-write
+
+
+ HOST_SLC1_RX_PF_VALID_INT_ENA1
+ 18
+ 1
+ read-write
+
+
+ HOST_SLC1_EXT_BIT0_INT_ENA1
+ 19
+ 1
+ read-write
+
+
+ HOST_SLC1_EXT_BIT1_INT_ENA1
+ 20
+ 1
+ read-write
+
+
+ HOST_SLC1_EXT_BIT2_INT_ENA1
+ 21
+ 1
+ read-write
+
+
+ HOST_SLC1_EXT_BIT3_INT_ENA1
+ 22
+ 1
+ read-write
+
+
+ HOST_SLC1_WIFI_RX_NEW_PACKET_INT_ENA1
+ 23
+ 1
+ read-write
+
+
+ HOST_SLC1_HOST_RD_RETRY_INT_ENA1
+ 24
+ 1
+ read-write
+
+
+ HOST_SLC1_BT_RX_NEW_PACKET_INT_ENA1
+ 25
+ 1
+ read-write
+
+
+
+
+ HOST_SLCHOSTDATE
+ 0x178
+ 0x20
+ 0x16022500
+
+
+ HOST_SLCHOST_DATE
+ 0
+ 32
+ read-write
+
+
+
+
+ HOST_SLCHOSTID
+ 0x17C
+ 0x20
+ 0x00000600
+
+
+ HOST_SLCHOST_ID
+ 0
+ 32
+ read-write
+
+
+
+
+ HOST_SLCHOST_CONF
+ 0x1F0
+ 0x20
+
+
+ HOST_FRC_SDIO11
+ 0
+ 5
+ read-write
+
+
+ HOST_FRC_SDIO20
+ 5
+ 5
+ read-write
+
+
+ HOST_FRC_NEG_SAMP
+ 10
+ 5
+ read-write
+
+
+ HOST_FRC_POS_SAMP
+ 15
+ 5
+ read-write
+
+
+ HOST_FRC_QUICK_IN
+ 20
+ 5
+ read-write
+
+
+ HOST_SDIO20_INT_DELAY
+ 25
+ 1
+ read-write
+
+
+ HOST_SDIO_PAD_PULLUP
+ 26
+ 1
+ read-write
+
+
+ HOST_HSPEED_CON_EN
+ 27
+ 1
+ read-write
+
+
+
+
+ HOST_SLCHOST_INF_ST
+ 0x1F4
+ 0x20
+
+
+ HOST_SDIO20_MODE
+ 0
+ 5
+ read-only
+
+
+ HOST_SDIO_NEG_SAMP
+ 5
+ 5
+ read-only
+
+
+ HOST_SDIO_QUICK_IN
+ 10
+ 5
+ read-only
+
+
+
+
+
+
+ SPI0
+ SPI (Serial Peripheral Interface) Controller
+ SPI
+ 0x3FF43000
+
+ 0x0
+ 0x110
+ registers
+
+
+ SPI0
+ 28
+
+
+
+ CMD
+ 0x0
+ 0x20
+
+
+ FLASH_PER
+ program erase resume bit program erase suspend operation will be triggered when the bit is set. The bit will be cleared once the operation done.1: enable 0: disable.
+ 16
+ 1
+ read-write
+
+
+ FLASH_PES
+ program erase suspend bit program erase suspend operation will be triggered when the bit is set. The bit will be cleared once the operation done.1: enable 0: disable.
+ 17
+ 1
+ read-write
+
+
+ USR
+ User define command enable. An operation will be triggered when the bit is set. The bit will be cleared once the operation done.1: enable 0: disable.
+ 18
+ 1
+ read-write
+
+
+ FLASH_HPM
+ Drive Flash into high performance mode. The bit will be cleared once the operation done.1: enable 0: disable.
+ 19
+ 1
+ read-write
+
+
+ FLASH_RES
+ This bit combined with reg_resandres bit releases Flash from the power-down state or high performance mode and obtains the devices ID. The bit will be cleared once the operation done.1: enable 0: disable.
+ 20
+ 1
+ read-write
+
+
+ FLASH_DP
+ Drive Flash into power down. An operation will be triggered when the bit is set. The bit will be cleared once the operation done.1: enable 0: disable.
+ 21
+ 1
+ read-write
+
+
+ FLASH_CE
+ Chip erase enable. Chip erase operation will be triggered when the bit is set. The bit will be cleared once the operation done.1: enable 0: disable.
+ 22
+ 1
+ read-write
+
+
+ FLASH_BE
+ Block erase enable. A 64KB block is erased via SPI command D8H. Block erase operation will be triggered when the bit is set. The bit will be cleared once the operation done.1: enable 0: disable.
+ 23
+ 1
+ read-write
+
+
+ FLASH_SE
+ Sector erase enable. A 4KB sector is erased via SPI command 20H. Sector erase operation will be triggered when the bit is set. The bit will be cleared once the operation done.1: enable 0: disable.
+ 24
+ 1
+ read-write
+
+
+ FLASH_PP
+ Page program enable(1 byte ~256 bytes data to be programmed). Page program operation will be triggered when the bit is set. The bit will be cleared once the operation done .1: enable 0: disable.
+ 25
+ 1
+ read-write
+
+
+ FLASH_WRSR
+ Write status register enable. Write status operation will be triggered when the bit is set. The bit will be cleared once the operation done.1: enable 0: disable.
+ 26
+ 1
+ read-write
+
+
+ FLASH_RDSR
+ Read status register-1. Read status operation will be triggered when the bit is set. The bit will be cleared once the operation done.1: enable 0: disable.
+ 27
+ 1
+ read-write
+
+
+ FLASH_RDID
+ Read JEDEC ID . Read ID command will be sent when the bit is set. The bit will be cleared once the operation done. 1: enable 0: disable.
+ 28
+ 1
+ read-write
+
+
+ FLASH_WRDI
+ Write flash disable. Write disable command will be sent when the bit is set. The bit will be cleared once the operation done. 1: enable 0: disable.
+ 29
+ 1
+ read-write
+
+
+ FLASH_WREN
+ Write flash enable. Write enable command will be sent when the bit is set. The bit will be cleared once the operation done. 1: enable 0: disable.
+ 30
+ 1
+ read-write
+
+
+ FLASH_READ
+ Read flash enable. Read flash operation will be triggered when the bit is set. The bit will be cleared once the operation done. 1: enable 0: disable.
+ 31
+ 1
+ read-write
+
+
+
+
+ ADDR
+ 0x4
+ 0x20
+
+
+ CTRL
+ 0x8
+ 0x20
+ 0x0020A400
+
+
+ FCS_CRC_EN
+ For SPI1 initialize crc32 module before writing encrypted data to flash. Active low.
+ 10
+ 1
+ read-write
+
+
+ TX_CRC_EN
+ For SPI1 enable crc32 when writing encrypted data to flash. 1: enable 0:disable
+ 11
+ 1
+ read-write
+
+
+ WAIT_FLASH_IDLE_EN
+ wait flash idle when program flash or erase flash. 1: enable 0: disable.
+ 12
+ 1
+ read-write
+
+
+ FASTRD_MODE
+ This bit enable the bits: spi_fread_qio spi_fread_dio spi_fread_qout and spi_fread_dout. 1: enable 0: disable.
+ 13
+ 1
+ read-write
+
+
+ FREAD_DUAL
+ In the read operations read-data phase apply 2 signals. 1: enable 0: disable.
+ 14
+ 1
+ read-write
+
+
+ RESANDRES
+ The Device ID is read out to SPI_RD_STATUS register, this bit combine with spi_flash_res bit. 1: enable 0: disable.
+ 15
+ 1
+ read-write
+
+
+ FREAD_QUAD
+ In the read operations read-data phase apply 4 signals. 1: enable 0: disable.
+ 20
+ 1
+ read-write
+
+
+ WP
+ Write protect signal output when SPI is idle. 1: output high 0: output low.
+ 21
+ 1
+ read-write
+
+
+ WRSR_2B
+ two bytes data will be written to status register when it is set. 1: enable 0: disable.
+ 22
+ 1
+ read-write
+
+
+ FREAD_DIO
+ In the read operations address phase and read-data phase apply 2 signals. 1: enable 0: disable.
+ 23
+ 1
+ read-write
+
+
+ FREAD_QIO
+ In the read operations address phase and read-data phase apply 4 signals. 1: enable 0: disable.
+ 24
+ 1
+ read-write
+
+
+ RD_BIT_ORDER
+ In read-data (MISO) phase 1: LSB first 0: MSB first
+ 25
+ 1
+ read-write
+
+
+ WR_BIT_ORDER
+ In command address write-data (MOSI) phases 1: LSB firs 0: MSB first
+ 26
+ 1
+ read-write
+
+
+
+
+ CTRL1
+ 0xC
+ 0x20
+ 0x5FFF0000
+
+
+ CS_HOLD_DELAY_RES
+ Delay cycles of resume Flash when resume Flash is enable by spi clock.
+ 16
+ 12
+ read-write
+
+
+ CS_HOLD_DELAY
+ SPI cs signal is delayed by spi clock cycles
+ 28
+ 4
+ read-write
+
+
+
+
+ RD_STATUS
+ 0x10
+ 0x20
+
+
+ STATUS
+ In the slave mode, it is the status for master to read out.
+ 0
+ 16
+ read-write
+
+
+ WB_MODE
+ Mode bits in the flash fast read mode, it is combined with spi_fastrd_mode bit.
+ 16
+ 8
+ read-write
+
+
+ STATUS_EXT
+ In the slave mode,it is the status for master to read out.
+ 24
+ 8
+ read-write
+
+
+
+
+ CTRL2
+ 0x14
+ 0x20
+ 0x00000011
+
+
+ SETUP_TIME
+ (cycles-1) of ¡°prepare¡± phase by spi clock, this bits combined with spi_cs_setup bit.
+ 0
+ 4
+ read-write
+
+
+ HOLD_TIME
+ delay cycles of cs pin by spi clock, this bits combined with spi_cs_hold bit.
+ 4
+ 4
+ read-write
+
+
+ CK_OUT_LOW_MODE
+ modify spi clock duty ratio when the value is lager than 8, the bits are combined with spi_clkcnt_N bits and spi_clkcnt_L bits.
+ 8
+ 4
+ read-write
+
+
+ CK_OUT_HIGH_MODE
+ modify spi clock duty ratio when the value is lager than 8, the bits are combined with spi_clkcnt_N bits and spi_clkcnt_H bits.
+ 12
+ 4
+ read-write
+
+
+ MISO_DELAY_MODE
+ MISO signals are delayed by spi_clk. 0: zero 1: if spi_ck_out_edge or spi_ck_i_edge is set 1 delayed by half cycle else delayed by one cycle 2: if spi_ck_out_edge or spi_ck_i_edge is set 1 delayed by one cycle else delayed by half cycle 3: delayed one cycle
+ 16
+ 2
+ read-write
+
+
+ MISO_DELAY_NUM
+ MISO signals are delayed by system clock cycles
+ 18
+ 3
+ read-write
+
+
+ MOSI_DELAY_MODE
+ MOSI signals are delayed by spi_clk. 0: zero 1: if spi_ck_out_edge or spi_ck_i_edge is set 1 delayed by half cycle else delayed by one cycle 2: if spi_ck_out_edge or spi_ck_i_edge is set 1 delayed by one cycle else delayed by half cycle 3: delayed one cycle
+ 21
+ 2
+ read-write
+
+
+ MOSI_DELAY_NUM
+ MOSI signals are delayed by system clock cycles
+ 23
+ 3
+ read-write
+
+
+ CS_DELAY_MODE
+ spi_cs signal is delayed by spi_clk . 0: zero 1: if spi_ck_out_edge or spi_ck_i_edge is set 1 delayed by half cycle else delayed by one cycle 2: if spi_ck_out_edge or spi_ck_i_edge is set 1 delayed by one cycle else delayed by half cycle 3: delayed one cycle
+ 26
+ 2
+ read-write
+
+
+ CS_DELAY_NUM
+ spi_cs signal is delayed by system clock cycles
+ 28
+ 4
+ read-write
+
+
+
+
+ CLOCK
+ 0x18
+ 0x20
+ 0x80003043
+
+
+ CLKCNT_L
+ In the master mode it must be equal to spi_clkcnt_N. In the slave mode it must be 0.
+ 0
+ 6
+ read-write
+
+
+ CLKCNT_H
+ In the master mode it must be floor((spi_clkcnt_N+1)/2-1). In the slave mode it must be 0.
+ 6
+ 6
+ read-write
+
+
+ CLKCNT_N
+ In the master mode it is the divider of spi_clk. So spi_clk frequency is system/(spi_clkdiv_pre+1)/(spi_clkcnt_N+1)
+ 12
+ 6
+ read-write
+
+
+ CLKDIV_PRE
+ In the master mode it is pre-divider of spi_clk.
+ 18
+ 13
+ read-write
+
+
+ CLK_EQU_SYSCLK
+ In the master mode 1: spi_clk is eqaul to system 0: spi_clk is divided from system clock.
+ 31
+ 1
+ read-write
+
+
+
+
+ USER
+ 0x1C
+ 0x20
+ 0x80000040
+
+
+ DOUTDIN
+ Set the bit to enable full duplex communication. 1: enable 0: disable.
+ 0
+ 1
+ read-write
+
+
+ CS_HOLD
+ spi cs keep low when spi is in ¡°done¡± phase. 1: enable 0: disable.
+ 4
+ 1
+ read-write
+
+
+ CS_SETUP
+ spi cs is enable when spi is in ¡°prepare¡± phase. 1: enable 0: disable.
+ 5
+ 1
+ read-write
+
+
+ CK_I_EDGE
+ In the slave mode the bit is same as spi_ck_out_edge in master mode. It is combined with spi_miso_delay_mode bits.
+ 6
+ 1
+ read-write
+
+
+ CK_OUT_EDGE
+ the bit combined with spi_mosi_delay_mode bits to set mosi signal delay mode.
+ 7
+ 1
+ read-write
+
+
+ RD_BYTE_ORDER
+ In read-data (MISO) phase 1: big-endian 0: little_endian
+ 10
+ 1
+ read-write
+
+
+ WR_BYTE_ORDER
+ In command address write-data (MOSI) phases 1: big-endian 0: litte_endian
+ 11
+ 1
+ read-write
+
+
+ FWRITE_DUAL
+ In the write operations read-data phase apply 2 signals
+ 12
+ 1
+ read-write
+
+
+ FWRITE_QUAD
+ In the write operations read-data phase apply 4 signals
+ 13
+ 1
+ read-write
+
+
+ FWRITE_DIO
+ In the write operations address phase and read-data phase apply 2 signals.
+ 14
+ 1
+ read-write
+
+
+ FWRITE_QIO
+ In the write operations address phase and read-data phase apply 4 signals.
+ 15
+ 1
+ read-write
+
+
+ SIO
+ Set the bit to enable 3-line half duplex communication mosi and miso signals share the same pin. 1: enable 0: disable.
+ 16
+ 1
+ read-write
+
+
+ USR_HOLD_POL
+ It is combined with hold bits to set the polarity of spi hold line 1: spi will be held when spi hold line is high 0: spi will be held when spi hold line is low
+ 17
+ 1
+ read-write
+
+
+ USR_DOUT_HOLD
+ spi is hold at data out state the bit combined with spi_usr_hold_pol bit.
+ 18
+ 1
+ read-write
+
+
+ USR_DIN_HOLD
+ spi is hold at data in state the bit combined with spi_usr_hold_pol bit.
+ 19
+ 1
+ read-write
+
+
+ USR_DUMMY_HOLD
+ spi is hold at dummy state the bit combined with spi_usr_hold_pol bit.
+ 20
+ 1
+ read-write
+
+
+ USR_ADDR_HOLD
+ spi is hold at address state the bit combined with spi_usr_hold_pol bit.
+ 21
+ 1
+ read-write
+
+
+ USR_CMD_HOLD
+ spi is hold at command state the bit combined with spi_usr_hold_pol bit.
+ 22
+ 1
+ read-write
+
+
+ USR_PREP_HOLD
+ spi is hold at prepare state the bit combined with spi_usr_hold_pol bit.
+ 23
+ 1
+ read-write
+
+
+ USR_MISO_HIGHPART
+ read-data phase only access to high-part of the buffer spi_w8~spi_w15. 1: enable 0: disable.
+ 24
+ 1
+ read-write
+
+
+ USR_MOSI_HIGHPART
+ write-data phase only access to high-part of the buffer spi_w8~spi_w15. 1: enable 0: disable.
+ 25
+ 1
+ read-write
+
+
+ USR_DUMMY_IDLE
+ spi clock is disable in dummy phase when the bit is enable.
+ 26
+ 1
+ read-write
+
+
+ USR_MOSI
+ This bit enable the write-data phase of an operation.
+ 27
+ 1
+ read-write
+
+
+ USR_MISO
+ This bit enable the read-data phase of an operation.
+ 28
+ 1
+ read-write
+
+
+ USR_DUMMY
+ This bit enable the dummy phase of an operation.
+ 29
+ 1
+ read-write
+
+
+ USR_ADDR
+ This bit enable the address phase of an operation.
+ 30
+ 1
+ read-write
+
+
+ USR_COMMAND
+ This bit enable the command phase of an operation.
+ 31
+ 1
+ read-write
+
+
+
+
+ USER1
+ 0x20
+ 0x20
+ 0x5C000007
+
+
+ USR_DUMMY_CYCLELEN
+ The length in spi_clk cycles of dummy phase. The register value shall be (cycle_num-1).
+ 0
+ 8
+ read-write
+
+
+ USR_ADDR_BITLEN
+ The length in bits of address phase. The register value shall be (bit_num-1).
+ 26
+ 6
+ read-only
+
+
+
+
+ USER2
+ 0x24
+ 0x20
+ 0x70000000
+
+
+ USR_COMMAND_VALUE
+ The value of command.
+ 0
+ 16
+ read-write
+
+
+ USR_COMMAND_BITLEN
+ The length in bits of command phase. The register value shall be (bit_num-1)
+ 28
+ 4
+ read-write
+
+
+
+
+ MOSI_DLEN
+ 0x28
+ 0x20
+
+
+ USR_MOSI_DBITLEN
+ The length in bits of write-data. The register value shall be (bit_num-1).
+ 0
+ 24
+ read-write
+
+
+
+
+ MISO_DLEN
+ 0x2C
+ 0x20
+
+
+ USR_MISO_DBITLEN
+ The length in bits of read-data. The register value shall be (bit_num-1).
+ 0
+ 24
+ read-write
+
+
+
+
+ SLV_WR_STATUS
+ 0x30
+ 0x20
+
+
+ SLV_WR_ST
+ In the slave mode this register are the status register for the master to write into. In the master mode this register are the higher 32bits in the 64 bits address condition.
+ 0
+ 32
+ read-write
+
+
+
+
+ PIN
+ 0x34
+ 0x20
+ 0x00000006
+
+
+ CS0_DIS
+ SPI CS0 pin enable, 1: disable CS0, 0: spi_cs0 signal is from/to CS0 pin
+ 0
+ 1
+ read-write
+
+
+ CS1_DIS
+ SPI CS1 pin enable, 1: disable CS1, 0: spi_cs1 signal is from/to CS1 pin
+ 1
+ 1
+ read-write
+
+
+ CS2_DIS
+ SPI CS2 pin enable, 1: disable CS2, 0: spi_cs2 signal is from/to CS2 pin
+ 2
+ 1
+ read-write
+
+
+ CK_DIS
+ 1: spi clk out disable 0: spi clk out enable
+ 5
+ 1
+ read-write
+
+
+ MASTER_CS_POL
+ In the master mode the bits are the polarity of spi cs line the value is equivalent to spi_cs ^ spi_master_cs_pol.
+ 6
+ 3
+ read-write
+
+
+ MASTER_CK_SEL
+ In the master mode spi cs line is enable as spi clk it is combined with spi_cs0_dis spi_cs1_dis spi_cs2_dis.
+ 11
+ 3
+ read-write
+
+
+ CK_IDLE_EDGE
+ 1: spi clk line is high when idle 0: spi clk line is low when idle
+ 29
+ 1
+ read-write
+
+
+ CS_KEEP_ACTIVE
+ spi cs line keep low when the bit is set.
+ 30
+ 1
+ read-write
+
+
+
+
+ SLAVE
+ 0x38
+ 0x20
+ 0x00000020
+
+
+ SLV_RD_BUF_DONE
+ The interrupt raw bit for the completion of read-buffer operation in the slave mode.
+ 0
+ 1
+ read-write
+
+
+ SLV_WR_BUF_DONE
+ The interrupt raw bit for the completion of write-buffer operation in the slave mode.
+ 1
+ 1
+ read-write
+
+
+ SLV_RD_STA_DONE
+ The interrupt raw bit for the completion of read-status operation in the slave mode.
+ 2
+ 1
+ read-write
+
+
+ SLV_WR_STA_DONE
+ The interrupt raw bit for the completion of write-status operation in the slave mode.
+ 3
+ 1
+ read-write
+
+
+ TRANS_DONE
+ The interrupt raw bit for the completion of any operation in both the master mode and the slave mode.
+ 4
+ 1
+ read-write
+
+
+ INT_EN
+ Interrupt enable bits for the below 5 sources
+ 5
+ 5
+ read-write
+
+
+ CS_I_MODE
+ In the slave mode this bits used to synchronize the input spi cs signal and eliminate spi cs jitter.
+ 10
+ 2
+ read-write
+
+
+ SLV_LAST_COMMAND
+ In the slave mode it is the value of command.
+ 17
+ 3
+ read-only
+
+
+ SLV_LAST_STATE
+ In the slave mode it is the state of spi state machine.
+ 20
+ 3
+ read-only
+
+
+ TRANS_CNT
+ The operations counter in both the master mode and the slave mode. 4: read-status
+ 23
+ 4
+ read-only
+
+
+ SLV_CMD_DEFINE
+ 1: slave mode commands are defined in SPI_SLAVE3. 0: slave mode commands are fixed as: 1: write-status 2: write-buffer and 3: read-buffer.
+ 27
+ 1
+ read-write
+
+
+ SLV_WR_RD_STA_EN
+ write and read status enable in the slave mode
+ 28
+ 1
+ read-write
+
+
+ SLV_WR_RD_BUF_EN
+ write and read buffer enable in the slave mode
+ 29
+ 1
+ read-write
+
+
+ MODE
+ 1: slave mode 0: master mode.
+ 30
+ 1
+ read-write
+
+
+ SYNC_RESET
+ Software reset enable, reset the spi clock line cs line and data lines.
+ 31
+ 1
+ read-write
+
+
+
+
+ SLAVE1
+ 0x3C
+ 0x20
+ 0x02000000
+
+
+ SLV_RDBUF_DUMMY_EN
+ In the slave mode it is the enable bit of dummy phase for read-buffer operations.
+ 0
+ 1
+ read-write
+
+
+ SLV_WRBUF_DUMMY_EN
+ In the slave mode it is the enable bit of dummy phase for write-buffer operations.
+ 1
+ 1
+ read-write
+
+
+ SLV_RDSTA_DUMMY_EN
+ In the slave mode it is the enable bit of dummy phase for read-status operations.
+ 2
+ 1
+ read-write
+
+
+ SLV_WRSTA_DUMMY_EN
+ In the slave mode it is the enable bit of dummy phase for write-status operations.
+ 3
+ 1
+ read-write
+
+
+ SLV_WR_ADDR_BITLEN
+ In the slave mode it is the address length in bits for write-buffer operation. The register value shall be (bit_num-1).
+ 4
+ 6
+ read-write
+
+
+ SLV_RD_ADDR_BITLEN
+ In the slave mode it is the address length in bits for read-buffer operation. The register value shall be (bit_num-1).
+ 10
+ 6
+ read-write
+
+
+ SLV_STATUS_READBACK
+ In the slave mode 1:read register of SPI_SLV_WR_STATUS 0: read register of SPI_RD_STATUS.
+ 25
+ 1
+ read-write
+
+
+ SLV_STATUS_FAST_EN
+ In the slave mode enable fast read status.
+ 26
+ 1
+ read-write
+
+
+ SLV_STATUS_BITLEN
+ In the slave mode it is the length of status bit.
+ 27
+ 5
+ read-write
+
+
+
+
+ SLAVE2
+ 0x40
+ 0x20
+
+
+ SLV_RDSTA_DUMMY_CYCLELEN
+ In the slave mode it is the length in spi_clk cycles of dummy phase for read-status operations. The register value shall be (cycle_num-1).
+ 0
+ 8
+ read-write
+
+
+ SLV_WRSTA_DUMMY_CYCLELEN
+ In the slave mode it is the length in spi_clk cycles of dummy phase for write-status operations. The register value shall be (cycle_num-1).
+ 8
+ 8
+ read-write
+
+
+ SLV_RDBUF_DUMMY_CYCLELEN
+ In the slave mode it is the length in spi_clk cycles of dummy phase for read-buffer operations. The register value shall be (cycle_num-1).
+ 16
+ 8
+ read-write
+
+
+ SLV_WRBUF_DUMMY_CYCLELEN
+ In the slave mode it is the length in spi_clk cycles of dummy phase for write-buffer operations. The register value shall be (cycle_num-1).
+ 24
+ 8
+ read-write
+
+
+
+
+ SLAVE3
+ 0x44
+ 0x20
+
+
+ SLV_RDBUF_CMD_VALUE
+ In the slave mode it is the value of read-buffer command.
+ 0
+ 8
+ read-write
+
+
+ SLV_WRBUF_CMD_VALUE
+ In the slave mode it is the value of write-buffer command.
+ 8
+ 8
+ read-write
+
+
+ SLV_RDSTA_CMD_VALUE
+ In the slave mode it is the value of read-status command.
+ 16
+ 8
+ read-write
+
+
+ SLV_WRSTA_CMD_VALUE
+ In the slave mode it is the value of write-status command.
+ 24
+ 8
+ read-write
+
+
+
+
+ SLV_WRBUF_DLEN
+ 0x48
+ 0x20
+
+
+ SLV_WRBUF_DBITLEN
+ In the slave mode it is the length in bits for write-buffer operations. The register value shall be (bit_num-1).
+ 0
+ 24
+ read-write
+
+
+
+
+ SLV_RDBUF_DLEN
+ 0x4C
+ 0x20
+
+
+ SLV_RDBUF_DBITLEN
+ In the slave mode it is the length in bits for read-buffer operations. The register value shall be (bit_num-1).
+ 0
+ 24
+ read-write
+
+
+
+
+ CACHE_FCTRL
+ 0x50
+ 0x20
+
+
+ CACHE_REQ_EN
+ For SPI0 Cache access enable 1: enable 0:disable.
+ 0
+ 1
+ read-write
+
+
+ CACHE_USR_CMD_4BYTE
+ For SPI0 cache read flash with 4 bytes command 1: enable 0:disable.
+ 1
+ 1
+ read-write
+
+
+ CACHE_FLASH_USR_CMD
+ For SPI0 cache read flash for user define command 1: enable 0:disable.
+ 2
+ 1
+ read-write
+
+
+ CACHE_FLASH_PES_EN
+ For SPI0 spi1 send suspend command before cache read flash 1: enable 0:disable.
+ 3
+ 1
+ read-write
+
+
+
+
+ CACHE_SCTRL
+ 0x54
+ 0x20
+ 0x15C04830
+
+
+ USR_SRAM_DIO
+ For SPI0 In the spi sram mode spi dual I/O mode enable 1: enable 0:disable
+ 1
+ 1
+ read-write
+
+
+ USR_SRAM_QIO
+ For SPI0 In the spi sram mode spi quad I/O mode enable 1: enable 0:disable
+ 2
+ 1
+ read-write
+
+
+ USR_WR_SRAM_DUMMY
+ For SPI0 In the spi sram mode it is the enable bit of dummy phase for write operations.
+ 3
+ 1
+ read-write
+
+
+ USR_RD_SRAM_DUMMY
+ For SPI0 In the spi sram mode it is the enable bit of dummy phase for read operations.
+ 4
+ 1
+ read-write
+
+
+ CACHE_SRAM_USR_RCMD
+ For SPI0 In the spi sram mode cache read sram for user define command.
+ 5
+ 1
+ read-write
+
+
+ SRAM_BYTES_LEN
+ For SPI0 In the sram mode it is the byte length of spi read sram data.
+ 6
+ 8
+ read-write
+
+
+ SRAM_DUMMY_CYCLELEN
+ For SPI0 In the sram mode it is the length in bits of address phase. The register value shall be (bit_num-1).
+ 14
+ 8
+ read-write
+
+
+ SRAM_ADDR_BITLEN
+ For SPI0 In the sram mode it is the length in bits of address phase. The register value shall be (bit_num-1).
+ 22
+ 6
+ read-write
+
+
+ CACHE_SRAM_USR_WCMD
+ For SPI0 In the spi sram mode cache write sram for user define command
+ 28
+ 1
+ read-write
+
+
+
+
+ SRAM_CMD
+ 0x58
+ 0x20
+
+
+ SRAM_DIO
+ For SPI0 SRAM DIO mode enable . SRAM DIO enable command will be send when the bit is set. The bit will be cleared once the operation done.
+ 0
+ 1
+ read-write
+
+
+ SRAM_QIO
+ For SPI0 SRAM QIO mode enable . SRAM QIO enable command will be send when the bit is set. The bit will be cleared once the operation done.
+ 1
+ 1
+ read-write
+
+
+ SRAM_RSTIO
+ For SPI0 SRAM IO mode reset enable. SRAM IO mode reset operation will be triggered when the bit is set. The bit will be cleared once the operation done
+ 4
+ 1
+ read-write
+
+
+
+
+ SRAM_DRD_CMD
+ 0x5C
+ 0x20
+
+
+ CACHE_SRAM_USR_RD_CMD_VALUE
+ For SPI0 When cache mode is enable it is the read command value of command phase for SRAM.
+ 0
+ 16
+ read-write
+
+
+ CACHE_SRAM_USR_RD_CMD_BITLEN
+ For SPI0 When cache mode is enable it is the length in bits of command phase for SRAM. The register value shall be (bit_num-1).
+ 28
+ 4
+ read-write
+
+
+
+
+ SRAM_DWR_CMD
+ 0x60
+ 0x20
+
+
+ CACHE_SRAM_USR_WR_CMD_VALUE
+ For SPI0 When cache mode is enable it is the write command value of command phase for SRAM.
+ 0
+ 16
+ read-write
+
+
+ CACHE_SRAM_USR_WR_CMD_BITLEN
+ For SPI0 When cache mode is enable it is the in bits of command phase for SRAM. The register value shall be (bit_num-1).
+ 28
+ 4
+ read-write
+
+
+
+
+ SLV_RD_BIT
+ 0x64
+ 0x20
+
+
+ SLV_RDATA_BIT
+ In the slave mode it is the bit length of read data. The value is the length - 1.
+ 0
+ 24
+ read-write
+
+
+
+
+ W0
+ 0x80
+ 0x20
+
+
+ BUF0
+ data buffer
+ 0
+ 32
+ read-write
+
+
+
+
+ W1
+ 0x84
+ 0x20
+
+
+ BUF1
+ data buffer
+ 0
+ 32
+ read-write
+
+
+
+
+ W2
+ 0x88
+ 0x20
+
+
+ BUF2
+ data buffer
+ 0
+ 32
+ read-write
+
+
+
+
+ W3
+ 0x8C
+ 0x20
+
+
+ BUF3
+ data buffer
+ 0
+ 32
+ read-write
+
+
+
+
+ W4
+ 0x90
+ 0x20
+
+
+ BUF4
+ data buffer
+ 0
+ 32
+ read-write
+
+
+
+
+ W5
+ 0x94
+ 0x20
+
+
+ BUF5
+ data buffer
+ 0
+ 32
+ read-write
+
+
+
+
+ W6
+ 0x98
+ 0x20
+
+
+ BUF6
+ data buffer
+ 0
+ 32
+ read-write
+
+
+
+
+ W7
+ 0x9C
+ 0x20
+
+
+ BUF7
+ data buffer
+ 0
+ 32
+ read-write
+
+
+
+
+ W8
+ 0xA0
+ 0x20
+
+
+ BUF8
+ data buffer
+ 0
+ 32
+ read-write
+
+
+
+
+ W9
+ 0xA4
+ 0x20
+
+
+ BUF9
+ data buffer
+ 0
+ 32
+ read-write
+
+
+
+
+ W10
+ 0xA8
+ 0x20
+
+
+ BUF10
+ data buffer
+ 0
+ 32
+ read-write
+
+
+
+
+ W11
+ 0xAC
+ 0x20
+
+
+ BUF11
+ data buffer
+ 0
+ 32
+ read-write
+
+
+
+
+ W12
+ 0xB0
+ 0x20
+
+
+ BUF12
+ data buffer
+ 0
+ 32
+ read-write
+
+
+
+
+ W13
+ 0xB4
+ 0x20
+
+
+ BUF13
+ data buffer
+ 0
+ 32
+ read-write
+
+
+
+
+ W14
+ 0xB8
+ 0x20
+
+
+ BUF14
+ data buffer
+ 0
+ 32
+ read-write
+
+
+
+
+ W15
+ 0xBC
+ 0x20
+
+
+ BUF15
+ data buffer
+ 0
+ 32
+ read-write
+
+
+
+
+ TX_CRC
+ 0xC0
+ 0x20
+
+
+ DATA
+ For SPI1 the value of crc32 for 256 bits data.
+ 0
+ 32
+ read-write
+
+
+
+
+ EXT0
+ 0xF0
+ 0x20
+ 0x800A0050
+
+
+ T_PP_TIME
+ page program delay time by system clock.
+ 0
+ 12
+ read-write
+
+
+ T_PP_SHIFT
+ page program delay time shift .
+ 16
+ 4
+ read-write
+
+
+ T_PP_ENA
+ page program delay enable.
+ 31
+ 1
+ read-write
+
+
+
+
+ EXT1
+ 0xF4
+ 0x20
+ 0x800F0000
+
+
+ T_ERASE_TIME
+ erase flash delay time by system clock.
+ 0
+ 12
+ read-write
+
+
+ T_ERASE_SHIFT
+ erase flash delay time shift.
+ 16
+ 4
+ read-write
+
+
+ T_ERASE_ENA
+ erase flash delay enable.
+ 31
+ 1
+ read-write
+
+
+
+
+ EXT2
+ 0xF8
+ 0x20
+
+
+ ST
+ The status of spi state machine .
+ 0
+ 3
+ read-only
+
+
+
+
+ EXT3
+ 0xFC
+ 0x20
+
+
+ INT_HOLD_ENA
+ This register is for two SPI masters to share the same cs clock and data signals. The bits of one SPI are set if the other SPI is busy the SPI will be hold. 1(3): hold at ¡°idle¡± phase 2: hold at ¡°prepare¡± phase.
+ 0
+ 2
+ read-write
+
+
+
+
+ DMA_CONF
+ 0x100
+ 0x20
+ 0x00000200
+
+
+ IN_RST
+ The bit is used to reset in dma fsm and in data fifo pointer.
+ 2
+ 1
+ read-write
+
+
+ OUT_RST
+ The bit is used to reset out dma fsm and out data fifo pointer.
+ 3
+ 1
+ read-write
+
+
+ AHBM_FIFO_RST
+ reset spi dma ahb master fifo pointer.
+ 4
+ 1
+ read-write
+
+
+ AHBM_RST
+ reset spi dma ahb master.
+ 5
+ 1
+ read-write
+
+
+ IN_LOOP_TEST
+ Set bit to test in link.
+ 6
+ 1
+ read-write
+
+
+ OUT_LOOP_TEST
+ Set bit to test out link.
+ 7
+ 1
+ read-write
+
+
+ OUT_AUTO_WRBACK
+ when the link is empty jump to next automatically.
+ 8
+ 1
+ read-write
+
+
+ OUT_EOF_MODE
+ out eof flag generation mode . 1: when dma pop all data from fifo 0:when ahb push all data to fifo.
+ 9
+ 1
+ read-write
+
+
+ OUTDSCR_BURST_EN
+ read descriptor use burst mode when read data for memory.
+ 10
+ 1
+ read-write
+
+
+ INDSCR_BURST_EN
+ read descriptor use burst mode when write data to memory.
+ 11
+ 1
+ read-write
+
+
+ OUT_DATA_BURST_EN
+ spi dma read data from memory in burst mode.
+ 12
+ 1
+ read-write
+
+
+ DMA_RX_STOP
+ spi dma read data stop when in continue tx/rx mode.
+ 14
+ 1
+ read-write
+
+
+ DMA_TX_STOP
+ spi dma write data stop when in continue tx/rx mode.
+ 15
+ 1
+ read-write
+
+
+ DMA_CONTINUE
+ spi dma continue tx/rx data.
+ 16
+ 1
+ read-write
+
+
+
+
+ DMA_OUT_LINK
+ 0x104
+ 0x20
+
+
+ OUTLINK_ADDR
+ The address of the first outlink descriptor.
+ 0
+ 20
+ read-write
+
+
+ OUTLINK_STOP
+ Set the bit to stop to use outlink descriptor.
+ 28
+ 1
+ read-write
+
+
+ OUTLINK_START
+ Set the bit to start to use outlink descriptor.
+ 29
+ 1
+ read-write
+
+
+ OUTLINK_RESTART
+ Set the bit to mount on new outlink descriptors.
+ 30
+ 1
+ read-write
+
+
+
+
+ DMA_IN_LINK
+ 0x108
+ 0x20
+
+
+ INLINK_ADDR
+ The address of the first inlink descriptor.
+ 0
+ 20
+ read-write
+
+
+ INLINK_AUTO_RET
+ when the bit is set inlink descriptor returns to the next descriptor while a packet is wrong
+ 20
+ 1
+ read-write
+
+
+ INLINK_STOP
+ Set the bit to stop to use inlink descriptor.
+ 28
+ 1
+ read-write
+
+
+ INLINK_START
+ Set the bit to start to use inlink descriptor.
+ 29
+ 1
+ read-write
+
+
+ INLINK_RESTART
+ Set the bit to mount on new inlink descriptors.
+ 30
+ 1
+ read-write
+
+
+
+
+ DMA_STATUS
+ 0x10C
+ 0x20
+
+
+ DMA_RX_EN
+ spi dma read data status bit.
+ 0
+ 1
+ read-only
+
+
+ DMA_TX_EN
+ spi dma write data status bit.
+ 1
+ 1
+ read-only
+
+
+
+
+ DMA_INT_ENA
+ 0x110
+ 0x20
+
+
+ INLINK_DSCR_EMPTY_INT_ENA
+ The enable bit for lack of enough inlink descriptors.
+ 0
+ 1
+ read-write
+
+
+ OUTLINK_DSCR_ERROR_INT_ENA
+ The enable bit for outlink descriptor error.
+ 1
+ 1
+ read-write
+
+
+ INLINK_DSCR_ERROR_INT_ENA
+ The enable bit for inlink descriptor error.
+ 2
+ 1
+ read-write
+
+
+ IN_DONE_INT_ENA
+ The enable bit for completing usage of a inlink descriptor.
+ 3
+ 1
+ read-write
+
+
+ IN_ERR_EOF_INT_ENA
+ The enable bit for receiving error.
+ 4
+ 1
+ read-write
+
+
+ IN_SUC_EOF_INT_ENA
+ The enable bit for completing receiving all the packets from host.
+ 5
+ 1
+ read-write
+
+
+ OUT_DONE_INT_ENA
+ The enable bit for completing usage of a outlink descriptor .
+ 6
+ 1
+ read-write
+
+
+ OUT_EOF_INT_ENA
+ The enable bit for sending a packet to host done.
+ 7
+ 1
+ read-write
+
+
+ OUT_TOTAL_EOF_INT_ENA
+ The enable bit for sending all the packets to host done.
+ 8
+ 1
+ read-write
+
+
+
+
+ DMA_INT_RAW
+ 0x114
+ 0x20
+
+
+ INLINK_DSCR_EMPTY_INT_RAW
+ The raw bit for lack of enough inlink descriptors.
+ 0
+ 1
+ read-only
+
+
+ OUTLINK_DSCR_ERROR_INT_RAW
+ The raw bit for outlink descriptor error.
+ 1
+ 1
+ read-only
+
+
+ INLINK_DSCR_ERROR_INT_RAW
+ The raw bit for inlink descriptor error.
+ 2
+ 1
+ read-only
+
+
+ IN_DONE_INT_RAW
+ The raw bit for completing usage of a inlink descriptor.
+ 3
+ 1
+ read-only
+
+
+ IN_ERR_EOF_INT_RAW
+ The raw bit for receiving error.
+ 4
+ 1
+ read-only
+
+
+ IN_SUC_EOF_INT_RAW
+ The raw bit for completing receiving all the packets from host.
+ 5
+ 1
+ read-only
+
+
+ OUT_DONE_INT_RAW
+ The raw bit for completing usage of a outlink descriptor.
+ 6
+ 1
+ read-only
+
+
+ OUT_EOF_INT_RAW
+ The raw bit for sending a packet to host done.
+ 7
+ 1
+ read-only
+
+
+ OUT_TOTAL_EOF_INT_RAW
+ The raw bit for sending all the packets to host done.
+ 8
+ 1
+ read-only
+
+
+
+
+ DMA_INT_ST
+ 0x118
+ 0x20
+
+
+ INLINK_DSCR_EMPTY_INT_ST
+ The status bit for lack of enough inlink descriptors.
+ 0
+ 1
+ read-only
+
+
+ OUTLINK_DSCR_ERROR_INT_ST
+ The status bit for outlink descriptor error.
+ 1
+ 1
+ read-only
+
+
+ INLINK_DSCR_ERROR_INT_ST
+ The status bit for inlink descriptor error.
+ 2
+ 1
+ read-only
+
+
+ IN_DONE_INT_ST
+ The status bit for completing usage of a inlink descriptor.
+ 3
+ 1
+ read-only
+
+
+ IN_ERR_EOF_INT_ST
+ The status bit for receiving error.
+ 4
+ 1
+ read-only
+
+
+ IN_SUC_EOF_INT_ST
+ The status bit for completing receiving all the packets from host.
+ 5
+ 1
+ read-only
+
+
+ OUT_DONE_INT_ST
+ The status bit for completing usage of a outlink descriptor.
+ 6
+ 1
+ read-only
+
+
+ OUT_EOF_INT_ST
+ The status bit for sending a packet to host done.
+ 7
+ 1
+ read-only
+
+
+ OUT_TOTAL_EOF_INT_ST
+ The status bit for sending all the packets to host done.
+ 8
+ 1
+ read-only
+
+
+
+
+ DMA_INT_CLR
+ 0x11C
+ 0x20
+
+
+ INLINK_DSCR_EMPTY_INT_CLR
+ The clear bit for lack of enough inlink descriptors.
+ 0
+ 1
+ read-write
+
+
+ OUTLINK_DSCR_ERROR_INT_CLR
+ The clear bit for outlink descriptor error.
+ 1
+ 1
+ read-write
+
+
+ INLINK_DSCR_ERROR_INT_CLR
+ The clear bit for inlink descriptor error.
+ 2
+ 1
+ read-write
+
+
+ IN_DONE_INT_CLR
+ The clear bit for completing usage of a inlink descriptor.
+ 3
+ 1
+ read-write
+
+
+ IN_ERR_EOF_INT_CLR
+ The clear bit for receiving error.
+ 4
+ 1
+ read-write
+
+
+ IN_SUC_EOF_INT_CLR
+ The clear bit for completing receiving all the packets from host.
+ 5
+ 1
+ read-write
+
+
+ OUT_DONE_INT_CLR
+ The clear bit for completing usage of a outlink descriptor.
+ 6
+ 1
+ read-write
+
+
+ OUT_EOF_INT_CLR
+ The clear bit for sending a packet to host done.
+ 7
+ 1
+ read-write
+
+
+ OUT_TOTAL_EOF_INT_CLR
+ The clear bit for sending all the packets to host done.
+ 8
+ 1
+ read-write
+
+
+
+
+ IN_ERR_EOF_DES_ADDR
+ 0x120
+ 0x20
+
+
+ DMA_IN_ERR_EOF_DES_ADDR
+ The inlink descriptor address when spi dma produce receiving error.
+ 0
+ 32
+ read-only
+
+
+
+
+ IN_SUC_EOF_DES_ADDR
+ 0x124
+ 0x20
+
+
+ DMA_IN_SUC_EOF_DES_ADDR
+ The last inlink descriptor address when spi dma produce from_suc_eof.
+ 0
+ 32
+ read-only
+
+
+
+
+ INLINK_DSCR
+ 0x128
+ 0x20
+
+
+ DMA_INLINK_DSCR
+ The content of current in descriptor pointer.
+ 0
+ 32
+ read-only
+
+
+
+
+ INLINK_DSCR_BF0
+ 0x12C
+ 0x20
+
+
+ DMA_INLINK_DSCR_BF0
+ The content of next in descriptor pointer.
+ 0
+ 32
+ read-only
+
+
+
+
+ INLINK_DSCR_BF1
+ 0x130
+ 0x20
+
+
+ DMA_INLINK_DSCR_BF1
+ The content of current in descriptor data buffer pointer.
+ 0
+ 32
+ read-only
+
+
+
+
+ OUT_EOF_BFR_DES_ADDR
+ 0x134
+ 0x20
+
+
+ DMA_OUT_EOF_BFR_DES_ADDR
+ The address of buffer relative to the outlink descriptor that produce eof.
+ 0
+ 32
+ read-only
+
+
+
+
+ OUT_EOF_DES_ADDR
+ 0x138
+ 0x20
+
+
+ DMA_OUT_EOF_DES_ADDR
+ The last outlink descriptor address when spi dma produce to_eof.
+ 0
+ 32
+ read-only
+
+
+
+
+ OUTLINK_DSCR
+ 0x13C
+ 0x20
+
+
+ DMA_OUTLINK_DSCR
+ The content of current out descriptor pointer.
+ 0
+ 32
+ read-only
+
+
+
+
+ OUTLINK_DSCR_BF0
+ 0x140
+ 0x20
+
+
+ DMA_OUTLINK_DSCR_BF0
+ The content of next out descriptor pointer.
+ 0
+ 32
+ read-only
+
+
+
+
+ OUTLINK_DSCR_BF1
+ 0x144
+ 0x20
+
+
+ DMA_OUTLINK_DSCR_BF1
+ The content of current out descriptor data buffer pointer.
+ 0
+ 32
+ read-only
+
+
+
+
+ DMA_RSTATUS
+ 0x148
+ 0x20
+
+
+ DMA_OUT_STATUS
+ spi dma read data from memory status.
+ 0
+ 32
+ read-only
+
+
+
+
+ DMA_TSTATUS
+ 0x14C
+ 0x20
+
+
+ DMA_IN_STATUS
+ spi dma write data to memory status.
+ 0
+ 32
+ read-only
+
+
+
+
+ DATE
+ 0x3FC
+ 0x20
+ 0x01604270
+
+
+ DATE
+ SPI register version.
+ 0
+ 28
+ read-only
+
+
+
+
+
+
+ SPI1
+ SPI (Serial Peripheral Interface) Controller
+ 0x3FF42000
+
+ SPI1
+ 29
+
+
+ SPI1_DMA
+ 52
+
+
+
+ SPI2
+ SPI (Serial Peripheral Interface) Controller
+ 0x3FF64000
+
+ SPI2
+ 30
+
+
+ SPI2_DMA
+ 53
+
+
+
+ SPI3
+ SPI (Serial Peripheral Interface) Controller
+ 0x3FF65000
+
+ SPI3
+ 31
+
+
+ SPI3_DMA
+ 54
+
+
+
+ TIMG0
+ Timer Group
+ TIMG
+ 0x3FF5F000
+
+ 0x0
+ 0xB0
+ registers
+
+
+ TG0_T0_LEVEL
+ 14
+
+
+ TG0_T1_LEVEL
+ 15
+
+
+ TG0_WDT_LEVEL
+ 16
+
+
+ TG0_LACT_LEVEL
+ 17
+
+
+ TG0_T0_EDGE
+ 58
+
+
+ TG0_T1_EDGE
+ 59
+
+
+ TG0_WDT_EDGE
+ 60
+
+
+ TG0_LACT_EDGE
+ 61
+
+
+
+ T0CONFIG
+ 0x0
+ 0x20
+ 0x60002000
+
+
+ ALARM_EN
+ When set alarm is enabled
+ 10
+ 1
+ read-write
+
+
+ LEVEL_INT_EN
+ When set level type interrupt will be generated during alarm
+ 11
+ 1
+ read-write
+
+
+ EDGE_INT_EN
+ When set edge type interrupt will be generated during alarm
+ 12
+ 1
+ read-write
+
+
+ DIVIDER
+ Timer 0 clock (T0_clk) prescale value.
+ 13
+ 16
+ read-write
+
+
+ AUTORELOAD
+ When set timer 0 auto-reload at alarming is enabled
+ 29
+ 1
+ read-write
+
+
+ INCREASE
+ When set timer 0 time-base counter increment. When cleared timer 0 time-base counter decrement.
+ 30
+ 1
+ read-write
+
+
+ EN
+ When set timer 0 time-base counter is enabled
+ 31
+ 1
+ read-write
+
+
+
+
+ T0LO
+ 0x4
+ 0x20
+
+
+ LO
+ Register to store timer 0 time-base counter current value lower 32 bits.
+ 0
+ 32
+ read-only
+
+
+
+
+ T0HI
+ 0x8
+ 0x20
+
+
+ HI
+ Register to store timer 0 time-base counter current value higher 32 bits.
+ 0
+ 32
+ read-only
+
+
+
+
+ T0UPDATE
+ 0xC
+ 0x20
+
+
+ UPDATE
+ Write any value will trigger a timer 0 time-base counter value update (timer 0 current value will be stored in registers above)
+ 0
+ 32
+ write-only
+
+
+
+
+ T0ALARMLO
+ 0x10
+ 0x20
+
+
+ ALARM_LO
+ Timer 0 time-base counter value lower 32 bits that will trigger the alarm
+ 0
+ 32
+ read-write
+
+
+
+
+ T0ALARMHI
+ 0x14
+ 0x20
+
+
+ ALARM_HI
+ Timer 0 time-base counter value higher 32 bits that will trigger the alarm
+ 0
+ 32
+ read-write
+
+
+
+
+ T0LOADLO
+ 0x18
+ 0x20
+
+
+ LOAD_LO
+ Lower 32 bits of the value that will load into timer 0 time-base counter
+ 0
+ 32
+ read-write
+
+
+
+
+ T0LOADHI
+ 0x1C
+ 0x20
+
+
+ LOAD_HI
+ higher 32 bits of the value that will load into timer 0 time-base counter
+ 0
+ 32
+ read-write
+
+
+
+
+ T0LOAD
+ 0x20
+ 0x20
+
+
+ LOAD
+ Write any value will trigger timer 0 time-base counter reload
+ 0
+ 32
+ write-only
+
+
+
+
+ T1CONFIG
+ 0x24
+ 0x20
+ 0x60002000
+
+
+ ALARM_EN
+ When set alarm is enabled
+ 10
+ 1
+ read-write
+
+
+ LEVEL_INT_EN
+ When set level type interrupt will be generated during alarm
+ 11
+ 1
+ read-write
+
+
+ EDGE_INT_EN
+ When set edge type interrupt will be generated during alarm
+ 12
+ 1
+ read-write
+
+
+ DIVIDER
+ Timer 1 clock (T1_clk) prescale value.
+ 13
+ 16
+ read-write
+
+
+ AUTORELOAD
+ When set timer 1 auto-reload at alarming is enabled
+ 29
+ 1
+ read-write
+
+
+ INCREASE
+ When set timer 1 time-base counter increment. When cleared timer 1 time-base counter decrement.
+ 30
+ 1
+ read-write
+
+
+ EN
+ When set timer 1 time-base counter is enabled
+ 31
+ 1
+ read-write
+
+
+
+
+ T1LO
+ 0x28
+ 0x20
+
+
+ LO
+ Register to store timer 1 time-base counter current value lower 32 bits.
+ 0
+ 32
+ read-only
+
+
+
+
+ T1HI
+ 0x2C
+ 0x20
+
+
+ HI
+ Register to store timer 1 time-base counter current value higher 32 bits.
+ 0
+ 32
+ read-only
+
+
+
+
+ T1UPDATE
+ 0x30
+ 0x20
+
+
+ UPDATE
+ Write any value will trigger a timer 1 time-base counter value update (timer 1 current value will be stored in registers above)
+ 0
+ 32
+ write-only
+
+
+
+
+ T1ALARMLO
+ 0x34
+ 0x20
+
+
+ ALARM_LO
+ Timer 1 time-base counter value lower 32 bits that will trigger the alarm
+ 0
+ 32
+ read-write
+
+
+
+
+ T1ALARMHI
+ 0x38
+ 0x20
+
+
+ ALARM_HI
+ Timer 1 time-base counter value higher 32 bits that will trigger the alarm
+ 0
+ 32
+ read-write
+
+
+
+
+ T1LOADLO
+ 0x3C
+ 0x20
+
+
+ LOAD_LO
+ Lower 32 bits of the value that will load into timer 1 time-base counter
+ 0
+ 32
+ read-write
+
+
+
+
+ T1LOADHI
+ 0x40
+ 0x20
+
+
+ LOAD_HI
+ higher 32 bits of the value that will load into timer 1 time-base counter
+ 0
+ 32
+ read-write
+
+
+
+
+ T1LOAD
+ 0x44
+ 0x20
+
+
+ LOAD
+ Write any value will trigger timer 1 time-base counter reload
+ 0
+ 32
+ write-only
+
+
+
+
+ WDTCONFIG0
+ 0x48
+ 0x20
+ 0x0004C000
+
+
+ WDT_FLASHBOOT_MOD_EN
+ When set flash boot protection is enabled
+ 14
+ 1
+ read-write
+
+
+ WDT_SYS_RESET_LENGTH
+ length of system reset selection. 0: 100ns 1: 200ns 2: 300ns 3: 400ns 4: 500ns 5: 800ns 6: 1.6us 7: 3.2us
+ 15
+ 3
+ read-write
+
+ WDT_SYS_RESET_LENGTH
+ read-write
+
+ NS100
+ 100ns
+ 0
+
+
+ NS200
+ 200ns
+ 1
+
+
+ NS300
+ 300ns
+ 2
+
+
+ NS400
+ 400ns
+ 3
+
+
+ NS500
+ 500ns
+ 4
+
+
+ NS800
+ 800ns
+ 5
+
+
+ NS1600
+ 1.6us
+ 6
+
+
+ NS3200
+ 3.2us
+ 7
+
+
+
+
+ WDT_CPU_RESET_LENGTH
+ length of CPU reset selection. 0: 100ns 1: 200ns 2: 300ns 3: 400ns 4: 500ns 5: 800ns 6: 1.6us 7: 3.2us
+ 18
+ 3
+ read-write
+
+ WDT_CPU_RESET_LENGTH
+ read-write
+
+ NS100
+ 100ns
+ 0
+
+
+ NS200
+ 200ns
+ 1
+
+
+ NS300
+ 300ns
+ 2
+
+
+ NS400
+ 400ns
+ 3
+
+
+ NS500
+ 500ns
+ 4
+
+
+ NS800
+ 800ns
+ 5
+
+
+ NS1600
+ 1.6us
+ 6
+
+
+ NS3200
+ 3.2us
+ 7
+
+
+
+
+ WDT_LEVEL_INT_EN
+ When set level type interrupt generation is enabled
+ 21
+ 1
+ read-write
+
+
+ WDT_EDGE_INT_EN
+ When set edge type interrupt generation is enabled
+ 22
+ 1
+ read-write
+
+
+ WDT_STG3
+ Stage 3 configuration. 0: off 1: interrupt 2: reset CPU 3: reset system
+ 23
+ 2
+ read-write
+
+ WDT_STG3
+ read-write
+
+ OFF
+ Off
+ 0
+
+
+ INTERRUPT
+ Interrupt
+ 1
+
+
+ RESET
+ Reset CPU
+ 2
+
+
+ RESET_SYS
+ Reset system
+ 3
+
+
+
+
+ WDT_STG2
+ Stage 2 configuration. 0: off 1: interrupt 2: reset CPU 3: reset system
+ 25
+ 2
+ read-write
+
+
+
+ WDT_STG1
+ Stage 1 configuration. 0: off 1: interrupt 2: reset CPU 3: reset system
+ 27
+ 2
+ read-write
+
+
+
+ WDT_STG0
+ Stage 0 configuration. 0: off 1: interrupt 2: reset CPU 3: reset system
+ 29
+ 2
+ read-write
+
+
+
+ WDT_EN
+ When set SWDT is enabled
+ 31
+ 1
+ read-write
+
+
+
+
+ WDTCONFIG1
+ 0x4C
+ 0x20
+ 0x00010000
+
+
+ WDT_CLK_PRESCALE
+ SWDT clock prescale value. Period = 12.5ns * value stored in this register
+ 16
+ 16
+ read-write
+
+
+
+
+ WDTCONFIG2
+ 0x50
+ 0x20
+ 0x018CBA80
+
+
+ WDT_STG0_HOLD
+ Stage 0 timeout value in SWDT clock cycles
+ 0
+ 32
+ read-write
+
+
+
+
+ WDTCONFIG3
+ 0x54
+ 0x20
+ 0x07FFFFFF
+
+
+ WDT_STG1_HOLD
+ Stage 1 timeout value in SWDT clock cycles
+ 0
+ 32
+ read-write
+
+
+
+
+ WDTCONFIG4
+ 0x58
+ 0x20
+ 0x000FFFFF
+
+
+ WDT_STG2_HOLD
+ Stage 2 timeout value in SWDT clock cycles
+ 0
+ 32
+ read-write
+
+
+
+
+ WDTCONFIG5
+ 0x5C
+ 0x20
+ 0x000FFFFF
+
+
+ WDT_STG3_HOLD
+ Stage 3 timeout value in SWDT clock cycles
+ 0
+ 32
+ read-write
+
+
+
+
+ WDTFEED
+ 0x60
+ 0x20
+
+
+ WDT_FEED
+ Write any value will feed SWDT
+ 0
+ 32
+ write-only
+
+
+
+
+ WDTWPROTECT
+ 0x64
+ 0x20
+ 0x50D83AA1
+
+
+ WDT_WKEY
+ If change its value from default then write protection is on.
+ 0
+ 32
+ read-write
+
+
+
+
+ RTCCALICFG
+ 0x68
+ 0x20
+ 0x00013000
+
+
+ RTC_CALI_START_CYCLING
+ 12
+ 1
+ read-write
+
+
+ RTC_CALI_CLK_SEL
+ 13
+ 2
+ read-write
+
+
+ RTC_CALI_RDY
+ 15
+ 1
+ read-only
+
+
+ RTC_CALI_MAX
+ 16
+ 15
+ read-write
+
+
+ RTC_CALI_START
+ 31
+ 1
+ read-write
+
+
+
+
+ RTCCALICFG1
+ 0x6C
+ 0x20
+
+
+ RTC_CALI_VALUE
+ 7
+ 25
+ read-only
+
+
+
+
+ LACTCONFIG
+ 0x70
+ 0x20
+ 0x60002300
+
+
+ LACT_RTC_ONLY
+ 7
+ 1
+ read-write
+
+
+ LACT_CPST_EN
+ 8
+ 1
+ read-write
+
+
+ LACT_LAC_EN
+ 9
+ 1
+ read-write
+
+
+ LACT_ALARM_EN
+ 10
+ 1
+ read-write
+
+
+ LACT_LEVEL_INT_EN
+ 11
+ 1
+ read-write
+
+
+ LACT_EDGE_INT_EN
+ 12
+ 1
+ read-write
+
+
+ LACT_DIVIDER
+ 13
+ 16
+ read-write
+
+
+ LACT_AUTORELOAD
+ 29
+ 1
+ read-write
+
+
+ LACT_INCREASE
+ 30
+ 1
+ read-write
+
+
+ LACT_EN
+ 31
+ 1
+ read-write
+
+
+
+
+ LACTRTC
+ 0x74
+ 0x20
+
+
+ LACT_RTC_STEP_LEN
+ 6
+ 26
+ read-write
+
+
+
+
+ LACTLO
+ 0x78
+ 0x20
+
+
+ LACT_LO
+ 0
+ 32
+ read-only
+
+
+
+
+ LACTHI
+ 0x7C
+ 0x20
+
+
+ LACT_HI
+ 0
+ 32
+ read-only
+
+
+
+
+ LACTUPDATE
+ 0x80
+ 0x20
+
+
+ LACT_UPDATE
+ 0
+ 32
+ write-only
+
+
+
+
+ LACTALARMLO
+ 0x84
+ 0x20
+
+
+ LACT_ALARM_LO
+ 0
+ 32
+ read-write
+
+
+
+
+ LACTALARMHI
+ 0x88
+ 0x20
+
+
+ LACT_ALARM_HI
+ 0
+ 32
+ read-write
+
+
+
+
+ LACTLOADLO
+ 0x8C
+ 0x20
+
+
+ LACT_LOAD_LO
+ 0
+ 32
+ read-write
+
+
+
+
+ LACTLOADHI
+ 0x90
+ 0x20
+
+
+ LACT_LOAD_HI
+ 0
+ 32
+ read-write
+
+
+
+
+ LACTLOAD
+ 0x94
+ 0x20
+
+
+ LACT_LOAD
+ 0
+ 32
+ write-only
+
+
+
+
+ INT_ENA_TIMERS
+ 0x98
+ 0x20
+
+
+ T0_INT_ENA
+ interrupt when timer0 alarm
+ 0
+ 1
+ read-write
+
+
+ T1_INT_ENA
+ interrupt when timer1 alarm
+ 1
+ 1
+ read-write
+
+
+ WDT_INT_ENA
+ Interrupt when an interrupt stage timeout
+ 2
+ 1
+ read-write
+
+
+ LACT_INT_ENA
+ 3
+ 1
+ read-write
+
+
+
+
+ INT_RAW_TIMERS
+ 0x9C
+ 0x20
+
+
+ T0_INT_RAW
+ interrupt when timer0 alarm
+ 0
+ 1
+ read-only
+
+
+ T1_INT_RAW
+ interrupt when timer1 alarm
+ 1
+ 1
+ read-only
+
+
+ WDT_INT_RAW
+ Interrupt when an interrupt stage timeout
+ 2
+ 1
+ read-only
+
+
+ LACT_INT_RAW
+ 3
+ 1
+ read-only
+
+
+
+
+ INT_ST_TIMERS
+ 0xA0
+ 0x20
+
+
+ T0_INT_ST
+ interrupt when timer0 alarm
+ 0
+ 1
+ read-only
+
+
+ T1_INT_ST
+ interrupt when timer1 alarm
+ 1
+ 1
+ read-only
+
+
+ WDT_INT_ST
+ Interrupt when an interrupt stage timeout
+ 2
+ 1
+ read-only
+
+
+ LACT_INT_ST
+ 3
+ 1
+ read-only
+
+
+
+
+ INT_CLR_TIMERS
+ 0xA4
+ 0x20
+
+
+ T0_INT_CLR
+ interrupt when timer0 alarm
+ 0
+ 1
+ write-only
+
+
+ T1_INT_CLR
+ interrupt when timer1 alarm
+ 1
+ 1
+ write-only
+
+
+ WDT_INT_CLR
+ Interrupt when an interrupt stage timeout
+ 2
+ 1
+ write-only
+
+
+ LACT_INT_CLR
+ 3
+ 1
+ write-only
+
+
+
+
+ NTIMERS_DATE
+ 0xF8
+ 0x20
+ 0x01604290
+
+
+ NTIMERS_DATE
+ Version of this regfile
+ 0
+ 28
+ read-write
+
+
+
+
+ TIMGCLK
+ 0xFC
+ 0x20
+
+
+ CLK_EN
+ Force clock enable for this regfile
+ 31
+ 1
+ read-write
+
+
+
+
+
+
+ TIMG1
+ Timer Group
+ 0x3FF60000
+
+ TG1_T0_LEVEL
+ 18
+
+
+ TG1_T1_LEVEL
+ 19
+
+
+ TG1_WDT_LEVEL
+ 20
+
+
+ TG1_LACT_LEVEL
+ 21
+
+
+ TG1_T0_EDGE
+ 62
+
+
+ TG1_T1_EDGE
+ 63
+
+
+ TG1_WDT_EDGE
+ 64
+
+
+ TG1_LACT_EDGE
+ 65
+
+
+
+ TWAI
+ Two-Wire Automotive Interface
+ TWAI
+ 0x3FF6B000
+
+ 0x0
+ 0x6C
+ registers
+
+
+ TWAI
+ 45
+
+
+
+ MODE
+ Mode Register
+ 0x0
+ 0x20
+ 0x00000001
+
+
+ RESET_MODE
+ This bit is used to configure the operating mode of the TWAI Controller. 1: Reset mode; 0: Operating mode.
+ 0
+ 1
+ read-write
+
+
+ LISTEN_ONLY_MODE
+ 1: Listen only mode. In this mode the nodes will only receive messages from the bus, without generating the acknowledge signal nor updating the RX error counter.
+ 1
+ 1
+ read-write
+
+
+ SELF_TEST_MODE
+ 1: Self test mode. In this mode the TX nodes can perform a successful transmission without receiving the acknowledge signal. This mode is often used to test a single node with the self reception request command.
+ 2
+ 1
+ read-write
+
+
+ RX_FILTER_MODE
+ This bit is used to configure the filter mode. 0: Dual filter mode; 1: Single filter mode.
+ 3
+ 1
+ read-write
+
+
+
+
+ CMD
+ Command Register
+ 0x4
+ 0x20
+
+
+ TX_REQ
+ Set the bit to 1 to allow the driving nodes start transmission.
+ 0
+ 1
+ write-only
+
+
+ ABORT_TX
+ Set the bit to 1 to cancel a pending transmission request.
+ 1
+ 1
+ write-only
+
+
+ RELEASE_BUF
+ Set the bit to 1 to release the RX buffer.
+ 2
+ 1
+ write-only
+
+
+ CLR_OVERRUN
+ Set the bit to 1 to clear the data overrun status bit.
+ 3
+ 1
+ write-only
+
+
+ SELF_RX_REQ
+ Self reception request command. Set the bit to 1 to allow a message be transmitted and received simultaneously.
+ 4
+ 1
+ write-only
+
+
+
+
+ STATUS
+ Status register
+ 0x8
+ 0x20
+
+
+ RX_BUF_ST
+ 1: The data in the RX buffer is not empty, with at least one received data packet.
+ 0
+ 1
+ read-only
+
+
+ OVERRUN_ST
+ 1: The RX FIFO is full and data overrun has occurred.
+ 1
+ 1
+ read-only
+
+
+ TX_BUF_ST
+ 1: The TX buffer is empty, the CPU may write a message into it.
+ 2
+ 1
+ read-only
+
+
+ TX_COMPLETE
+ 1: The TWAI controller has successfully received a packet from the bus.
+ 3
+ 1
+ read-only
+
+
+ RX_ST
+ 1: The TWAI Controller is receiving a message from the bus.
+ 4
+ 1
+ read-only
+
+
+ TX_ST
+ 1: The TWAI Controller is transmitting a message to the bus.
+ 5
+ 1
+ read-only
+
+
+ ERR_ST
+ 1: At least one of the RX/TX error counter has reached or exceeded the value set in register TWAI_ERR_WARNING_LIMIT_REG.
+ 6
+ 1
+ read-only
+
+
+ BUS_OFF_ST
+ 1: In bus-off status, the TWAI Controller is no longer involved in bus activities.
+ 7
+ 1
+ read-only
+
+
+ MISS_ST
+ This bit reflects whether the data packet in the RX FIFO is complete. 1: The current packet is missing; 0: The current packet is complete
+ 8
+ 1
+ read-only
+
+
+
+
+ INT_RAW
+ Interrupt Register
+ 0xC
+ 0x20
+
+
+ RX_INT_ST
+ Receive interrupt. If this bit is set to 1, it indicates there are messages to be handled in the RX FIFO.
+ 0
+ 1
+ read-only
+
+
+ TX_INT_ST
+ Transmit interrupt. If this bit is set to 1, it indicates the message transmitting mis- sion is finished and a new transmission is able to execute.
+ 1
+ 1
+ read-only
+
+
+ ERR_WARN_INT_ST
+ Error warning interrupt. If this bit is set to 1, it indicates the error status signal and the bus-off status signal of Status register have changed (e.g., switched from 0 to 1 or from 1 to 0).
+ 2
+ 1
+ read-only
+
+
+ OVERRUN_INT_ST
+ Data overrun interrupt. If this bit is set to 1, it indicates a data overrun interrupt is generated in the RX FIFO.
+ 3
+ 1
+ read-only
+
+
+ ERR_PASSIVE_INT_ST
+ Error passive interrupt. If this bit is set to 1, it indicates the TWAI Controller is switched between error active status and error passive status due to the change of error counters.
+ 5
+ 1
+ read-only
+
+
+ ARB_LOST_INT_ST
+ Arbitration lost interrupt. If this bit is set to 1, it indicates an arbitration lost interrupt is generated.
+ 6
+ 1
+ read-only
+
+
+ BUS_ERR_INT_ST
+ Error interrupt. If this bit is set to 1, it indicates an error is detected on the bus.
+ 7
+ 1
+ read-only
+
+
+
+
+ INT_ENA
+ Interrupt Enable Register
+ 0x10
+ 0x20
+
+
+ RX_INT_ENA
+ Set this bit to 1 to enable receive interrupt.
+ 0
+ 1
+ read-write
+
+
+ TX_INT_ENA
+ Set this bit to 1 to enable transmit interrupt.
+ 1
+ 1
+ read-write
+
+
+ ERR_WARN_INT_ENA
+ Set this bit to 1 to enable error warning interrupt.
+ 2
+ 1
+ read-write
+
+
+ OVERRUN_INT_ENA
+ Set this bit to 1 to enable data overrun interrupt.
+ 3
+ 1
+ read-write
+
+
+ ERR_PASSIVE_INT_ENA
+ Set this bit to 1 to enable error passive interrupt.
+ 5
+ 1
+ read-write
+
+
+ ARB_LOST_INT_ENA
+ Set this bit to 1 to enable arbitration lost interrupt.
+ 6
+ 1
+ read-write
+
+
+ BUS_ERR_INT_ENA
+ Set this bit to 1 to enable error interrupt.
+ 7
+ 1
+ read-write
+
+
+
+
+ BUS_TIMING_0
+ Bus Timing Register 0
+ 0x18
+ 0x20
+
+
+ BAUD_PRESC
+ Baud Rate Prescaler, determines the frequency dividing ratio.
+ 0
+ 14
+
+
+ SYNC_JUMP_WIDTH
+ Synchronization Jump Width (SJW), 1 \verb+~+ 14 Tq wide.
+ 14
+ 2
+
+
+
+
+ BUS_TIMING_1
+ Bus Timing Register 1
+ 0x1C
+ 0x20
+
+
+ TIME_SEG1
+ The width of PBS1.
+ 0
+ 4
+
+
+ TIME_SEG2
+ The width of PBS2.
+ 4
+ 3
+
+
+ TIME_SAMP
+ The number of sample points. 0: the bus is sampled once; 1: the bus is sampled three times
+ 7
+ 1
+
+
+
+
+ ARB_LOST_CAP
+ Arbitration Lost Capture Register
+ 0x2C
+ 0x20
+
+
+ ARB_LOST_CAP
+ This register contains information about the bit position of lost arbitration.
+ 0
+ 5
+ read-only
+
+
+
+
+ ERR_CODE_CAP
+ Error Code Capture Register
+ 0x30
+ 0x20
+
+
+ ECC_SEGMENT
+ This register contains information about the location of errors, see Table 181 for details.
+ 0
+ 5
+ read-only
+
+
+ ECC_DIRECTION
+ This register contains information about transmission direction of the node when error occurs. 1: Error occurs when receiving a message; 0: Error occurs when transmitting a message
+ 5
+ 1
+ read-only
+
+
+ ECC_TYPE
+ This register contains information about error types: 00: bit error; 01: form error; 10: stuff error; 11: other type of error
+ 6
+ 2
+ read-only
+
+
+
+
+ ERR_WARNING_LIMIT
+ Error Warning Limit Register
+ 0x34
+ 0x20
+ 0x00000060
+
+
+ ERR_WARNING_LIMIT
+ Error warning threshold. In the case when any of a error counter value exceeds the threshold, or all the error counter values are below the threshold, an error warning interrupt will be triggered (given the enable signal is valid).
+ 0
+ 8
+
+
+
+
+ RX_ERR_CNT
+ Receive Error Counter Register
+ 0x38
+ 0x20
+
+
+ RX_ERR_CNT
+ The RX error counter register, reflects value changes under reception status.
+ 0
+ 8
+
+
+
+
+ TX_ERR_CNT
+ Transmit Error Counter Register
+ 0x3C
+ 0x20
+
+
+ TX_ERR_CNT
+ The TX error counter register, reflects value changes under transmission status.
+ 0
+ 8
+
+
+
+
+ DATA_0
+ Data register 0
+ 0x40
+ 0x20
+
+
+ TX_BYTE_0
+ In reset mode, it is acceptance code register 0 with R/W Permission. In operation mode, it stores the 0th byte information of the data to be transmitted under operating mode.
+ 0
+ 8
+ write-only
+
+
+
+
+ DATA_1
+ Data register 1
+ 0x44
+ 0x20
+
+
+ TX_BYTE_1
+ In reset mode, it is acceptance code register 1 with R/W Permission. In operation mode, it stores the 1st byte information of the data to be transmitted under operating mode.
+ 0
+ 8
+ write-only
+
+
+
+
+ DATA_2
+ Data register 2
+ 0x48
+ 0x20
+
+
+ TX_BYTE_2
+ In reset mode, it is acceptance code register 2 with R/W Permission. In operation mode, it stores the 2nd byte information of the data to be transmitted under operating mode.
+ 0
+ 8
+ write-only
+
+
+
+
+ DATA_3
+ Data register 3
+ 0x4C
+ 0x20
+
+
+ TX_BYTE_3
+ In reset mode, it is acceptance code register 3 with R/W Permission. In operation mode, it stores the 3rd byte information of the data to be transmitted under operating mode.
+ 0
+ 8
+ write-only
+
+
+
+
+ DATA_4
+ Data register 4
+ 0x50
+ 0x20
+
+
+ TX_BYTE_4
+ In reset mode, it is acceptance mask register 0 with R/W Permission. In operation mode, it stores the 4th byte information of the data to be transmitted under operating mode.
+ 0
+ 8
+ write-only
+
+
+
+
+ DATA_5
+ Data register 5
+ 0x54
+ 0x20
+
+
+ TX_BYTE_5
+ In reset mode, it is acceptance mask register 1 with R/W Permission. In operation mode, it stores the 5th byte information of the data to be transmitted under operating mode.
+ 0
+ 8
+ write-only
+
+
+
+
+ DATA_6
+ Data register 6
+ 0x58
+ 0x20
+
+
+ TX_BYTE_6
+ In reset mode, it is acceptance mask register 2 with R/W Permission. In operation mode, it stores the 6th byte information of the data to be transmitted under operating mode.
+ 0
+ 8
+ write-only
+
+
+
+
+ DATA_7
+ Data register 7
+ 0x5C
+ 0x20
+
+
+ TX_BYTE_7
+ In reset mode, it is acceptance mask register 3 with R/W Permission. In operation mode, it stores the 7th byte information of the data to be transmitted under operating mode.
+ 0
+ 8
+ write-only
+
+
+
+
+ DATA_8
+ Data register 8
+ 0x60
+ 0x20
+
+
+ TX_BYTE_8
+ Stored the 8th byte information of the data to be transmitted under operating mode.
+ 0
+ 8
+ write-only
+
+
+
+
+ DATA_9
+ Data register 9
+ 0x64
+ 0x20
+
+
+ TX_BYTE_9
+ Stored the 9th byte information of the data to be transmitted under operating mode.
+ 0
+ 8
+ write-only
+
+
+
+
+ DATA_10
+ Data register 10
+ 0x68
+ 0x20
+
+
+ TX_BYTE_10
+ Stored the 10th byte information of the data to be transmitted under operating mode.
+ 0
+ 8
+ write-only
+
+
+
+
+ DATA_11
+ Data register 11
+ 0x6C
+ 0x20
+
+
+ TX_BYTE_11
+ Stored the 11th byte information of the data to be transmitted under operating mode.
+ 0
+ 8
+ write-only
+
+
+
+
+ DATA_12
+ Data register 12
+ 0x70
+ 0x20
+
+
+ TX_BYTE_12
+ Stored the 12th byte information of the data to be transmitted under operating mode.
+ 0
+ 8
+ write-only
+
+
+
+
+ RX_MESSAGE_CNT
+ Receive Message Counter Register
+ 0x74
+ 0x20
+
+
+ RX_MESSAGE_COUNTER
+ This register reflects the number of messages available within the RX FIFO.
+ 0
+ 7
+ read-only
+
+
+
+
+ CLOCK_DIVIDER
+ Clock Divider register
+ 0x7C
+ 0x20
+
+
+ CD
+ These bits are used to configure frequency dividing coefficients of the external CLKOUT pin.
+ 0
+ 8
+ read-write
+
+
+ CLOCK_OFF
+ This bit can be configured under reset mode. 1: Disable the external CLKOUT pin; 0: Enable the external CLKOUT pin
+ 8
+ 1
+
+
+
+
+
+
+ UART0
+ UART (Universal Asynchronous Receiver-Transmitter) Controller
+ UART
+ 0x3FF40000
+
+ 0x0
+ 0x7C
+ registers
+
+
+ UART0
+ 34
+
+
+
+ FIFO
+ 0x0
+ 0x20
+
+
+ RXFIFO_RD_BYTE
+ This register stores one byte data read by rx fifo.
+ 0
+ 8
+ read-write
+
+
+
+
+ INT_RAW
+ 0x4
+ 0x20
+
+
+ RXFIFO_FULL_INT_RAW
+ This interrupt raw bit turns to high level when receiver receives more data than (rx_flow_thrhd_h3 rx_flow_thrhd).
+ 0
+ 1
+ read-only
+
+
+ TXFIFO_EMPTY_INT_RAW
+ This interrupt raw bit turns to high level when the amount of data in transmitter's fifo is less than ((tx_mem_cnttxfifo_cnt) .
+ 1
+ 1
+ read-only
+
+
+ PARITY_ERR_INT_RAW
+ This interrupt raw bit turns to high level when receiver detects the parity error of data.
+ 2
+ 1
+ read-only
+
+
+ FRM_ERR_INT_RAW
+ This interrupt raw bit turns to high level when receiver detects data's frame error .
+ 3
+ 1
+ read-only
+
+
+ RXFIFO_OVF_INT_RAW
+ This interrupt raw bit turns to high level when receiver receives more data than the fifo can store.
+ 4
+ 1
+ read-only
+
+
+ DSR_CHG_INT_RAW
+ This interrupt raw bit turns to high level when receiver detects the edge change of dsrn signal.
+ 5
+ 1
+ read-only
+
+
+ CTS_CHG_INT_RAW
+ This interrupt raw bit turns to high level when receiver detects the edge change of ctsn signal.
+ 6
+ 1
+ read-only
+
+
+ BRK_DET_INT_RAW
+ This interrupt raw bit turns to high level when receiver detects the 0 after the stop bit.
+ 7
+ 1
+ read-only
+
+
+ RXFIFO_TOUT_INT_RAW
+ This interrupt raw bit turns to high level when receiver takes more time than rx_tout_thrhd to receive a byte.
+ 8
+ 1
+ read-only
+
+
+ SW_XON_INT_RAW
+ This interrupt raw bit turns to high level when receiver receives xoff char with uart_sw_flow_con_en is set to 1.
+ 9
+ 1
+ read-only
+
+
+ SW_XOFF_INT_RAW
+ This interrupt raw bit turns to high level when receiver receives xon char with uart_sw_flow_con_en is set to 1.
+ 10
+ 1
+ read-only
+
+
+ GLITCH_DET_INT_RAW
+ This interrupt raw bit turns to high level when receiver detects the start bit.
+ 11
+ 1
+ read-only
+
+
+ TX_BRK_DONE_INT_RAW
+ This interrupt raw bit turns to high level when transmitter completes sendding 0 after all the datas in transmitter's fifo are send.
+ 12
+ 1
+ read-only
+
+
+ TX_BRK_IDLE_DONE_INT_RAW
+ This interrupt raw bit turns to high level when transmitter has kept the shortest duration after the last data has been send.
+ 13
+ 1
+ read-only
+
+
+ TX_DONE_INT_RAW
+ This interrupt raw bit turns to high level when transmitter has send all the data in fifo.
+ 14
+ 1
+ read-only
+
+
+ RS485_PARITY_ERR_INT_RAW
+ This interrupt raw bit turns to high level when rs485 detects the parity error.
+ 15
+ 1
+ read-only
+
+
+ RS485_FRM_ERR_INT_RAW
+ This interrupt raw bit turns to high level when rs485 detects the data frame error.
+ 16
+ 1
+ read-only
+
+
+ RS485_CLASH_INT_RAW
+ This interrupt raw bit turns to high level when rs485 detects the clash between transmitter and receiver.
+ 17
+ 1
+ read-only
+
+
+ AT_CMD_CHAR_DET_INT_RAW
+ This interrupt raw bit turns to high level when receiver detects the configured at_cmd chars.
+ 18
+ 1
+ read-only
+
+
+
+
+ INT_ST
+ 0x8
+ 0x20
+
+
+ RXFIFO_FULL_INT_ST
+ This is the status bit for rxfifo_full_int_raw when rxfifo_full_int_ena is set to 1.
+ 0
+ 1
+ read-only
+
+
+ TXFIFO_EMPTY_INT_ST
+ This is the status bit for txfifo_empty_int_raw when txfifo_empty_int_ena is set to 1.
+ 1
+ 1
+ read-only
+
+
+ PARITY_ERR_INT_ST
+ This is the status bit for parity_err_int_raw when parity_err_int_ena is set to 1.
+ 2
+ 1
+ read-only
+
+
+ FRM_ERR_INT_ST
+ This is the status bit for frm_err_int_raw when fm_err_int_ena is set to 1.
+ 3
+ 1
+ read-only
+
+
+ RXFIFO_OVF_INT_ST
+ This is the status bit for rxfifo_ovf_int_raw when rxfifo_ovf_int_ena is set to 1.
+ 4
+ 1
+ read-only
+
+
+ DSR_CHG_INT_ST
+ This is the status bit for dsr_chg_int_raw when dsr_chg_int_ena is set to 1.
+ 5
+ 1
+ read-only
+
+
+ CTS_CHG_INT_ST
+ This is the status bit for cts_chg_int_raw when cts_chg_int_ena is set to 1.
+ 6
+ 1
+ read-only
+
+
+ BRK_DET_INT_ST
+ This is the status bit for brk_det_int_raw when brk_det_int_ena is set to 1.
+ 7
+ 1
+ read-only
+
+
+ RXFIFO_TOUT_INT_ST
+ This is the status bit for rxfifo_tout_int_raw when rxfifo_tout_int_ena is set to 1.
+ 8
+ 1
+ read-only
+
+
+ SW_XON_INT_ST
+ This is the status bit for sw_xon_int_raw when sw_xon_int_ena is set to 1.
+ 9
+ 1
+ read-only
+
+
+ SW_XOFF_INT_ST
+ This is the status bit for sw_xoff_int_raw when sw_xoff_int_ena is set to 1.
+ 10
+ 1
+ read-only
+
+
+ GLITCH_DET_INT_ST
+ This is the status bit for glitch_det_int_raw when glitch_det_int_ena is set to 1.
+ 11
+ 1
+ read-only
+
+
+ TX_BRK_DONE_INT_ST
+ This is the status bit for tx_brk_done_int_raw when tx_brk_done_int_ena is set to 1.
+ 12
+ 1
+ read-only
+
+
+ TX_BRK_IDLE_DONE_INT_ST
+ This is the stauts bit for tx_brk_idle_done_int_raw when tx_brk_idle_done_int_ena is set to 1.
+ 13
+ 1
+ read-only
+
+
+ TX_DONE_INT_ST
+ This is the status bit for tx_done_int_raw when tx_done_int_ena is set to 1.
+ 14
+ 1
+ read-only
+
+
+ RS485_PARITY_ERR_INT_ST
+ This is the status bit for rs485_parity_err_int_raw when rs485_parity_int_ena is set to 1.
+ 15
+ 1
+ read-only
+
+
+ RS485_FRM_ERR_INT_ST
+ This is the status bit for rs485_fm_err_int_raw when rs485_fm_err_int_ena is set to 1.
+ 16
+ 1
+ read-only
+
+
+ RS485_CLASH_INT_ST
+ This is the status bit for rs485_clash_int_raw when rs485_clash_int_ena is set to 1.
+ 17
+ 1
+ read-only
+
+
+ AT_CMD_CHAR_DET_INT_ST
+ This is the status bit for at_cmd_det_int_raw when at_cmd_char_det_int_ena is set to 1.
+ 18
+ 1
+ read-only
+
+
+
+
+ INT_ENA
+ 0xC
+ 0x20
+
+
+ RXFIFO_FULL_INT_ENA
+ This is the enable bit for rxfifo_full_int_st register.
+ 0
+ 1
+ read-write
+
+
+ TXFIFO_EMPTY_INT_ENA
+ This is the enable bit for rxfifo_full_int_st register.
+ 1
+ 1
+ read-write
+
+
+ PARITY_ERR_INT_ENA
+ This is the enable bit for parity_err_int_st register.
+ 2
+ 1
+ read-write
+
+
+ FRM_ERR_INT_ENA
+ This is the enable bit for frm_err_int_st register.
+ 3
+ 1
+ read-write
+
+
+ RXFIFO_OVF_INT_ENA
+ This is the enable bit for rxfifo_ovf_int_st register.
+ 4
+ 1
+ read-write
+
+
+ DSR_CHG_INT_ENA
+ This is the enable bit for dsr_chg_int_st register.
+ 5
+ 1
+ read-write
+
+
+ CTS_CHG_INT_ENA
+ This is the enable bit for cts_chg_int_st register.
+ 6
+ 1
+ read-write
+
+
+ BRK_DET_INT_ENA
+ This is the enable bit for brk_det_int_st register.
+ 7
+ 1
+ read-write
+
+
+ RXFIFO_TOUT_INT_ENA
+ This is the enable bit for rxfifo_tout_int_st register.
+ 8
+ 1
+ read-write
+
+
+ SW_XON_INT_ENA
+ This is the enable bit for sw_xon_int_st register.
+ 9
+ 1
+ read-write
+
+
+ SW_XOFF_INT_ENA
+ This is the enable bit for sw_xoff_int_st register.
+ 10
+ 1
+ read-write
+
+
+ GLITCH_DET_INT_ENA
+ This is the enable bit for glitch_det_int_st register.
+ 11
+ 1
+ read-write
+
+
+ TX_BRK_DONE_INT_ENA
+ This is the enable bit for tx_brk_done_int_st register.
+ 12
+ 1
+ read-write
+
+
+ TX_BRK_IDLE_DONE_INT_ENA
+ This is the enable bit for tx_brk_idle_done_int_st register.
+ 13
+ 1
+ read-write
+
+
+ TX_DONE_INT_ENA
+ This is the enable bit for tx_done_int_st register.
+ 14
+ 1
+ read-write
+
+
+ RS485_PARITY_ERR_INT_ENA
+ This is the enable bit for rs485_parity_err_int_st register.
+ 15
+ 1
+ read-write
+
+
+ RS485_FRM_ERR_INT_ENA
+ This is the enable bit for rs485_parity_err_int_st register.
+ 16
+ 1
+ read-write
+
+
+ RS485_CLASH_INT_ENA
+ This is the enable bit for rs485_clash_int_st register.
+ 17
+ 1
+ read-write
+
+
+ AT_CMD_CHAR_DET_INT_ENA
+ This is the enable bit for at_cmd_char_det_int_st register.
+ 18
+ 1
+ read-write
+
+
+
+
+ INT_CLR
+ 0x10
+ 0x20
+
+
+ RXFIFO_FULL_INT_CLR
+ Set this bit to clear the rxfifo_full_int_raw interrupt.
+ 0
+ 1
+ write-only
+
+
+ TXFIFO_EMPTY_INT_CLR
+ Set this bit to clear txfifo_empty_int_raw interrupt.
+ 1
+ 1
+ write-only
+
+
+ PARITY_ERR_INT_CLR
+ Set this bit to clear parity_err_int_raw interrupt.
+ 2
+ 1
+ write-only
+
+
+ FRM_ERR_INT_CLR
+ Set this bit to clear frm_err_int_raw interrupt.
+ 3
+ 1
+ write-only
+
+
+ RXFIFO_OVF_INT_CLR
+ Set this bit to clear rxfifo_ovf_int_raw interrupt.
+ 4
+ 1
+ write-only
+
+
+ DSR_CHG_INT_CLR
+ Set this bit to clear the dsr_chg_int_raw interrupt.
+ 5
+ 1
+ write-only
+
+
+ CTS_CHG_INT_CLR
+ Set this bit to clear the cts_chg_int_raw interrupt.
+ 6
+ 1
+ write-only
+
+
+ BRK_DET_INT_CLR
+ Set this bit to clear the brk_det_int_raw interrupt.
+ 7
+ 1
+ write-only
+
+
+ RXFIFO_TOUT_INT_CLR
+ Set this bit to clear the rxfifo_tout_int_raw interrupt.
+ 8
+ 1
+ write-only
+
+
+ SW_XON_INT_CLR
+ Set this bit to clear the sw_xon_int_raw interrupt.
+ 9
+ 1
+ write-only
+
+
+ SW_XOFF_INT_CLR
+ Set this bit to clear the sw_xon_int_raw interrupt.
+ 10
+ 1
+ write-only
+
+
+ GLITCH_DET_INT_CLR
+ Set this bit to clear the glitch_det_int_raw interrupt.
+ 11
+ 1
+ write-only
+
+
+ TX_BRK_DONE_INT_CLR
+ Set this bit to clear the tx_brk_done_int_raw interrupt..
+ 12
+ 1
+ write-only
+
+
+ TX_BRK_IDLE_DONE_INT_CLR
+ Set this bit to clear the tx_brk_idle_done_int_raw interrupt.
+ 13
+ 1
+ write-only
+
+
+ TX_DONE_INT_CLR
+ Set this bit to clear the tx_done_int_raw interrupt.
+ 14
+ 1
+ write-only
+
+
+ RS485_PARITY_ERR_INT_CLR
+ Set this bit to clear the rs485_parity_err_int_raw interrupt.
+ 15
+ 1
+ write-only
+
+
+ RS485_FRM_ERR_INT_CLR
+ Set this bit to clear the rs485_frm_err_int_raw interrupt.
+ 16
+ 1
+ write-only
+
+
+ RS485_CLASH_INT_CLR
+ Set this bit to clear the rs485_clash_int_raw interrupt.
+ 17
+ 1
+ write-only
+
+
+ AT_CMD_CHAR_DET_INT_CLR
+ Set this bit to clear the at_cmd_char_det_int_raw interrupt.
+ 18
+ 1
+ write-only
+
+
+
+
+ CLKDIV
+ 0x14
+ 0x20
+ 0x000002B6
+
+
+ CLKDIV
+ The register value is the integer part of the frequency divider's factor.
+ 0
+ 20
+ read-write
+
+
+ FRAG
+ The register value is the decimal part of the frequency divider's factor.
+ 20
+ 4
+ read-write
+
+
+
+
+ AUTOBAUD
+ 0x18
+ 0x20
+ 0x00001000
+
+
+ EN
+ This is the enable bit for detecting baudrate.
+ 0
+ 1
+ read-write
+
+
+ GLITCH_FILT
+ when input pulse width is lower then this value igore this pulse.this register is used in autobaud detect process.
+ 8
+ 8
+ read-write
+
+
+
+
+ STATUS
+ 0x1C
+ 0x20
+
+
+ RXFIFO_CNT
+ (rx_mem_cnt rxfifo_cnt) stores the byte num of valid datas in receiver's fifo. rx_mem_cnt register stores the 3 most significant bits rxfifo_cnt stores the 8 least significant bits.
+ 0
+ 8
+ read-only
+
+
+ ST_URX_OUT
+ This register stores the value of receiver's finite state machine. 0:RX_IDLE 1:RX_STRT 2:RX_DAT0 3:RX_DAT1 4:RX_DAT2 5:RX_DAT3 6:RX_DAT4 7:RX_DAT5 8:RX_DAT6 9:RX_DAT7 10:RX_PRTY 11:RX_STP1 12:RX_STP2 13:RX_DL1
+ 8
+ 4
+ read-only
+
+
+ DSRN
+ This register stores the level value of the internal uart dsr signal.
+ 13
+ 1
+ read-only
+
+
+ CTSN
+ This register stores the level value of the internal uart cts signal.
+ 14
+ 1
+ read-only
+
+
+ RXD
+ This register stores the level value of the internal uart rxd signal.
+ 15
+ 1
+ read-only
+
+
+ TXFIFO_CNT
+ (tx_mem_cnt txfifo_cnt) stores the byte num of valid datas in transmitter's fifo.tx_mem_cnt stores the 3 most significant bits txfifo_cnt stores the 8 least significant bits.
+ 16
+ 8
+ read-only
+
+
+ ST_UTX_OUT
+ This register stores the value of transmitter's finite state machine. 0:TX_IDLE 1:TX_STRT 2:TX_DAT0 3:TX_DAT1 4:TX_DAT2 5:TX_DAT3 6:TX_DAT4 7:TX_DAT5 8:TX_DAT6 9:TX_DAT7 10:TX_PRTY 11:TX_STP1 12:TX_STP2 13:TX_DL0 14:TX_DL1
+ 24
+ 4
+ read-only
+
+
+ DTRN
+ The register represent the level value of the internal uart dsr signal.
+ 29
+ 1
+ read-only
+
+
+ RTSN
+ This register represent the level value of the internal uart cts signal.
+ 30
+ 1
+ read-only
+
+
+ TXD
+ This register represent the level value of the internal uart rxd signal.
+ 31
+ 1
+ read-only
+
+
+
+
+ CONF0
+ 0x20
+ 0x20
+ 0x0800001C
+
+
+ PARITY
+ This register is used to configure the parity check mode. 0:even 1:odd
+ 0
+ 1
+ read-write
+
+
+ PARITY_EN
+ Set this bit to enable uart parity check.
+ 1
+ 1
+ read-write
+
+
+ BIT_NUM
+ This registe is used to set the length of data: 0:5bits 1:6bits 2:7bits 3:8bits
+ 2
+ 2
+ read-write
+
+
+ STOP_BIT_NUM
+ This register is used to set the length of stop bit. 1:1bit 2:1.5bits 3:2bits
+ 4
+ 2
+ read-write
+
+
+ SW_RTS
+ This register is used to configure the software rts signal which is used in software flow control.
+ 6
+ 1
+ read-write
+
+
+ SW_DTR
+ This register is used to configure the software dtr signal which is used in software flow control..
+ 7
+ 1
+ read-write
+
+
+ TXD_BRK
+ Set this bit to enbale transmitter to send 0 when the process of sending data is done.
+ 8
+ 1
+ read-write
+
+
+ IRDA_DPLX
+ Set this bit to enable irda loopback mode.
+ 9
+ 1
+ read-write
+
+
+ IRDA_TX_EN
+ This is the start enable bit for irda transmitter.
+ 10
+ 1
+ read-write
+
+
+ IRDA_WCTL
+ 1.the irda transmitter's 11th bit is the same to the 10th bit. 0.set irda transmitter's 11th bit to 0.
+ 11
+ 1
+ read-write
+
+
+ IRDA_TX_INV
+ Set this bit to inverse the level value of irda transmitter's level.
+ 12
+ 1
+ read-write
+
+
+ IRDA_RX_INV
+ Set this bit to inverse the level value of irda receiver's level.
+ 13
+ 1
+ read-write
+
+
+ LOOPBACK
+ Set this bit to enable uart loopback test mode.
+ 14
+ 1
+ read-write
+
+
+ TX_FLOW_EN
+ Set this bit to enable transmitter's flow control function.
+ 15
+ 1
+ read-write
+
+
+ IRDA_EN
+ Set this bit to enable irda protocol.
+ 16
+ 1
+ read-write
+
+
+ RXFIFO_RST
+ Set this bit to reset uart receiver's fifo.
+ 17
+ 1
+ read-write
+
+
+ TXFIFO_RST
+ Set this bit to reset uart transmitter's fifo.
+ 18
+ 1
+ read-write
+
+
+ RXD_INV
+ Set this bit to inverse the level value of uart rxd signal.
+ 19
+ 1
+ read-write
+
+
+ CTS_INV
+ Set this bit to inverse the level value of uart cts signal.
+ 20
+ 1
+ read-write
+
+
+ DSR_INV
+ Set this bit to inverse the level value of uart dsr signal.
+ 21
+ 1
+ read-write
+
+
+ TXD_INV
+ Set this bit to inverse the level value of uart txd signal.
+ 22
+ 1
+ read-write
+
+
+ RTS_INV
+ Set this bit to inverse the level value of uart rts signal.
+ 23
+ 1
+ read-write
+
+
+ DTR_INV
+ Set this bit to inverse the level value of uart dtr signal.
+ 24
+ 1
+ read-write
+
+
+ CLK_EN
+ 1.force clock on for registers.support clock only when write registers
+ 25
+ 1
+ read-write
+
+
+ ERR_WR_MASK
+ 1.receiver stops storing data int fifo when data is wrong. 0.receiver stores the data even if the received data is wrong.
+ 26
+ 1
+ read-write
+
+
+ TICK_REF_ALWAYS_ON
+ This register is used to select the clock.1.apb clock 0:ref_tick
+ 27
+ 1
+ read-write
+
+
+
+
+ CONF1
+ 0x24
+ 0x20
+ 0x00006060
+
+
+ RXFIFO_FULL_THRHD
+ When receiver receives more data than its threshold value.receiver will produce rxfifo_full_int_raw interrupt.the threshold value is (rx_flow_thrhd_h3 rxfifo_full_thrhd).
+ 0
+ 7
+ read-write
+
+
+ TXFIFO_EMPTY_THRHD
+ when the data amount in transmitter fifo is less than its threshold value. it will produce txfifo_empty_int_raw interrupt. the threshold value is (tx_mem_empty_thrhd txfifo_empty_thrhd)
+ 8
+ 7
+ read-write
+
+
+ RX_FLOW_THRHD
+ when receiver receives more data than its threshold value. receiver produce signal to tell the transmitter stop transferring data. the threshold value is (rx_flow_thrhd_h3 rx_flow_thrhd).
+ 16
+ 7
+ read-write
+
+
+ RX_FLOW_EN
+ This is the flow enable bit for uart receiver. 1:choose software flow control with configuring sw_rts signal
+ 23
+ 1
+ read-write
+
+
+ RX_TOUT_THRHD
+ This register is used to configure the timeout value for uart receiver receiving a byte.
+ 24
+ 7
+ read-write
+
+
+ RX_TOUT_EN
+ This is the enble bit for uart receiver's timeout function.
+ 31
+ 1
+ read-write
+
+
+
+
+ LOWPULSE
+ 0x28
+ 0x20
+ 0x000FFFFF
+
+
+ MIN_CNT
+ This register stores the value of the minimum duration time for the low level pulse. it is used in baudrate-detect process.
+ 0
+ 20
+ read-only
+
+
+
+
+ HIGHPULSE
+ 0x2C
+ 0x20
+ 0x000FFFFF
+
+
+ MIN_CNT
+ This register stores the value of the maxinum duration time for the high level pulse. it is used in baudrate-detect process.
+ 0
+ 20
+ read-only
+
+
+
+
+ RXD_CNT
+ 0x30
+ 0x20
+
+
+ RXD_EDGE_CNT
+ This register stores the count of rxd edge change. it is used in baudrate-detect process.
+ 0
+ 10
+ read-only
+
+
+
+
+ FLOW_CONF
+ 0x34
+ 0x20
+
+
+ SW_FLOW_CON_EN
+ Set this bit to enable software flow control. it is used with register sw_xon or sw_xoff .
+ 0
+ 1
+ read-write
+
+
+ XONOFF_DEL
+ Set this bit to remove flow control char from the received data.
+ 1
+ 1
+ read-write
+
+
+ FORCE_XON
+ Set this bit to clear ctsn to stop the transmitter from sending data.
+ 2
+ 1
+ read-write
+
+
+ FORCE_XOFF
+ Set this bit to set ctsn to enable the transmitter to go on sending data.
+ 3
+ 1
+ read-write
+
+
+ SEND_XON
+ Set this bit to send xon char. it is cleared by hardware automatically.
+ 4
+ 1
+ read-write
+
+
+ SEND_XOFF
+ Set this bit to send xoff char. it is cleared by hardware automatically.
+ 5
+ 1
+ read-write
+
+
+
+
+ SLEEP_CONF
+ 0x38
+ 0x20
+ 0x000000F0
+
+
+ ACTIVE_THRESHOLD
+ When the input rxd edge changes more than this register value. the uart is active from light sleeping mode.
+ 0
+ 10
+ read-write
+
+
+
+
+ SWFC_CONF
+ 0x3C
+ 0x20
+ 0x1311E000
+
+
+ XON_THRESHOLD
+ when the data amount in receiver's fifo is more than this register value. it will send a xoff char with uart_sw_flow_con_en set to 1.
+ 0
+ 8
+ read-write
+
+
+ XOFF_THRESHOLD
+ When the data amount in receiver's fifo is less than this register value. it will send a xon char with uart_sw_flow_con_en set to 1.
+ 8
+ 8
+ read-write
+
+
+ XON_CHAR
+ This register stores the xon flow control char.
+ 16
+ 8
+ read-write
+
+
+ XOFF_CHAR
+ This register stores the xoff flow control char.
+ 24
+ 8
+ read-write
+
+
+
+
+ IDLE_CONF
+ 0x40
+ 0x20
+ 0x00A40100
+
+
+ RX_IDLE_THRHD
+ when receiver takes more time than this register value to receive a byte data. it will produce frame end signal for uhci to stop receiving data.
+ 0
+ 10
+ read-write
+
+
+ TX_IDLE_NUM
+ This register is used to configure the duration time between transfers.
+ 10
+ 10
+ read-write
+
+
+ TX_BRK_NUM
+ This register is used to configure the num of 0 send after the process of sending data is done. it is active when txd_brk is set to 1.
+ 20
+ 8
+ read-write
+
+
+
+
+ RS485_CONF
+ 0x44
+ 0x20
+
+
+ RS485_EN
+ Set this bit to choose rs485 mode.
+ 0
+ 1
+ read-write
+
+
+ DL0_EN
+ Set this bit to delay the stop bit by 1 bit.
+ 1
+ 1
+ read-write
+
+
+ DL1_EN
+ Set this bit to delay the stop bit by 1 bit.
+ 2
+ 1
+ read-write
+
+
+ RS485TX_RX_EN
+ Set this bit to enable loopback transmitter's output data signal to receiver's input data signal.
+ 3
+ 1
+ read-write
+
+
+ RS485RXBY_TX_EN
+ 1: enable rs485's transmitter to send data when rs485's receiver is busy. 0:rs485's transmitter should not send data when its receiver is busy.
+ 4
+ 1
+ read-write
+
+
+ RS485_RX_DLY_NUM
+ This register is used to delay the receiver's internal data signal.
+ 5
+ 1
+ read-write
+
+
+ RS485_TX_DLY_NUM
+ This register is used to delay the transmitter's internal data signal.
+ 6
+ 4
+ read-write
+
+
+
+
+ AT_CMD_PRECNT
+ 0x48
+ 0x20
+ 0x00186A00
+
+
+ PRE_IDLE_NUM
+ This register is used to configure the idle duration time before the first at_cmd is received by receiver. when the the duration is less than this register value it will not take the next data received as at_cmd char.
+ 0
+ 24
+ read-write
+
+
+
+
+ AT_CMD_POSTCNT
+ 0x4C
+ 0x20
+ 0x00186A00
+
+
+ POST_IDLE_NUM
+ This register is used to configure the duration time between the last at_cmd and the next data. when the duration is less than this register value it will not take the previous data as at_cmd char.
+ 0
+ 24
+ read-write
+
+
+
+
+ AT_CMD_GAPTOUT
+ 0x50
+ 0x20
+ 0x00001E00
+
+
+ RX_GAP_TOUT
+ This register is used to configure the duration time between the at_cmd chars. when the duration time is less than this register value it will not take the datas as continous at_cmd chars.
+ 0
+ 24
+ read-write
+
+
+
+
+ AT_CMD_CHAR
+ 0x54
+ 0x20
+ 0x0000032B
+
+
+ AT_CMD_CHAR
+ This register is used to configure the content of at_cmd char.
+ 0
+ 8
+ read-write
+
+
+ CHAR_NUM
+ This register is used to configure the num of continous at_cmd chars received by receiver.
+ 8
+ 8
+ read-write
+
+
+
+
+ MEM_CONF
+ 0x58
+ 0x20
+ 0x00000088
+
+
+ MEM_PD
+ Set this bit to power down mem.when reg_mem_pd registers in the 3 uarts are all set to 1 mem will enter low power mode.
+ 0
+ 1
+ read-write
+
+
+ RX_SIZE
+ This register is used to configure the amount of mem allocated to receiver's fifo. the default byte num is 128.
+ 3
+ 4
+ read-write
+
+
+ TX_SIZE
+ This register is used to configure the amount of mem allocated to transmitter's fifo.the default byte num is 128.
+ 7
+ 4
+ read-write
+
+
+ RX_FLOW_THRHD_H3
+ refer to the rx_flow_thrhd's describtion.
+ 15
+ 3
+ read-write
+
+
+ RX_TOUT_THRHD_H3
+ refer to the rx_tout_thrhd's describtion.
+ 18
+ 3
+ read-write
+
+
+ XON_THRESHOLD_H2
+ refer to the uart_xon_threshold's describtion.
+ 21
+ 2
+ read-write
+
+
+ XOFF_THRESHOLD_H2
+ refer to the uart_xoff_threshold's describtion.
+ 23
+ 2
+ read-write
+
+
+ RX_MEM_FULL_THRHD
+ refer to the rxfifo_full_thrhd's describtion.
+ 25
+ 3
+ read-write
+
+
+ TX_MEM_EMPTY_THRHD
+ refer to txfifo_empty_thrhd 's describtion.
+ 28
+ 3
+ read-write
+
+
+
+
+ MEM_TX_STATUS
+ 0x5C
+ 0x20
+
+
+ MEM_TX_STATUS
+ 0
+ 24
+ read-only
+
+
+
+
+ MEM_RX_STATUS
+ 0x60
+ 0x20
+
+
+ MEM_RX_STATUS
+ This register stores the current uart rx mem read address and rx mem write address
+ 0
+ 24
+ read-only
+
+
+ MEM_RX_RD_ADDR
+ This register stores the rx mem read address
+ 2
+ 11
+ read-only
+
+
+ MEM_RX_WR_ADDR
+ This register stores the rx mem write address
+ 13
+ 11
+ read-only
+
+
+
+
+ MEM_CNT_STATUS
+ 0x64
+ 0x20
+
+
+ RX_MEM_CNT
+ refer to the rxfifo_cnt's describtion.
+ 0
+ 3
+ read-only
+
+
+ TX_MEM_CNT
+ refer to the txfifo_cnt's describtion.
+ 3
+ 3
+ read-only
+
+
+
+
+ POSPULSE
+ 0x68
+ 0x20
+ 0x000FFFFF
+
+
+ POSEDGE_MIN_CNT
+ This register stores the count of rxd posedge edge. it is used in boudrate-detect process.
+ 0
+ 20
+ read-only
+
+
+
+
+ NEGPULSE
+ 0x6C
+ 0x20
+ 0x000FFFFF
+
+
+ NEGEDGE_MIN_CNT
+ This register stores the count of rxd negedge edge. it is used in boudrate-detect process.
+ 0
+ 20
+ read-only
+
+
+
+
+ DATE
+ 0x78
+ 0x20
+ 0x15122500
+
+
+ DATE
+ 0
+ 32
+ read-write
+
+
+
+
+ ID
+ 0x7C
+ 0x20
+ 0x00000500
+
+
+ ID
+ 0
+ 32
+ read-write
+
+
+
+
+
+
+ UART1
+ UART (Universal Asynchronous Receiver-Transmitter) Controller
+ 0x3FF50000
+
+ UART1
+ 35
+
+
+
+ UART2
+ UART (Universal Asynchronous Receiver-Transmitter) Controller
+ 0x3FF6E000
+
+ UART2
+ 36
+
+
+
+ UHCI0
+ Universal Host Controller Interface
+ UHCI
+ 0x3FF54000
+
+ 0x0
+ 0xC8
+ registers
+
+
+ UHCI0
+ 12
+
+
+
+ CONF0
+ 0x0
+ 0x20
+ 0x00370100
+
+
+ IN_RST
+ Set this bit to reset in link operations.
+ 0
+ 1
+ read-write
+
+
+ OUT_RST
+ Set this bit to reset out link operations.
+ 1
+ 1
+ read-write
+
+
+ AHBM_FIFO_RST
+ Set this bit to reset dma ahb fifo.
+ 2
+ 1
+ read-write
+
+
+ AHBM_RST
+ Set this bit to reset dma ahb interface.
+ 3
+ 1
+ read-write
+
+
+ IN_LOOP_TEST
+ Set this bit to enable loop test for in links.
+ 4
+ 1
+ read-write
+
+
+ OUT_LOOP_TEST
+ Set this bit to enable loop test for out links.
+ 5
+ 1
+ read-write
+
+
+ OUT_AUTO_WRBACK
+ when in link's length is 0 go on to use the next in link automatically.
+ 6
+ 1
+ read-write
+
+
+ OUT_NO_RESTART_CLR
+ don't use
+ 7
+ 1
+ read-write
+
+
+ OUT_EOF_MODE
+ Set this bit to produce eof after DMA pops all data clear this bit to produce eof after DMA pushes all data
+ 8
+ 1
+ read-write
+
+
+ UART0_CE
+ Set this bit to use UART to transmit or receive data.
+ 9
+ 1
+ read-write
+
+
+ UART1_CE
+ Set this bit to use UART1 to transmit or receive data.
+ 10
+ 1
+ read-write
+
+
+ UART2_CE
+ Set this bit to use UART2 to transmit or receive data.
+ 11
+ 1
+ read-write
+
+
+ OUTDSCR_BURST_EN
+ Set this bit to enable DMA in links to use burst mode.
+ 12
+ 1
+ read-write
+
+
+ INDSCR_BURST_EN
+ Set this bit to enable DMA out links to use burst mode.
+ 13
+ 1
+ read-write
+
+
+ OUT_DATA_BURST_EN
+ Set this bit to enable DMA burst MODE
+ 14
+ 1
+ read-write
+
+
+ MEM_TRANS_EN
+ 15
+ 1
+ read-write
+
+
+ SEPER_EN
+ Set this bit to use special char to separate the data frame.
+ 16
+ 1
+ read-write
+
+
+ HEAD_EN
+ Set this bit to enable to use head packet before the data frame.
+ 17
+ 1
+ read-write
+
+
+ CRC_REC_EN
+ Set this bit to enable receiver''s ability of crc calculation when crc_en bit in head packet is 1 then there will be crc bytes after data_frame
+ 18
+ 1
+ read-write
+
+
+ UART_IDLE_EOF_EN
+ Set this bit to enable to use idle time when the idle time after data frame is satisfied this means the end of a data frame.
+ 19
+ 1
+ read-write
+
+
+ LEN_EOF_EN
+ Set this bit to enable to use packet_len in packet head when the received data is equal to packet_len this means the end of a data frame.
+ 20
+ 1
+ read-write
+
+
+ ENCODE_CRC_EN
+ Set this bit to enable crc calculation for data frame when bit6 in the head packet is 1.
+ 21
+ 1
+ read-write
+
+
+ CLK_EN
+ Set this bit to enable clock-gating for read or write registers.
+ 22
+ 1
+ read-write
+
+
+ UART_RX_BRK_EOF_EN
+ Set this bit to enable to use brk char as the end of a data frame.
+ 23
+ 1
+ read-write
+
+
+
+
+ INT_RAW
+ 0x4
+ 0x20
+
+
+ RX_START_INT_RAW
+ when a separator char has been send it will produce uhci_rx_start_int interrupt.
+ 0
+ 1
+ read-only
+
+
+ TX_START_INT_RAW
+ when DMA detects a separator char it will produce uhci_tx_start_int interrupt.
+ 1
+ 1
+ read-only
+
+
+ RX_HUNG_INT_RAW
+ when DMA takes a lot of time to receive a data it will produce uhci_rx_hung_int interrupt.
+ 2
+ 1
+ read-only
+
+
+ TX_HUNG_INT_RAW
+ when DMA takes a lot of time to read a data from RAM it will produce uhci_tx_hung_int interrupt.
+ 3
+ 1
+ read-only
+
+
+ IN_DONE_INT_RAW
+ when a in link descriptor has been completed it will produce uhci_in_done_int interrupt.
+ 4
+ 1
+ read-only
+
+
+ IN_SUC_EOF_INT_RAW
+ when a data packet has been received it will produce uhci_in_suc_eof_int interrupt.
+ 5
+ 1
+ read-only
+
+
+ IN_ERR_EOF_INT_RAW
+ when there are some errors about eof in in link descriptor it will produce uhci_in_err_eof_int interrupt.
+ 6
+ 1
+ read-only
+
+
+ OUT_DONE_INT_RAW
+ when a out link descriptor is completed it will produce uhci_out_done_int interrupt.
+ 7
+ 1
+ read-only
+
+
+ OUT_EOF_INT_RAW
+ when the current descriptor's eof bit is 1 it will produce uhci_out_eof_int interrupt.
+ 8
+ 1
+ read-only
+
+
+ IN_DSCR_ERR_INT_RAW
+ when there are some errors about the out link descriptor it will produce uhci_in_dscr_err_int interrupt.
+ 9
+ 1
+ read-only
+
+
+ OUT_DSCR_ERR_INT_RAW
+ when there are some errors about the in link descriptor it will produce uhci_out_dscr_err_int interrupt.
+ 10
+ 1
+ read-only
+
+
+ IN_DSCR_EMPTY_INT_RAW
+ when there are not enough in links for DMA it will produce uhci_in_dscr_err_int interrupt.
+ 11
+ 1
+ read-only
+
+
+ OUTLINK_EOF_ERR_INT_RAW
+ when there are some errors about eof in outlink descriptor it will produce uhci_outlink_eof_err_int interrupt.
+ 12
+ 1
+ read-only
+
+
+ OUT_TOTAL_EOF_INT_RAW
+ When all data have been send it will produce uhci_out_total_eof_int interrupt.
+ 13
+ 1
+ read-only
+
+
+ SEND_S_Q_INT_RAW
+ When use single send registers to send a short packets it will produce this interrupt when dma has send the short packet.
+ 14
+ 1
+ read-only
+
+
+ SEND_A_Q_INT_RAW
+ When use always_send registers to send a series of short packets it will produce this interrupt when dma has send the short packet.
+ 15
+ 1
+ read-only
+
+
+ DMA_INFIFO_FULL_WM_INT_RAW
+ 16
+ 1
+ read-only
+
+
+
+
+ INT_ST
+ 0x8
+ 0x20
+
+
+ RX_START_INT_ST
+ 0
+ 1
+ read-only
+
+
+ TX_START_INT_ST
+ 1
+ 1
+ read-only
+
+
+ RX_HUNG_INT_ST
+ 2
+ 1
+ read-only
+
+
+ TX_HUNG_INT_ST
+ 3
+ 1
+ read-only
+
+
+ IN_DONE_INT_ST
+ 4
+ 1
+ read-only
+
+
+ IN_SUC_EOF_INT_ST
+ 5
+ 1
+ read-only
+
+
+ IN_ERR_EOF_INT_ST
+ 6
+ 1
+ read-only
+
+
+ OUT_DONE_INT_ST
+ 7
+ 1
+ read-only
+
+
+ OUT_EOF_INT_ST
+ 8
+ 1
+ read-only
+
+
+ IN_DSCR_ERR_INT_ST
+ 9
+ 1
+ read-only
+
+
+ OUT_DSCR_ERR_INT_ST
+ 10
+ 1
+ read-only
+
+
+ IN_DSCR_EMPTY_INT_ST
+ 11
+ 1
+ read-only
+
+
+ OUTLINK_EOF_ERR_INT_ST
+ 12
+ 1
+ read-only
+
+
+ OUT_TOTAL_EOF_INT_ST
+ 13
+ 1
+ read-only
+
+
+ SEND_S_Q_INT_ST
+ 14
+ 1
+ read-only
+
+
+ SEND_A_Q_INT_ST
+ 15
+ 1
+ read-only
+
+
+ DMA_INFIFO_FULL_WM_INT_ST
+ 16
+ 1
+ read-only
+
+
+
+
+ INT_ENA
+ 0xC
+ 0x20
+
+
+ RX_START_INT_ENA
+ 0
+ 1
+ read-write
+
+
+ TX_START_INT_ENA
+ 1
+ 1
+ read-write
+
+
+ RX_HUNG_INT_ENA
+ 2
+ 1
+ read-write
+
+
+ TX_HUNG_INT_ENA
+ 3
+ 1
+ read-write
+
+
+ IN_DONE_INT_ENA
+ 4
+ 1
+ read-write
+
+
+ IN_SUC_EOF_INT_ENA
+ 5
+ 1
+ read-write
+
+
+ IN_ERR_EOF_INT_ENA
+ 6
+ 1
+ read-write
+
+
+ OUT_DONE_INT_ENA
+ 7
+ 1
+ read-write
+
+
+ OUT_EOF_INT_ENA
+ 8
+ 1
+ read-write
+
+
+ IN_DSCR_ERR_INT_ENA
+ 9
+ 1
+ read-write
+
+
+ OUT_DSCR_ERR_INT_ENA
+ 10
+ 1
+ read-write
+
+
+ IN_DSCR_EMPTY_INT_ENA
+ 11
+ 1
+ read-write
+
+
+ OUTLINK_EOF_ERR_INT_ENA
+ 12
+ 1
+ read-write
+
+
+ OUT_TOTAL_EOF_INT_ENA
+ 13
+ 1
+ read-write
+
+
+ SEND_S_Q_INT_ENA
+ 14
+ 1
+ read-write
+
+
+ SEND_A_Q_INT_ENA
+ 15
+ 1
+ read-write
+
+
+ DMA_INFIFO_FULL_WM_INT_ENA
+ 16
+ 1
+ read-write
+
+
+
+
+ INT_CLR
+ 0x10
+ 0x20
+
+
+ RX_START_INT_CLR
+ 0
+ 1
+ write-only
+
+
+ TX_START_INT_CLR
+ 1
+ 1
+ write-only
+
+
+ RX_HUNG_INT_CLR
+ 2
+ 1
+ write-only
+
+
+ TX_HUNG_INT_CLR
+ 3
+ 1
+ write-only
+
+
+ IN_DONE_INT_CLR
+ 4
+ 1
+ write-only
+
+
+ IN_SUC_EOF_INT_CLR
+ 5
+ 1
+ write-only
+
+
+ IN_ERR_EOF_INT_CLR
+ 6
+ 1
+ write-only
+
+
+ OUT_DONE_INT_CLR
+ 7
+ 1
+ write-only
+
+
+ OUT_EOF_INT_CLR
+ 8
+ 1
+ write-only
+
+
+ IN_DSCR_ERR_INT_CLR
+ 9
+ 1
+ write-only
+
+
+ OUT_DSCR_ERR_INT_CLR
+ 10
+ 1
+ write-only
+
+
+ IN_DSCR_EMPTY_INT_CLR
+ 11
+ 1
+ write-only
+
+
+ OUTLINK_EOF_ERR_INT_CLR
+ 12
+ 1
+ write-only
+
+
+ OUT_TOTAL_EOF_INT_CLR
+ 13
+ 1
+ write-only
+
+
+ SEND_S_Q_INT_CLR
+ 14
+ 1
+ write-only
+
+
+ SEND_A_Q_INT_CLR
+ 15
+ 1
+ write-only
+
+
+ DMA_INFIFO_FULL_WM_INT_CLR
+ 16
+ 1
+ write-only
+
+
+
+
+ DMA_OUT_STATUS
+ 0x14
+ 0x20
+ 0x00000002
+
+
+ OUT_FULL
+ 1:DMA out link descriptor's fifo is full.
+ 0
+ 1
+ read-only
+
+
+ OUT_EMPTY
+ 1:DMA in link descriptor's fifo is empty.
+ 1
+ 1
+ read-only
+
+
+
+
+ DMA_OUT_PUSH
+ 0x18
+ 0x20
+
+
+ OUTFIFO_WDATA
+ This is the data need to be pushed into out link descriptor's fifo.
+ 0
+ 9
+ read-write
+
+
+ OUTFIFO_PUSH
+ Set this bit to push data in out link descriptor's fifo.
+ 16
+ 1
+ read-write
+
+
+
+
+ DMA_IN_STATUS
+ 0x1C
+ 0x20
+ 0x00000002
+
+
+ IN_FULL
+ 0
+ 1
+ read-only
+
+
+ IN_EMPTY
+ 1
+ 1
+ read-only
+
+
+ RX_ERR_CAUSE
+ This register stores the errors caused in out link descriptor's data packet.
+ 4
+ 3
+ read-only
+
+
+
+
+ DMA_IN_POP
+ 0x20
+ 0x20
+
+
+ INFIFO_RDATA
+ This register stores the data pop from in link descriptor's fifo.
+ 0
+ 12
+ read-only
+
+
+ INFIFO_POP
+ Set this bit to pop data in in link descriptor's fifo.
+ 16
+ 1
+ read-write
+
+
+
+
+ DMA_OUT_LINK
+ 0x24
+ 0x20
+
+
+ OUTLINK_ADDR
+ This register stores the least 20 bits of the first out link descriptor's address.
+ 0
+ 20
+ read-write
+
+
+ OUTLINK_STOP
+ Set this bit to stop dealing with the out link descriptors.
+ 28
+ 1
+ read-write
+
+
+ OUTLINK_START
+ Set this bit to start dealing with the out link descriptors.
+ 29
+ 1
+ read-write
+
+
+ OUTLINK_RESTART
+ Set this bit to mount on new out link descriptors
+ 30
+ 1
+ read-write
+
+
+ OUTLINK_PARK
+ 1ÂŁÂş the out link descriptor's fsm is in idle state. 0:the out link descriptor's fsm is working.
+ 31
+ 1
+ read-only
+
+
+
+
+ DMA_IN_LINK
+ 0x28
+ 0x20
+ 0x00100000
+
+
+ INLINK_ADDR
+ This register stores the least 20 bits of the first in link descriptor's address.
+ 0
+ 20
+ read-write
+
+
+ INLINK_AUTO_RET
+ 1:when a packet is wrong in link descriptor returns to the descriptor which is lately used.
+ 20
+ 1
+ read-write
+
+
+ INLINK_STOP
+ Set this bit to stop dealing with the in link descriptors.
+ 28
+ 1
+ read-write
+
+
+ INLINK_START
+ Set this bit to start dealing with the in link descriptors.
+ 29
+ 1
+ read-write
+
+
+ INLINK_RESTART
+ Set this bit to mount on new in link descriptors
+ 30
+ 1
+ read-write
+
+
+ INLINK_PARK
+ 1:the in link descriptor's fsm is in idle state. 0:the in link descriptor's fsm is working
+ 31
+ 1
+ read-only
+
+
+
+
+ CONF1
+ 0x2C
+ 0x20
+ 0x00000033
+
+
+ CHECK_SUM_EN
+ Set this bit to enable decoder to check check_sum in packet header.
+ 0
+ 1
+ read-write
+
+
+ CHECK_SEQ_EN
+ Set this bit to enable decoder to check seq num in packet header.
+ 1
+ 1
+ read-write
+
+
+ CRC_DISABLE
+ Set this bit to disable crc calculation.
+ 2
+ 1
+ read-write
+
+
+ SAVE_HEAD
+ Set this bit to save packet header .
+ 3
+ 1
+ read-write
+
+
+ TX_CHECK_SUM_RE
+ Set this bit to enable hardware replace check_sum in packet header automatically.
+ 4
+ 1
+ read-write
+
+
+ TX_ACK_NUM_RE
+ Set this bit to enable hardware replace ack num in packet header automatically.
+ 5
+ 1
+ read-write
+
+
+ CHECK_OWNER
+ Set this bit to check the owner bit in link descriptor.
+ 6
+ 1
+ read-write
+
+
+ WAIT_SW_START
+ Set this bit to enable software way to add packet header.
+ 7
+ 1
+ read-write
+
+
+ SW_START
+ Set this bit to start inserting the packet header.
+ 8
+ 1
+ read-write
+
+
+ DMA_INFIFO_FULL_THRS
+ when data amount in link descriptor's fifo is more than this register value it will produce uhci_dma_infifo_full_wm_int interrupt.
+ 9
+ 12
+ read-write
+
+
+
+
+ STATE0
+ 0x30
+ 0x20
+
+
+ STATE0
+ 0
+ 32
+ read-only
+
+
+
+
+ STATE1
+ 0x34
+ 0x20
+
+
+ STATE1
+ 0
+ 32
+ read-only
+
+
+
+
+ DMA_OUT_EOF_DES_ADDR
+ 0x38
+ 0x20
+
+
+ OUT_EOF_DES_ADDR
+ This register stores the address of out link descriptoir when eof bit in this descriptor is 1.
+ 0
+ 32
+ read-only
+
+
+
+
+ DMA_IN_SUC_EOF_DES_ADDR
+ 0x3C
+ 0x20
+
+
+ IN_SUC_EOF_DES_ADDR
+ This register stores the address of in link descriptor when eof bit in this descriptor is 1.
+ 0
+ 32
+ read-only
+
+
+
+
+ DMA_IN_ERR_EOF_DES_ADDR
+ 0x40
+ 0x20
+
+
+ IN_ERR_EOF_DES_ADDR
+ This register stores the address of in link descriptor when there are some errors in this descriptor.
+ 0
+ 32
+ read-only
+
+
+
+
+ DMA_OUT_EOF_BFR_DES_ADDR
+ 0x44
+ 0x20
+
+
+ OUT_EOF_BFR_DES_ADDR
+ This register stores the address of out link descriptor when there are some errors in this descriptor.
+ 0
+ 32
+ read-only
+
+
+
+
+ AHB_TEST
+ 0x48
+ 0x20
+
+
+ AHB_TESTMODE
+ bit2 is ahb bus test enable ,bit1 is used to choose wrtie(1) or read(0) mode. bit0 is used to choose test only once(1) or continue(0)
+ 0
+ 3
+ read-write
+
+
+ AHB_TESTADDR
+ The two bits represent ahb bus address bit[20:19]
+ 4
+ 2
+ read-write
+
+
+
+
+ DMA_IN_DSCR
+ 0x4C
+ 0x20
+
+
+ INLINK_DSCR
+ The content of current in link descriptor's third dword
+ 0
+ 32
+ read-only
+
+
+
+
+ DMA_IN_DSCR_BF0
+ 0x50
+ 0x20
+
+
+ INLINK_DSCR_BF0
+ The content of current in link descriptor's first dword
+ 0
+ 32
+ read-only
+
+
+
+
+ DMA_IN_DSCR_BF1
+ 0x54
+ 0x20
+
+
+ INLINK_DSCR_BF1
+ The content of current in link descriptor's second dword
+ 0
+ 32
+ read-only
+
+
+
+
+ DMA_OUT_DSCR
+ 0x58
+ 0x20
+
+
+ OUTLINK_DSCR
+ The content of current out link descriptor's third dword
+ 0
+ 32
+ read-only
+
+
+
+
+ DMA_OUT_DSCR_BF0
+ 0x5C
+ 0x20
+
+
+ OUTLINK_DSCR_BF0
+ The content of current out link descriptor's first dword
+ 0
+ 32
+ read-only
+
+
+
+
+ DMA_OUT_DSCR_BF1
+ 0x60
+ 0x20
+
+
+ OUTLINK_DSCR_BF1
+ The content of current out link descriptor's second dword
+ 0
+ 32
+ read-only
+
+
+
+
+ ESCAPE_CONF
+ 0x64
+ 0x20
+ 0x00000033
+
+
+ TX_C0_ESC_EN
+ Set this bit to enable 0xc0 char decode when DMA receives data.
+ 0
+ 1
+ read-write
+
+
+ TX_DB_ESC_EN
+ Set this bit to enable 0xdb char decode when DMA receives data.
+ 1
+ 1
+ read-write
+
+
+ TX_11_ESC_EN
+ Set this bit to enable flow control char 0x11 decode when DMA receives data.
+ 2
+ 1
+ read-write
+
+
+ TX_13_ESC_EN
+ Set this bit to enable flow control char 0x13 decode when DMA receives data.
+ 3
+ 1
+ read-write
+
+
+ RX_C0_ESC_EN
+ Set this bit to enable 0xc0 char replace when DMA sends data.
+ 4
+ 1
+ read-write
+
+
+ RX_DB_ESC_EN
+ Set this bit to enable 0xdb char replace when DMA sends data.
+ 5
+ 1
+ read-write
+
+
+ RX_11_ESC_EN
+ Set this bit to enable flow control char 0x11 replace when DMA sends data.
+ 6
+ 1
+ read-write
+
+
+ RX_13_ESC_EN
+ Set this bit to enable flow control char 0x13 replace when DMA sends data.
+ 7
+ 1
+ read-write
+
+
+
+
+ HUNG_CONF
+ 0x68
+ 0x20
+ 0x00810810
+
+
+ TXFIFO_TIMEOUT
+ This register stores the timeout value.when DMA takes more time than this register value to receive a data it will produce uhci_tx_hung_int interrupt.
+ 0
+ 8
+ read-write
+
+
+ TXFIFO_TIMEOUT_SHIFT
+ The tick count is cleared when its value >=(17'd8000>>reg_txfifo_timeout_shift)
+ 8
+ 3
+ read-write
+
+
+ TXFIFO_TIMEOUT_ENA
+ The enable bit for txfifo receive data timeout
+ 11
+ 1
+ read-write
+
+
+ RXFIFO_TIMEOUT
+ This register stores the timeout value.when DMA takes more time than this register value to read a data from RAM it will produce uhci_rx_hung_int interrupt.
+ 12
+ 8
+ read-write
+
+
+ RXFIFO_TIMEOUT_SHIFT
+ The tick count is cleared when its value >=(17'd8000>>reg_rxfifo_timeout_shift)
+ 20
+ 3
+ read-write
+
+
+ RXFIFO_TIMEOUT_ENA
+ This is the enable bit for DMA send data timeout
+ 23
+ 1
+ read-write
+
+
+
+
+ ACK_NUM
+ 0x6C
+ 0x20
+
+
+ RX_HEAD
+ 0x70
+ 0x20
+
+
+ RX_HEAD
+ This register stores the packet header received by DMA
+ 0
+ 32
+ read-only
+
+
+
+
+ QUICK_SENT
+ 0x74
+ 0x20
+
+
+ SINGLE_SEND_NUM
+ The bits are used to choose which short packet
+ 0
+ 3
+ read-write
+
+
+ SINGLE_SEND_EN
+ Set this bit to enable send a short packet
+ 3
+ 1
+ read-write
+
+
+ ALWAYS_SEND_NUM
+ The bits are used to choose which short packet
+ 4
+ 3
+ read-write
+
+
+ ALWAYS_SEND_EN
+ Set this bit to enable continuously send the same short packet
+ 7
+ 1
+ read-write
+
+
+
+
+ Q0_WORD0
+ 0x78
+ 0x20
+
+
+ SEND_Q0_WORD0
+ This register stores the content of short packet's first dword
+ 0
+ 32
+ read-write
+
+
+
+
+ Q0_WORD1
+ 0x7C
+ 0x20
+
+
+ SEND_Q0_WORD1
+ This register stores the content of short packet's second dword
+ 0
+ 32
+ read-write
+
+
+
+
+ Q1_WORD0
+ 0x80
+ 0x20
+
+
+ SEND_Q1_WORD0
+ This register stores the content of short packet's first dword
+ 0
+ 32
+ read-write
+
+
+
+
+ Q1_WORD1
+ 0x84
+ 0x20
+
+
+ SEND_Q1_WORD1
+ This register stores the content of short packet's second dword
+ 0
+ 32
+ read-write
+
+
+
+
+ Q2_WORD0
+ 0x88
+ 0x20
+
+
+ SEND_Q2_WORD0
+ This register stores the content of short packet's first dword
+ 0
+ 32
+ read-write
+
+
+
+
+ Q2_WORD1
+ 0x8C
+ 0x20
+
+
+ SEND_Q2_WORD1
+ This register stores the content of short packet's second dword
+ 0
+ 32
+ read-write
+
+
+
+
+ Q3_WORD0
+ 0x90
+ 0x20
+
+
+ SEND_Q3_WORD0
+ This register stores the content of short packet's first dword
+ 0
+ 32
+ read-write
+
+
+
+
+ Q3_WORD1
+ 0x94
+ 0x20
+
+
+ SEND_Q3_WORD1
+ This register stores the content of short packet's second dword
+ 0
+ 32
+ read-write
+
+
+
+
+ Q4_WORD0
+ 0x98
+ 0x20
+
+
+ SEND_Q4_WORD0
+ This register stores the content of short packet's first dword
+ 0
+ 32
+ read-write
+
+
+
+
+ Q4_WORD1
+ 0x9C
+ 0x20
+
+
+ SEND_Q4_WORD1
+ This register stores the content of short packet's second dword
+ 0
+ 32
+ read-write
+
+
+
+
+ Q5_WORD0
+ 0xA0
+ 0x20
+
+
+ SEND_Q5_WORD0
+ This register stores the content of short packet's first dword
+ 0
+ 32
+ read-write
+
+
+
+
+ Q5_WORD1
+ 0xA4
+ 0x20
+
+
+ SEND_Q5_WORD1
+ This register stores the content of short packet's second dword
+ 0
+ 32
+ read-write
+
+
+
+
+ Q6_WORD0
+ 0xA8
+ 0x20
+
+
+ SEND_Q6_WORD0
+ This register stores the content of short packet's first dword
+ 0
+ 32
+ read-write
+
+
+
+
+ Q6_WORD1
+ 0xAC
+ 0x20
+
+
+ SEND_Q6_WORD1
+ This register stores the content of short packet's second dword
+ 0
+ 32
+ read-write
+
+
+
+
+ ESC_CONF0
+ 0xB0
+ 0x20
+ 0x00DCDBC0
+
+
+ SEPER_CHAR
+ This register stores the seperator char seperator char is used to seperate the data frame.
+ 0
+ 8
+ read-write
+
+
+ SEPER_ESC_CHAR0
+ This register stores thee first char used to replace seperator char in data.
+ 8
+ 8
+ read-write
+
+
+ SEPER_ESC_CHAR1
+ This register stores the second char used to replace seperator char in data . 0xdc 0xdb replace 0xc0 by default.
+ 16
+ 8
+ read-write
+
+
+
+
+ ESC_CONF1
+ 0xB4
+ 0x20
+ 0x00DDDBDB
+
+
+ ESC_SEQ0
+ This register stores the first substitute char used to replace the seperator char.
+ 0
+ 8
+ read-write
+
+
+ ESC_SEQ0_CHAR0
+ This register stores the first char used to replace reg_esc_seq0 in data.
+ 8
+ 8
+ read-write
+
+
+ ESC_SEQ0_CHAR1
+ This register stores the second char used to replace the reg_esc_seq0 in data
+ 16
+ 8
+ read-write
+
+
+
+
+ ESC_CONF2
+ 0xB8
+ 0x20
+ 0x00DEDB11
+
+
+ ESC_SEQ1
+ This register stores the flow control char to turn on the flow_control
+ 0
+ 8
+ read-write
+
+
+ ESC_SEQ1_CHAR0
+ This register stores the first char used to replace the reg_esc_seq1 in data.
+ 8
+ 8
+ read-write
+
+
+ ESC_SEQ1_CHAR1
+ This register stores the second char used to replace the reg_esc_seq1 in data.
+ 16
+ 8
+ read-write
+
+
+
+
+ ESC_CONF3
+ 0xBC
+ 0x20
+ 0x00DFDB13
+
+
+ ESC_SEQ2
+ This register stores the flow_control char to turn off the flow_control
+ 0
+ 8
+ read-write
+
+
+ ESC_SEQ2_CHAR0
+ This register stores the first char used to replace the reg_esc_seq2 in data.
+ 8
+ 8
+ read-write
+
+
+ ESC_SEQ2_CHAR1
+ This register stores the second char used to replace the reg_esc_seq2 in data.
+ 16
+ 8
+ read-write
+
+
+
+
+ PKT_THRES
+ 0xC0
+ 0x20
+ 0x00000080
+
+
+ PKT_THRS
+ when the amount of packet payload is greater than this value the process of receiving data is done.
+ 0
+ 13
+ read-write
+
+
+
+
+ DATE
+ 0xFC
+ 0x20
+ 0x16041001
+
+
+ DATE
+ version information
+ 0
+ 32
+ read-write
+
+
+
+
+
+
+ UHCI1
+ Universal Host Controller Interface
+ 0x3FF4C000
+
+ UHCI1
+ 13
+
+
+
+
\ No newline at end of file
diff --git a/src/debug_custom.json b/src/debug_custom.json
new file mode 100644
index 0000000..4dbe431
--- /dev/null
+++ b/src/debug_custom.json
@@ -0,0 +1,19 @@
+{
+ "name":"Arduino on ESP32",
+ "toolchainPrefix":"xtensa-esp32-elf",
+ "svdFile":"debug.svd",
+ "request":"attach",
+ "postAttachCommands":[
+ "set remote hardware-watchpoint-limit 2",
+ "monitor reset halt",
+ "monitor gdb_sync",
+ "thb setup",
+ "c"
+ ],
+ "overrideRestartCommands":[
+ "monitor reset halt",
+ "monitor gdb_sync",
+ "thb setup",
+ "c"
+ ]
+}
\ No newline at end of file
diff --git a/src/detect.cpp b/src/detect.cpp
new file mode 100644
index 0000000..54a0646
--- /dev/null
+++ b/src/detect.cpp
@@ -0,0 +1,169 @@
+#include
+#include
+// Similar to https://github.com/Levi--G/IMU-WhoAmIVerifier
+
+//Do be aware that MPU9150's will report as 6050s, this is because a 9150 is a 6050 with a magnetometer
+//if you have a 9250 board and it reports as a 6050, it's most likely a 9150.
+
+//This code will check for an IMU when reset and, if one is found, it will report what it is.
+//To re run the check without resetting the Arduino, pull pin 4 to GND.
+
+#define NUM_IMUS 40
+
+bool errorflag;
+
+typedef struct IMU {
+ uint8_t Address1;
+ uint8_t Address2;
+ uint8_t Register;
+ uint8_t ExpectedID;
+ const char* IMUName PROGMEM;
+ const char* IMUCapabilities PROGMEM;
+ bool LibSupported;
+};
+
+const IMU IMUList[NUM_IMUS] =
+{
+ {0x68, 0x69, 0x75, 0x68, "MPU6050", "3A,3G", true},
+ {0x68, 0x69, 0x75, 0x70, "MPU6500", "3A,3G", true},
+ {0x68, 0x69, 0x75, 0x74, "MPU6515", "3A,3G", true},
+ {0x68, 0x69, 0x75, 0x19, "MPU6886", "3A,3G", true},
+ {0x68, 0x69, 0x75, 0x71, "MPU9250", "3A,3G,3M", true},
+ {0x68, 0x69, 0x75, 0x73, "MPU9255", "3A,3G,3M", true},
+ {0x69, 0x68, 0x00, 0xD1, "BMI160", "3A,3G", true},
+ {0x6B, 0x6A, 0x0F, 0x69, "LSM6DS3", "3A,3G", true},
+ {0x6B, 0x6A, 0x0F, 0x6A, "LSM6DSL", "3A,3G", true},
+ {0x68, 0x69, 0x75, 0x98, "ICM20689", "3A,3G", true},
+ {0x68, 0x69, 0x75, 0x20, "ICM20690", "3A,3G", true},
+ {0x6B, 0x6A, 0x00, 0x05, "QMI8658", "3A,3G", true},
+ {0x18, 0x19, 0x00, 0xFA, "BMI055 or BMX055", "3A,3G or 3A,3G,3M", true},
+ {0x0D, 0x0D, 0x0D, 0xFF, "QMC5883L", "3M", true},
+ {0x68, 0x69, 0x75, 0x75, "Unknown or fake Invensense IMU, use 'IMU_Generic'", "3A,3G, possibly 3M?", true},
+ {0x6B, 0x6A, 0x0F, 0x6B, "LSM6DSR", "3A,3G", false},
+ {0x6B, 0x6A, 0x0F, 0x6C, "LSM6DSO", "3A,3G", false},
+ {0x6B, 0x6A, 0x00, 0xFC, "QMI8610", "3A,3G", false},
+ {0x68, 0x69, 0x75, 0x92, "ICG20330", "3G", false},
+ {0x68, 0x69, 0x75, 0xB5, "IAM20380", "3A", false},
+ {0x68, 0x69, 0x75, 0xB6, "IAM20381", "3G", false},
+ {0x68, 0x69, 0x75, 0x11, "ICM20600", "3A,3G", false},
+ {0x68, 0x69, 0x75, 0xAC, "ICM20601", "3A,3G", false},
+ {0x68, 0x69, 0x75, 0x12, "ICM20602", "3A,3G", false},
+ {0x68, 0x69, 0x75, 0xAF, "ICM20608-G", "3A,3G", false},
+ {0x68, 0x69, 0x75, 0xA6, "ICM20609", "3A,3G", false},
+ {0x68, 0x69, 0x00, 0xE0, "ICM20648", "3A,3G", false},
+ {0x68, 0x69, 0x00, 0xE1, "ICM20649", "3A,3G", false},
+ {0x68, 0x69, 0x75, 0xA9, "ICG20660", "3A,3G", false},
+ {0x68, 0x69, 0x75, 0x91, "IAM20680", "3A,3G", false},
+ {0x68, 0x69, 0x00, 0xEA, "ICM20948", "3A,3G,3M", false},
+ {0x68, 0x69, 0x75, 0x6C, "IIM42351", "3A", false},
+ {0x68, 0x69, 0x75, 0x6D, "IIM42352", "3A", false},
+ {0x68, 0x69, 0x75, 0x4E, "ICM40627", "3A,3G", false},
+ {0x68, 0x69, 0x75, 0x42, "ICM42605", "3A,3G", false},
+ {0x68, 0x69, 0x75, 0x6F, "IIM42652", "3A,3G", false},
+ {0x68, 0x69, 0x75, 0x67, "ICM42670-P", "3A,3G", false},
+ {0x68, 0x69, 0x75, 0xDB, "ICM42688-V", "3A,3G", false},
+ {0x68, 0x69, 0x00, 0x68, "MPU3050", "3G", false},
+ {0x1E, 0x1E, 0x0C, 0x33, "HMC5883L", "3M", false},
+};
+
+void setup() {
+ Serial.begin(9600);
+ while (!Serial) ;
+ errorflag = false;
+ pinMode(4, INPUT_PULLUP);
+ Wire.begin();
+#ifdef WIRE_HAS_TIMEOUT
+ Wire.setWireTimeout(3000);
+#endif
+ Serial.println(F("\n=========== IMU Identifier ==========="));
+}
+
+uint8_t readByte(uint8_t address, uint8_t subAddress)
+{
+ uint8_t data; // `data` will store the register data
+ Wire.beginTransmission(address); // Initialize the Tx buffer
+ Wire.write(subAddress); // Put slave register address in Tx buffer
+ int i = Wire.endTransmission(false); // Send the Tx buffer, but send a restart to keep connection alive
+ if (i == 5) {
+ return 0;
+ errorflag = true;
+ }
+ i = Wire.requestFrom(address, (uint8_t) 1, true); // Read one byte from slave register address
+ if (i == 0) {
+ return 0;
+ errorflag = true;
+ }
+ if (Wire.available()) {
+ data = Wire.read(); // Fill Rx buffer with result
+ }
+ return data; // Return data read from slave register
+}
+
+void loop() {
+ static int a = 0;
+ while (digitalRead(4) && a != 0) ; //do once
+ a = 1;
+ bool detected = false;
+ for (int i = 0; i < NUM_IMUS; i++)
+ {
+#ifdef WIRE_HAS_TIMEOUT
+ if (errorflag || Wire.getWireTimeoutFlag()) {
+ Serial.print(F("Error while reading address 0x"));
+ Serial.print(IMUList[i].Address1, HEX);
+ Serial.print(F(": "));
+ if (Wire.getWireTimeoutFlag()) {
+ Serial.println(F("I2C bus timed out. (Bad IMU? check wiring.)"));
+ }
+ else {
+ Serial.println(F("Unknown error while reading/writing"));
+ }
+ Serial.println(F("======================================"));
+ Wire.clearWireTimeoutFlag();
+ errorflag = false;
+ delay(2000);
+ return;
+ }
+#endif
+ if (readByte(IMUList[i].Address1, IMUList[i].Register) == IMUList[i].ExpectedID)
+ {
+ detected = true;
+ Serial.print(F("IMU Found: "));
+ Serial.print(IMUList[i].IMUName);
+ Serial.print(F(" On address: 0x"));
+ Serial.println(IMUList[i].Address1, HEX);
+ Serial.print(F("This IMU is capable of the following axis: "));
+ Serial.println(IMUList[i].IMUCapabilities);
+ if (IMUList[i].LibSupported) {
+ Serial.println(F("This IMU is supported by the FastIMU library."));
+ }
+ else
+ {
+ Serial.println(F("This IMU is not supported by the FastIMU library."));
+ }
+ Serial.println(F("======================================"));
+ }
+ else if (readByte(IMUList[i].Address2, IMUList[i].Register) == IMUList[i].ExpectedID)
+ {
+ detected = true;
+ Serial.print(F("IMU Found: "));
+ Serial.print(IMUList[i].IMUName);
+ Serial.print(F(" On address: 0x"));
+ Serial.println(IMUList[i].Address2, HEX);
+ Serial.print(F("This IMU is capable of the following axis: "));
+ Serial.println(IMUList[i].IMUCapabilities);
+ if (IMUList[i].LibSupported) {
+ Serial.println(F("This IMU is supported by the FastIMU library."));
+ }
+ else
+ {
+ Serial.println(F(" This IMU is not supported by the FastIMU library."));
+ }
+ Serial.println(F("======================================"));
+ }
+ }
+ if (!detected) {
+ Serial.println(F("No IMU detected"));
+ Serial.println(F("======================================"));
+ }
+ delay(1000);
+}
diff --git a/src/kalibracija.cpp b/src/kalibracija.cpp
new file mode 100644
index 0000000..8d7d36d
--- /dev/null
+++ b/src/kalibracija.cpp
@@ -0,0 +1,364 @@
+// MPU6050 offset-finder, based on Jeff Rowberg's MPU6050_RAW
+// 2016-10-19 by Robert R. Fenichel (bob@fenichel.net)
+
+// I2C device class (I2Cdev) demonstration Arduino sketch for MPU6050 class
+// 10/7/2011 by Jeff Rowberg
+// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
+//
+// Changelog:
+// 2019-07-11 - added PID offset generation at begninning Generates first offsets
+// - in @ 6 seconds and completes with 4 more sets @ 10 seconds
+// - then continues with origional 2016 calibration code.
+// 2016-11-25 - added delays to reduce sampling rate to ~200 Hz
+// added temporizing printing during long computations
+// 2016-10-25 - requires inequality (Low < Target, High > Target) during expansion
+// dynamic speed change when closing in
+// 2016-10-22 - cosmetic changes
+// 2016-10-19 - initial release of IMU_Zero
+// 2013-05-08 - added multiple output formats
+// - added seamless Fastwire support
+// 2011-10-07 - initial release of MPU6050_RAW
+
+/* ============================================
+I2Cdev device library code is placed under the MIT license
+Copyright (c) 2011 Jeff Rowberg
+
+Permission is hereby granted, free of charge, to any person obtaining a copy
+of this software and associated documentation files (the "Software"), to deal
+in the Software without restriction, including without limitation the rights
+to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+copies of the Software, and to permit persons to whom the Software is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in
+all copies or substantial portions of the Software.
+
+THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+THE SOFTWARE.
+
+ If an MPU6050
+ * is an ideal member of its tribe,
+ * is properly warmed up,
+ * is at rest in a neutral position,
+ * is in a location where the pull of gravity is exactly 1g, and
+ * has been loaded with the best possible offsets,
+then it will report 0 for all accelerations and displacements, except for
+Z acceleration, for which it will report 16384 (that is, 2^14). Your device
+probably won't do quite this well, but good offsets will all get the baseline
+outputs close to these target values.
+
+ Put the MPU6050 on a flat and horizontal surface, and leave it operating for
+5-10 minutes so its temperature gets stabilized.
+
+ Run this program. A "----- done -----" line will indicate that it has done its best.
+With the current accuracy-related constants (NFast = 1000, NSlow = 10000), it will take
+a few minutes to get there.
+
+ Along the way, it will generate a dozen or so lines of output, showing that for each
+of the 6 desired offsets, it is
+ * first, trying to find two estimates, one too low and one too high, and
+ * then, closing in until the bracket can't be made smaller.
+
+ The line just above the "done" line will look something like
+ [567,567] --> [-1,2] [-2223,-2223] --> [0,1] [1131,1132] --> [16374,16404] [155,156] --> [-1,1] [-25,-24] --> [0,3] [5,6] --> [0,4]
+As will have been shown in interspersed header lines, the six groups making up this
+line describe the optimum offsets for the X acceleration, Y acceleration, Z acceleration,
+X gyro, Y gyro, and Z gyro, respectively. In the sample shown just above, the trial showed
+that +567 was the best offset for the X acceleration, -2223 was best for Y acceleration,
+and so on.
+
+ The need for the delay between readings (usDelay) was brought to my attention by Nikolaus Doppelhammer.
+===============================================
+*/
+
+// I2Cdev and MPU6050 must be installed as libraries, or else the .cpp/.h files
+// for both classes must be in the include path of your project
+#include
+#include "I2Cdev.h"
+#include "MPU6050.h"
+
+// I2C MPU6050
+#define SDApin 1
+#define SCLpin 3
+
+// Arduino Wire library is required if I2Cdev I2CDEV_ARDUINO_WIRE implementation
+// is used in I2Cdev.h
+#if I2CDEV_IMPLEMENTATION == I2CDEV_ARDUINO_WIRE
+ #include "Wire.h"
+#endif
+
+// class default I2C address is 0x68
+// specific I2C addresses may be passed as a parameter here
+// AD0 low = 0x68 (default for InvenSense evaluation board)
+// AD0 high = 0x69
+MPU6050 accelgyro;
+//MPU6050 accelgyro(0x69); // <-- use for AD0 high
+
+
+const char LBRACKET = '[';
+const char RBRACKET = ']';
+const char COMMA = ',';
+const char BLANK = ' ';
+const char PERIOD = '.';
+
+const int iAx = 0;
+const int iAy = 1;
+const int iAz = 2;
+const int iGx = 3;
+const int iGy = 4;
+const int iGz = 5;
+
+const int usDelay = 3150; // empirical, to hold sampling to 200 Hz
+const int NFast = 1000; // the bigger, the better (but slower)
+const int NSlow = 10000; // ..
+const int LinesBetweenHeaders = 5;
+ int LowValue[6];
+ int HighValue[6];
+ int Smoothed[6];
+ int LowOffset[6];
+ int HighOffset[6];
+ int Target[6];
+ int LinesOut;
+ int N;
+
+void ForceHeader()
+ { LinesOut = 99; }
+
+void SetAveraging(int NewN)
+ { N = NewN;
+ Serial.print("averaging ");
+ Serial.print(N);
+ Serial.println(" readings each time");
+ } // SetAveraging
+
+
+void GetSmoothed()
+ { int16_t RawValue[6];
+ int i;
+ long Sums[6];
+ for (i = iAx; i <= iGz; i++)
+ { Sums[i] = 0; }
+// unsigned long Start = micros();
+
+ for (i = 1; i <= N; i++)
+ { // get sums
+ accelgyro.getMotion6(&RawValue[iAx], &RawValue[iAy], &RawValue[iAz],
+ &RawValue[iGx], &RawValue[iGy], &RawValue[iGz]);
+ if ((i % 500) == 0)
+ Serial.print(PERIOD);
+ delayMicroseconds(usDelay);
+ for (int j = iAx; j <= iGz; j++)
+ Sums[j] = Sums[j] + RawValue[j];
+ } // get sums
+// unsigned long usForN = micros() - Start;
+// Serial.print(" reading at ");
+// Serial.print(1000000/((usForN+N/2)/N));
+// Serial.println(" Hz");
+ for (i = iAx; i <= iGz; i++)
+ { Smoothed[i] = (Sums[i] + N/2) / N ; }
+ } // GetSmoothed
+
+void Initialize()
+ {
+ // join I2C bus (I2Cdev library doesn't do this automatically)
+ #if I2CDEV_IMPLEMENTATION == I2CDEV_ARDUINO_WIRE
+ Wire.begin(SDApin, SCLpin);
+ #elif I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_FASTWIRE
+ Fastwire::setup(400, true);
+ #endif
+
+ Serial.begin(9600);
+
+ // initialize device
+ Serial.println("Initializing I2C devices...");
+ accelgyro.initialize();
+
+ // verify connection
+ Serial.println("Testing device connections...");
+ Serial.println(accelgyro.testConnection() ? "MPU6050 connection successful" : "MPU6050 connection failed");
+ Serial.println("PID tuning Each Dot = 100 readings");
+ /*A tidbit on how PID (PI actually) tuning works.
+ When we change the offset in the MPU6050 we can get instant results. This allows us to use Proportional and
+ integral of the PID to discover the ideal offsets. Integral is the key to discovering these offsets, Integral
+ uses the error from set-point (set-point is zero), it takes a fraction of this error (error * ki) and adds it
+ to the integral value. Each reading narrows the error down to the desired offset. The greater the error from
+ set-point, the more we adjust the integral value. The proportional does its part by hiding the noise from the
+ integral math. The Derivative is not used because of the noise and because the sensor is stationary. With the
+ noise removed the integral value lands on a solid offset after just 600 readings. At the end of each set of 100
+ readings, the integral value is used for the actual offsets and the last proportional reading is ignored due to
+ the fact it reacts to any noise.
+ */
+ accelgyro.CalibrateAccel(6);
+ accelgyro.CalibrateGyro(6);
+ Serial.println("\nat 600 Readings");
+ accelgyro.PrintActiveOffsets();
+ Serial.println();
+ accelgyro.CalibrateAccel(1);
+ accelgyro.CalibrateGyro(1);
+ Serial.println("700 Total Readings");
+ accelgyro.PrintActiveOffsets();
+ Serial.println();
+ accelgyro.CalibrateAccel(1);
+ accelgyro.CalibrateGyro(1);
+ Serial.println("800 Total Readings");
+ accelgyro.PrintActiveOffsets();
+ Serial.println();
+ accelgyro.CalibrateAccel(1);
+ accelgyro.CalibrateGyro(1);
+ Serial.println("900 Total Readings");
+ accelgyro.PrintActiveOffsets();
+ Serial.println();
+ accelgyro.CalibrateAccel(1);
+ accelgyro.CalibrateGyro(1);
+ Serial.println("1000 Total Readings");
+ accelgyro.PrintActiveOffsets();
+ Serial.println("\n\n Any of the above offsets will work nice \n\n Lets proof the PID tuning using another method:");
+ } // Initialize
+
+void SetOffsets(int TheOffsets[6])
+ { accelgyro.setXAccelOffset(TheOffsets [iAx]);
+ accelgyro.setYAccelOffset(TheOffsets [iAy]);
+ accelgyro.setZAccelOffset(TheOffsets [iAz]);
+ accelgyro.setXGyroOffset (TheOffsets [iGx]);
+ accelgyro.setYGyroOffset (TheOffsets [iGy]);
+ accelgyro.setZGyroOffset (TheOffsets [iGz]);
+ } // SetOffsets
+
+void ShowProgress()
+ { if (LinesOut >= LinesBetweenHeaders)
+ { // show header
+ Serial.println("\tXAccel\t\t\tYAccel\t\t\t\tZAccel\t\t\tXGyro\t\t\tYGyro\t\t\tZGyro");
+ LinesOut = 0;
+ } // show header
+ Serial.print(BLANK);
+ for (int i = iAx; i <= iGz; i++)
+ { Serial.print(LBRACKET);
+ Serial.print(LowOffset[i]),
+ Serial.print(COMMA);
+ Serial.print(HighOffset[i]);
+ Serial.print("] --> [");
+ Serial.print(LowValue[i]);
+ Serial.print(COMMA);
+ Serial.print(HighValue[i]);
+ if (i == iGz)
+ { Serial.println(RBRACKET); }
+ else
+ { Serial.print("]\t"); }
+ }
+ LinesOut++;
+ } // ShowProgress
+
+void PullBracketsIn()
+ { boolean AllBracketsNarrow;
+ boolean StillWorking;
+ int NewOffset[6];
+
+ Serial.println("\nclosing in:");
+ AllBracketsNarrow = false;
+ ForceHeader();
+ StillWorking = true;
+ while (StillWorking)
+ { StillWorking = false;
+ if (AllBracketsNarrow && (N == NFast))
+ { SetAveraging(NSlow); }
+ else
+ { AllBracketsNarrow = true; }// tentative
+ for (int i = iAx; i <= iGz; i++)
+ { if (HighOffset[i] <= (LowOffset[i]+1))
+ { NewOffset[i] = LowOffset[i]; }
+ else
+ { // binary search
+ StillWorking = true;
+ NewOffset[i] = (LowOffset[i] + HighOffset[i]) / 2;
+ if (HighOffset[i] > (LowOffset[i] + 10))
+ { AllBracketsNarrow = false; }
+ } // binary search
+ }
+ SetOffsets(NewOffset);
+ GetSmoothed();
+ for (int i = iAx; i <= iGz; i++)
+ { // closing in
+ if (Smoothed[i] > Target[i])
+ { // use lower half
+ HighOffset[i] = NewOffset[i];
+ HighValue[i] = Smoothed[i];
+ } // use lower half
+ else
+ { // use upper half
+ LowOffset[i] = NewOffset[i];
+ LowValue[i] = Smoothed[i];
+ } // use upper half
+ } // closing in
+ ShowProgress();
+ } // still working
+
+ } // PullBracketsIn
+
+void PullBracketsOut()
+ { boolean Done = false;
+ int NextLowOffset[6];
+ int NextHighOffset[6];
+
+ Serial.println("expanding:");
+ ForceHeader();
+
+ while (!Done)
+ { Done = true;
+ SetOffsets(LowOffset);
+ GetSmoothed();
+ for (int i = iAx; i <= iGz; i++)
+ { // got low values
+ LowValue[i] = Smoothed[i];
+ if (LowValue[i] >= Target[i])
+ { Done = false;
+ NextLowOffset[i] = LowOffset[i] - 1000;
+ }
+ else
+ { NextLowOffset[i] = LowOffset[i]; }
+ } // got low values
+
+ SetOffsets(HighOffset);
+ GetSmoothed();
+ for (int i = iAx; i <= iGz; i++)
+ { // got high values
+ HighValue[i] = Smoothed[i];
+ if (HighValue[i] <= Target[i])
+ { Done = false;
+ NextHighOffset[i] = HighOffset[i] + 1000;
+ }
+ else
+ { NextHighOffset[i] = HighOffset[i]; }
+ } // got high values
+ ShowProgress();
+ for (int i = iAx; i <= iGz; i++)
+ { LowOffset[i] = NextLowOffset[i]; // had to wait until ShowProgress done
+ HighOffset[i] = NextHighOffset[i]; // ..
+ }
+ } // keep going
+ } // PullBracketsOut
+
+void setup()
+ { Initialize();
+ for (int i = iAx; i <= iGz; i++)
+ { // set targets and initial guesses
+ Target[i] = 0; // must fix for ZAccel
+ HighOffset[i] = 0;
+ LowOffset[i] = 0;
+ } // set targets and initial guesses
+ Target[iAz] = 16384;
+ SetAveraging(NFast);
+
+ PullBracketsOut();
+ PullBracketsIn();
+
+ Serial.println("-------------- done --------------");
+ } // setup
+
+void loop()
+ {
+ } // loop
diff --git a/src/main.cpp b/src/main.cpp
new file mode 100644
index 0000000..d686a6b
--- /dev/null
+++ b/src/main.cpp
@@ -0,0 +1,267 @@
+#include "Wire.h"
+#include "MPU6050_6Axis_MotionApps612.h"
+#include
+
+// I2C MPU6050
+#define SDApin 1
+#define SCLpin 3
+
+// RGB LED
+#define NUMPIXELS 1
+#define PIXELPIN 18
+
+// ID kegla mora bit unikaten za vsakega! (se poslje poleg parametrov)
+#define SENZOR_ID 1
+
+// Stanje baterije
+#define BATTERYPIN 8
+
+#include
+#include
+
+uint8_t sprejemnikMac[] = {0x08, 0x3A, 0xF2, 0x50, 0xEF, 0x6C };
+
+typedef struct sensor_msg {
+ uint8_t id;
+ /*
+ float aX;
+ float aY;
+ float aZ;
+ */
+ float qX;
+ float qY;
+ float qZ;
+ float qW;
+ double bat;
+} sensor_msg;
+
+sensor_msg odcitek;
+esp_now_peer_info_t peerInfo;
+
+
+// Motion sensor object
+MPU6050 mpu;
+
+// MPU control/status vars
+bool dmpReady = false; // set true if DMP init was successful
+uint8_t mpuIntStatus; // holds actual interrupt status byte from MPU
+uint8_t devStatus; // return status after each device operation (0 = success, !0 = error)
+uint16_t packetSize; // expected DMP packet size (default is 42 bytes)
+uint16_t fifoCount; // count of all bytes currently in FIFO
+uint8_t fifoBuffer[64]; // FIFO storage buffer
+
+// orientation/motion vars
+Quaternion q; // [w, x, y, z] quaternion container
+Quaternion pq; // [w, x, y, z] previous quaternion container
+Quaternion diff; // [w, x, y, z] quaternion derivate container
+Quaternion cq; // [w, x, y, z] calibration quaternion
+VectorInt16 aa; // [x, y, z] accel sensor measurements
+VectorInt16 gy; // [x, y, z] gyro sensor measurements
+VectorInt16 aaReal; // [x, y, z] gravity-free accel sensor measurements
+VectorFloat gravity; // [x, y, z] gravity vector
+float ypr[3];
+
+// Neopixel!
+Adafruit_NeoPixel pixels(NUMPIXELS, PIXELPIN, NEO_GRB + NEO_KHZ800);
+
+int cas = 0;
+
+void setup() {
+ Serial.begin(115200); // set this as high as you can reliably run on your platform
+
+ Serial.print("Gravitacija perspektive senzor init ");
+ Serial.println(SENZOR_ID);
+
+ pixels.begin();
+
+ // Modra za init
+ pixels.setPixelColor(0, pixels.Color(0, 0, 255));
+ pixels.show();
+
+ Wire.begin(SDApin, SCLpin);
+ Wire.setClock(400000); // 400kHz I2C clock. Comment this line if having compilation difficulties
+
+ // Start MPU
+ mpu.initialize();
+
+ // Set sensitivity / range
+ //mpu.setFullScaleGyroRange(MPU6050_GYRO_FS_250);
+ //mpu.setFullScaleAccelRange(MPU6050_ACCEL_FS_2);
+
+ // DMP init
+ devStatus = mpu.dmpInitialize();
+
+ // supply your own gyro offsets here, scaled for min sensitivity
+ // !!! Run Zero IMU to get readings (read comments for instructions)
+
+ /* Senzorpaket broj jedan (roka) */
+ mpu.setXAccelOffset(5439);
+ mpu.setYAccelOffset(-4509);
+ mpu.setZAccelOffset(10719);
+ mpu.setXGyroOffset(-30);
+ mpu.setYGyroOffset(-25);
+ mpu.setZGyroOffset(-19);
+
+
+ /* Senzorpaket II (glava)
+ mpu.setXAccelOffset(6555);
+ mpu.setYAccelOffset(-5252);
+ mpu.setZAccelOffset(9537);
+ mpu.setXGyroOffset(28);
+ mpu.setYGyroOffset(91);
+ mpu.setZGyroOffset(16);
+ */
+
+ /* Senzorpaket III (bekap)
+ mpu.setXAccelOffset(-3751);
+ mpu.setYAccelOffset(4927);
+ mpu.setZAccelOffset(8661);
+ mpu.setXGyroOffset(-130);
+ mpu.setYGyroOffset(-100);
+ mpu.setZGyroOffset(-4);
+ */
+
+ // make sure it worked (returns 0 if so)
+ if (devStatus == 0) {
+ // Calibration Time: generate offsets and calibrate our MPU6050
+ mpu.CalibrateAccel(6);
+ mpu.CalibrateGyro(6);
+ //Serial.println();
+ //mpu.PrintActiveOffsets();
+ // turn on the DMP, now that it's ready
+ //Serial.println(F("Enabling DMP..."));
+ mpu.setDMPEnabled(true);
+
+ // set our DMP Ready flag so the main loop() function knows it's okay to use it
+ //Serial.println(F("DMP ready! Waiting for first interrupt..."));
+ dmpReady = true;
+
+ // get expected DMP packet size for later comparison
+ packetSize = mpu.dmpGetFIFOPacketSize();
+ } else {
+ Serial.println("DMP Initialization failed (code " + String(devStatus) + ")");
+ // ERROR!
+ // 1 = initial memory load failed
+ // 2 = DMP configuration updates failed
+ // (if it's going to break, usually the code will be 1)
+
+ // Rdeca za fejl
+ pixels.setPixelColor(0, pixels.Color(255, 0, 0));
+ pixels.show();
+ return;
+ }
+
+ // Zelena za wifi init
+ pixels.setPixelColor(0, pixels.Color(0, 255, 0));
+ pixels.show();
+
+ // WIFI init
+ WiFi.mode(WIFI_STA);
+ if (esp_now_init() != ESP_OK) {
+ Serial.println("Error initializing ESP-NOW");
+ // Vijolicna za wifi fejl
+ pixels.setPixelColor(0, pixels.Color(255, 0, 255));
+ pixels.show();
+ return;
+ }
+
+ memcpy(peerInfo.peer_addr, sprejemnikMac, 6);
+ peerInfo.channel = 0;
+ peerInfo.encrypt = false;
+
+ if (esp_now_add_peer(&peerInfo) != ESP_OK){
+ Serial.println("WIFI registracija ni uspela");
+ // Rumena za drug wifi fejl
+ pixels.setPixelColor(0, pixels.Color(255, 255, 0));
+ pixels.show();
+ return;
+ }
+
+ // bel pixel za sve ok
+ pixels.setPixelColor(0, pixels.Color(255, 255, 255));
+ pixels.show();
+
+ // zacnemo
+ cas = millis();
+}
+
+void loop() {
+ // if programming failed, don't try to do anything
+ if (!dmpReady) return;
+
+ // read a packet from FIFO
+ if (mpu.dmpGetCurrentFIFOPacket(fifoBuffer)) { // Get the Latest packet
+
+ // Store last Q value
+ pq = Quaternion(q.w,q.x,q.y,q.z);
+
+ // get quaternion values in easy matrix form: w x y z
+ mpu.dmpGetQuaternion(&q, fifoBuffer);
+ q = q.getProduct(cq);
+
+ mpu.dmpGetAccel(&aa, fifoBuffer);
+ mpu.dmpGetGravity(&gravity, &q);
+ //mpu.dmpGetLinearAccel(&aaReal, &aa, &gravity);
+ mpu.dmpGetYawPitchRoll(ypr, &q, &gravity);
+
+ odcitek.id = SENZOR_ID;
+
+ // Quaternion - rotacija
+ odcitek.qX = q.x * -1;
+ odcitek.qY = q.y * -1;
+ odcitek.qZ = q.z;
+ odcitek.qW = q.w;
+
+ Serial.print("Quaternion: ");
+ Serial.print(q.x * -1);
+ Serial.print(" ");
+ Serial.print(q.y * -1);
+ Serial.print(" ");
+ Serial.print(q.z);
+ Serial.print(" ");
+ Serial.println(q.w);
+
+ // display real acceleration, adjusted to remove gravity
+ /*
+ odcitek.aX = aaReal.x;
+ odcitek.aY = aaReal.y;
+ odcitek.aZ = aaReal.z;
+
+ Serial.print("Accel: ");
+ Serial.print(aaReal.x);
+ Serial.print(" ");
+ Serial.print(aaReal.y);
+ Serial.print(" ");
+ Serial.println(aaReal.z);
+ */
+
+ Serial.print("YPR: ");
+ Serial.print(ypr[0]);
+ Serial.print(" ");
+ Serial.print(ypr[1]);
+ Serial.print(" ");
+ Serial.println(ypr[2]);
+
+ // Nastavimo LED!
+ /*
+ analogWrite(26, abs(ypr[0]) / M_PI * 255);
+ analogWrite(18, abs(ypr[1]) / M_PI * 255);
+ analogWrite(19, abs(ypr[2]) / M_PI * 255);
+ */
+
+ // Vsako sekundo odcitamo baterijo
+ if (millis() - cas > 1000) {
+ cas = millis();
+ odcitek.bat = analogRead(BATTERYPIN) * (1.1 / 8192);
+ }
+
+ esp_err_t result = esp_now_send(sprejemnikMac, (uint8_t *) &odcitek, sizeof(odcitek));
+
+ if (result == ESP_OK) {
+ Serial.println("Uspesno poslano");
+ } else {
+ Serial.println("Napaka pri posiljanju");
+ Serial.println(result);
+ }
+ }
+}
diff --git a/src/sprejemnik.cpp b/src/sprejemnik.cpp
new file mode 100644
index 0000000..1e68b9b
--- /dev/null
+++ b/src/sprejemnik.cpp
@@ -0,0 +1,162 @@
+#include
+
+#include
+#include
+#include
+
+#include
+#include
+
+//#define DEBUG
+
+#ifdef BOARD_HAS_USB_SERIAL
+#include
+SLIPEncodedUSBSerial SLIPSerial( thisBoardsSerialUSB );
+#else
+#include
+SLIPEncodedSerial SLIPSerial(Serial); // Change to Serial1 or Serial2 etc. for boards with multiple serial ports that don’t have Serial
+#endif
+
+// Set your new MAC Address
+// MAC naslov sprejemnika: 08:3A:F2:50:EF:6C
+uint8_t newMACAddress[] = {0x08, 0x3A, 0xF2, 0x50, 0xEF, 0x6C};
+
+typedef struct sensor_msg {
+ uint8_t id;
+ /*
+ float aX;
+ float aY;
+ float aZ;
+ */
+ float qX;
+ float qY;
+ float qZ;
+ float qW;
+ double bat;
+} sensor_msg;
+
+//sensor_msg odcitek;
+
+// Maksimalno stevilo
+#define ST_KEGLOV 10
+
+int odcitekId;
+sensor_msg odcitki[ST_KEGLOV];
+bool poslji[ST_KEGLOV];
+
+void prejemPodatkov(const uint8_t * mac_addr, const uint8_t * noviPodatki, int len) {
+
+ char macNaslov[18];
+ snprintf(macNaslov, sizeof(macNaslov), "%02x:%02x:%02x:%02x:%02x:%02x",
+ mac_addr[0], mac_addr[1], mac_addr[2], mac_addr[3], mac_addr[4], mac_addr[5]);
+
+ #ifdef DEBUG
+ Serial.print("Prejel podatke od ");
+ Serial.println(macNaslov);
+ #endif
+
+ // ID odcitka je na prvem mestu!
+ memcpy(&odcitekId, noviPodatki, sizeof(uint8_t));
+
+ #ifdef DEBUG
+ Serial.print("RAZBIRAM ID ");
+ Serial.println(odcitekId);
+ #endif
+
+ memcpy(&odcitki[odcitekId], noviPodatki, sizeof(sensor_msg));
+
+ #ifdef DEBUG
+ /*
+ Serial.printf("aX: %i \n", odcitki[odcitekId].aX);
+ Serial.printf("aY: %i \n", odcitki[odcitekId].aY);
+ Serial.printf("aZ: %i \n", odcitki[odcitekId].aZ);
+ */
+ Serial.printf("qX: %f \n", odcitki[odcitekId].qX);
+ Serial.printf("qY: %f \n", odcitki[odcitekId].qY);
+ Serial.printf("qZ: %f \n", odcitki[odcitekId].qZ);
+ Serial.printf("qW: %f \n", odcitki[odcitekId].qW);
+ Serial.printf("bat: %d \n", odcitki[odcitekId].bat);
+ Serial.println();
+ #endif
+
+ poslji[odcitekId] = true;
+}
+
+void setup() {
+ SLIPSerial.begin(115200);
+
+ // Ne posiljaj preden se podatki napolnijo
+ for (int i = 0; i < ST_KEGLOV; i++) {
+ poslji[0] = false;
+ }
+
+ Serial.println("Inicializiram WIFI...");
+ WiFi.mode(WIFI_STA);
+
+ esp_wifi_set_mac(WIFI_IF_STA, &newMACAddress[0]);
+
+ esp_err_t result = esp_now_init();
+ if (result != ESP_OK) {
+ Serial.println("Error initializing ESP-NOW");
+ Serial.println(result);
+ return;
+ }
+ Serial.print("MAC naslov: ");
+ Serial.println(WiFi.macAddress());
+ esp_now_register_recv_cb(prejemPodatkov);
+}
+
+void loop() {
+ /* OSC MSG channels */
+ OSCBundle bundle;
+ char glava[32];
+
+ for (int i = 0; i < ST_KEGLOV; i++) {
+ if (poslji[i]) {
+
+ /*
+ sprintf(glava, "/ww/%d/accel", i);
+ // Serial.print("Posiljam ");
+ // Serial.println(glava);
+ bundle.add(glava)
+ .add(odcitki[i].aX)
+ .add(odcitki[i].aY)
+ .add(odcitki[i].aZ);
+ */
+
+ sprintf(glava, "/ww/%d/quaternion", i);
+ /*
+ Serial.print("Posiljam ");
+ Serial.println(glava);
+ */
+ bundle.add(glava)
+ .add(odcitki[i].qW)
+ .add(odcitki[i].qX)
+ .add(odcitki[i].qY)
+ .add(odcitki[i].qZ);
+
+ sprintf(glava, "/ww/%d/bat", i);
+ bundle.add(glava)
+ .add(odcitki[i].bat);
+
+ /*
+ Serial.printf("XaX: %i \n", odcitki[i].aX);
+ Serial.printf("XaY: %i \n", odcitki[i].aY);
+ Serial.printf("XaZ: %i \n", odcitki[i].aZ);
+ Serial.printf("XqX: %f \n", odcitki[i].qX);
+ Serial.printf("XqY: %f \n", odcitki[i].qY);
+ Serial.printf("XqZ: %f \n", odcitki[i].qZ);
+ Serial.printf("XqW: %f \n", odcitki[i].qW);
+ Serial.println();
+ */
+
+ SLIPSerial.beginPacket();
+ bundle.send(SLIPSerial);
+ SLIPSerial.endPacket();
+
+ bundle.empty();
+ poslji[i] = false;
+ }
+ }
+ //delay(10);
+}