diff --git a/CHANGELOG.md b/CHANGELOG.md index a2e722eac..1c3c9ca0f 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -18,6 +18,7 @@ All notable changes to this project will be documented in this file. - ESP32 Extent BLE (#11212) - ESP32 support for WS2812 hardware driver via RMT or I2S - ESP32 support for secondary I2C controller +- Add support for MPU6686 on primary or secondary I2C bus ### Changed diff --git a/I2CDEVICES.md b/I2CDEVICES.md index 60ee9608b..8d5e34459 100644 --- a/I2CDEVICES.md +++ b/I2CDEVICES.md @@ -91,3 +91,4 @@ Index | Define | Driver | Device | Address(es) | Description 55 | USE_EZOPMP | xsns_78 | EZOPMP | 0x61 - 0x70 | Peristaltic Pump 56 | USE_SEESAW_SOIL | xsns_81 | SEESOIL | 0x36 - 0x39 | Adafruit seesaw soil moisture sensor 57 | USE_TOF10120 | xsns_84 | TOF10120 | 0x52 | Time-of-flight (ToF) distance sensor + 58 | USE_MPU6886 | xsns_85 | MPU6886 | 0x68 | MPU6886 M5Stack \ No newline at end of file diff --git a/lib/lib_i2c/MPU6886/library.properties b/lib/lib_i2c/MPU6886/library.properties new file mode 100644 index 000000000..1a08c8516 --- /dev/null +++ b/lib/lib_i2c/MPU6886/library.properties @@ -0,0 +1,9 @@ +name=MPU6886 +version= +author=M5StickC +maintainer=Stephan Hadinger +sentence=Support for MPU6886 +paragraph=Support for MPU6886 +category= +url=https://github.com/m5stack/M5StickC/blob/master/src/utility/ +architectures=esp32,esp8266 diff --git a/lib/libesp32/CORE2_Library/MPU6886.cpp b/lib/lib_i2c/MPU6886/src/MPU6886.cpp similarity index 68% rename from lib/libesp32/CORE2_Library/MPU6886.cpp rename to lib/lib_i2c/MPU6886/src/MPU6886.cpp index 418c94b39..9ae45461d 100755 --- a/lib/libesp32/CORE2_Library/MPU6886.cpp +++ b/lib/lib_i2c/MPU6886/src/MPU6886.cpp @@ -2,39 +2,33 @@ #include #include -MPU6886::MPU6886(){ - -} - void MPU6886::I2C_Read_NBytes(uint8_t driver_Addr, uint8_t start_Addr, uint8_t number_Bytes, uint8_t *read_Buffer){ - Wire1.beginTransmission(driver_Addr); - Wire1.write(start_Addr); - Wire1.endTransmission(false); + myWire.beginTransmission(driver_Addr); + myWire.write(start_Addr); + myWire.endTransmission(false); uint8_t i = 0; - Wire1.requestFrom(driver_Addr,number_Bytes); + myWire.requestFrom(driver_Addr,number_Bytes); //! Put read results in the Rx buffer - while (Wire1.available()) { - read_Buffer[i++] = Wire1.read(); + while (myWire.available()) { + read_Buffer[i++] = myWire.read(); } } void MPU6886::I2C_Write_NBytes(uint8_t driver_Addr, uint8_t start_Addr, uint8_t number_Bytes, uint8_t *write_Buffer){ - Wire1.beginTransmission(driver_Addr); - Wire1.write(start_Addr); - Wire1.write(*write_Buffer); - Wire1.endTransmission(); + myWire.beginTransmission(driver_Addr); + myWire.write(start_Addr); + myWire.write(*write_Buffer); + myWire.endTransmission(); } int MPU6886::Init(void){ unsigned char tempdata[1]; unsigned char regdata; - - Wire1.begin(21,22); - + I2C_Read_NBytes(MPU6886_ADDRESS, MPU6886_WHOAMI, 1, tempdata); if(tempdata[0] != 0x19) return -1; @@ -52,11 +46,11 @@ int MPU6886::Init(void){ I2C_Write_NBytes(MPU6886_ADDRESS, MPU6886_PWR_MGMT_1, 1, ®data); delay(10); - regdata = 0x10; + regdata = 0x10; // AFS_8G I2C_Write_NBytes(MPU6886_ADDRESS, MPU6886_ACCEL_CONFIG, 1, ®data); delay(1); - regdata = 0x18; + regdata = 0x18; // GFS_2000DPS I2C_Write_NBytes(MPU6886_ADDRESS, MPU6886_GYRO_CONFIG, 1, ®data); delay(1); @@ -128,24 +122,24 @@ void MPU6886::getTempAdc(int16_t *t){ -//!俯仰,航向,横滚:pitch,yaw,roll,指三维空间中飞行器的旋转状态。 -void MPU6886::getAhrsData(float *pitch,float *roll,float *yaw){ +// //!俯仰,航向,横滚:pitch,yaw,roll,指三维空间中飞行器的旋转状态。 +// void MPU6886::getAhrsData(float *pitch,float *roll,float *yaw){ - float accX = 0; - float accY = 0; - float accZ = 0; +// float accX = 0; +// float accY = 0; +// float accZ = 0; - float gyroX = 0; - float gyroY = 0; - float gyroZ = 0; +// float gyroX = 0; +// float gyroY = 0; +// float gyroZ = 0; - getGyroData(&gyroX,&gyroY,&gyroZ); - getAccelData(&accX,&accY,&accZ); +// getGyroData(&gyroX,&gyroY,&gyroZ); +// getAccelData(&accX,&accY,&accZ); - MahonyAHRSupdateIMU(gyroX * DEG_TO_RAD, gyroY * DEG_TO_RAD, gyroZ * DEG_TO_RAD, accX, accY, accZ,pitch,roll,yaw); +// MahonyAHRSupdateIMU(gyroX * DEG_TO_RAD, gyroY * DEG_TO_RAD, gyroZ * DEG_TO_RAD, accX, accY, accZ,pitch,roll,yaw); -} +// } void MPU6886::getGres(){ @@ -153,16 +147,20 @@ void MPU6886::getGres(){ { // Possible gyro scales (and their register bit settings) are: case GFS_250DPS: - gRes = 250.0/32768.0; + gRes = 250.0f/32768.0f; + gyRange = 250; break; case GFS_500DPS: - gRes = 500.0/32768.0; + gRes = 500.0f/32768.0f; + gyRange = 500; break; case GFS_1000DPS: - gRes = 1000.0/32768.0; + gRes = 1000.0f/32768.0f; + gyRange = 1000; break; case GFS_2000DPS: - gRes = 2000.0/32768.0; + gRes = 2000.0f/32768.0f; + gyRange = 2000; break; } @@ -177,15 +175,19 @@ void MPU6886::getAres(){ // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value: case AFS_2G: aRes = 2.0/32768.0; + acRange = 2000; break; case AFS_4G: aRes = 4.0/32768.0; + acRange = 4000; break; case AFS_8G: aRes = 8.0/32768.0; + acRange = 8000; break; case AFS_16G: aRes = 16.0/32768.0; + acRange = 16000; break; } @@ -215,7 +217,19 @@ void MPU6886::SetAccelFsr(Ascale scale) } +// x/y/z are in 1/1000 if g +// avoiding costly float calculations +void MPU6886::getAccelDataInt(int16_t* ax, int16_t* ay, int16_t* az) { + int16_t accX = 0; + int16_t accY = 0; + int16_t accZ = 0; + getAccelAdc(&accX, &accY, &accZ); + if (ax != nullptr) { *ax = ((int32_t)accX * acRange) / 0x7FFFL; } + if (ay != nullptr) { *ay = ((int32_t)accY * acRange) / 0x7FFFL; } + if (az != nullptr) { *az = ((int32_t)accZ * acRange) / 0x7FFFL; } + +} void MPU6886::getAccelData(float* ax, float* ay, float* az){ @@ -232,6 +246,20 @@ void MPU6886::getAccelData(float* ax, float* ay, float* az){ } +// x/y/z are in dps - degrees per second +// avoiding costly float calculations +void MPU6886::getGyroDataInt(int16_t* ax, int16_t* ay, int16_t* az) { + int16_t gyX = 0; + int16_t gyY = 0; + int16_t gyZ = 0; + getGyroAdc(&gyX, &gyY, &gyZ); + + if (ax != nullptr) { *ax = ((int32_t)gyX * gyRange) / 0x7FFFL; } + if (ay != nullptr) { *ay = ((int32_t)gyY * gyRange) / 0x7FFFL; } + if (az != nullptr) { *az = ((int32_t)gyZ * gyRange) / 0x7FFFL; } + +} + void MPU6886::getGyroData(float* gx, float* gy, float* gz){ int16_t gyroX = 0; int16_t gyroY = 0; diff --git a/lib/libesp32/CORE2_Library/MPU6886.h b/lib/lib_i2c/MPU6886/src/MPU6886.h similarity index 82% rename from lib/libesp32/CORE2_Library/MPU6886.h rename to lib/lib_i2c/MPU6886/src/MPU6886.h index b1a0fb16b..025f71587 100755 --- a/lib/libesp32/CORE2_Library/MPU6886.h +++ b/lib/lib_i2c/MPU6886/src/MPU6886.h @@ -10,7 +10,6 @@ #include #include -#include "MahonyAHRS.h" #define MPU6886_ADDRESS 0x68 #define MPU6886_WHOAMI 0x75 @@ -67,8 +66,15 @@ class MPU6886 { Gscale Gyscale = GFS_2000DPS; Ascale Acscale = AFS_8G; + int16_t acRange = 8000; // 1/1000 of g + int16_t gyRange = 2000; // dps - degree per second public: - MPU6886(); + MPU6886(void) {}; + #ifdef ESP32 + void setBus(uint32_t _bus) { myWire = _bus ? Wire1 : Wire; }; + #else + void setBus(uint32_t _bus) { myWire = Wire; }; + #endif int Init(void); void getAccelAdc(int16_t* ax, int16_t* ay, int16_t* az); void getGyroAdc(int16_t* gx, int16_t* gy, int16_t* gz); @@ -77,13 +83,17 @@ class MPU6886 { void getAccelData(float* ax, float* ay, float* az); void getGyroData(float* gx, float* gy, float* gz); void getTempData(float *t); + // int variants + void getAccelDataInt(int16_t* ax, int16_t* ay, int16_t* az); + void getGyroDataInt(int16_t* gx, int16_t* gy, int16_t* gz); void SetGyroFsr(Gscale scale); void SetAccelFsr(Ascale scale); - void getAhrsData(float *pitch,float *roll,float *yaw); + // void getAhrsData(float *pitch,float *roll,float *yaw); public: + TwoWire & myWire = Wire; // default to Wire (bus 0) float aRes, gRes; private: diff --git a/lib/libesp32/CORE2_Library/MahonyAHRS.cpp b/lib/libesp32/CORE2_Library/MahonyAHRS.cpp deleted file mode 100755 index cae005075..000000000 --- a/lib/libesp32/CORE2_Library/MahonyAHRS.cpp +++ /dev/null @@ -1,254 +0,0 @@ -//===================================================================================================== -// MahonyAHRS.c -//===================================================================================================== -// -// Madgwick's implementation of Mayhony's AHRS algorithm. -// See: http://www.x-io.co.uk/node/8#open_source_ahrs_and_imu_algorithms -// -// Date Author Notes -// 29/09/2011 SOH Madgwick Initial release -// 02/10/2011 SOH Madgwick Optimised for reduced CPU load -// -//===================================================================================================== - -//--------------------------------------------------------------------------------------------------- -// Header files - -#include "MahonyAHRS.h" -#include "Arduino.h" -#include -//--------------------------------------------------------------------------------------------------- -// Definitions - -#define sampleFreq 25.0f // sample frequency in Hz -#define twoKpDef (2.0f * 1.0f) // 2 * proportional gain -#define twoKiDef (2.0f * 0.0f) // 2 * integral gain - -//#define twoKiDef (0.0f * 0.0f) - -//--------------------------------------------------------------------------------------------------- -// Variable definitions - -volatile float twoKp = twoKpDef; // 2 * proportional gain (Kp) -volatile float twoKi = twoKiDef; // 2 * integral gain (Ki) -volatile float q0 = 1.0, q1 = 0.0, q2 = 0.0, q3 = 0.0; // quaternion of sensor frame relative to auxiliary frame -volatile float integralFBx = 0.0f, integralFBy = 0.0f, integralFBz = 0.0f; // integral error terms scaled by Ki - -//--------------------------------------------------------------------------------------------------- -// Function declarations - -//float invSqrt(float x); - -//==================================================================================================== -// Functions - -//--------------------------------------------------------------------------------------------------- -// AHRS algorithm update - -void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz) { - float recipNorm; - float q0q0, q0q1, q0q2, q0q3, q1q1, q1q2, q1q3, q2q2, q2q3, q3q3; - float hx, hy, bx, bz; - float halfvx, halfvy, halfvz, halfwx, halfwy, halfwz; - float halfex, halfey, halfez; - float qa, qb, qc; - - // Use IMU algorithm if magnetometer measurement invalid (avoids NaN in magnetometer normalisation) - if((mx == 0.0f) && (my == 0.0f) && (mz == 0.0f)) { - //MahonyAHRSupdateIMU(gx, gy, gz, ax, ay, az); - return; - } - - // Compute feedback only if accelerometer measurement valid (avoids NaN in accelerometer normalisation) - if(!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) { - - // Normalise accelerometer measurement - recipNorm = sqrt(ax * ax + ay * ay + az * az); - ax *= recipNorm; - ay *= recipNorm; - az *= recipNorm; - - // Normalise magnetometer measurement - recipNorm = sqrt(mx * mx + my * my + mz * mz); - mx *= recipNorm; - my *= recipNorm; - mz *= recipNorm; - - // Auxiliary variables to avoid repeated arithmetic - q0q0 = q0 * q0; - q0q1 = q0 * q1; - q0q2 = q0 * q2; - q0q3 = q0 * q3; - q1q1 = q1 * q1; - q1q2 = q1 * q2; - q1q3 = q1 * q3; - q2q2 = q2 * q2; - q2q3 = q2 * q3; - q3q3 = q3 * q3; - - // Reference direction of Earth's magnetic field - hx = 2.0f * (mx * (0.5f - q2q2 - q3q3) + my * (q1q2 - q0q3) + mz * (q1q3 + q0q2)); - hy = 2.0f * (mx * (q1q2 + q0q3) + my * (0.5f - q1q1 - q3q3) + mz * (q2q3 - q0q1)); - bx = sqrt(hx * hx + hy * hy); - bz = 2.0f * (mx * (q1q3 - q0q2) + my * (q2q3 + q0q1) + mz * (0.5f - q1q1 - q2q2)); - - // Estimated direction of gravity and magnetic field - halfvx = q1q3 - q0q2; - halfvy = q0q1 + q2q3; - halfvz = q0q0 - 0.5f + q3q3; - halfwx = bx * (0.5f - q2q2 - q3q3) + bz * (q1q3 - q0q2); - halfwy = bx * (q1q2 - q0q3) + bz * (q0q1 + q2q3); - halfwz = bx * (q0q2 + q1q3) + bz * (0.5f - q1q1 - q2q2); - - // Error is sum of cross product between estimated direction and measured direction of field vectors - halfex = (ay * halfvz - az * halfvy) + (my * halfwz - mz * halfwy); - halfey = (az * halfvx - ax * halfvz) + (mz * halfwx - mx * halfwz); - halfez = (ax * halfvy - ay * halfvx) + (mx * halfwy - my * halfwx); - - // Compute and apply integral feedback if enabled - if(twoKi > 0.0f) { - integralFBx += twoKi * halfex * (1.0f / sampleFreq); // integral error scaled by Ki - integralFBy += twoKi * halfey * (1.0f / sampleFreq); - integralFBz += twoKi * halfez * (1.0f / sampleFreq); - gx += integralFBx; // apply integral feedback - gy += integralFBy; - gz += integralFBz; - } - else { - integralFBx = 0.0f; // prevent integral windup - integralFBy = 0.0f; - integralFBz = 0.0f; - } - - // Apply proportional feedback - gx += twoKp * halfex; - gy += twoKp * halfey; - gz += twoKp * halfez; - } - - // Integrate rate of change of quaternion - gx *= (0.5f * (1.0f / sampleFreq)); // pre-multiply common factors - gy *= (0.5f * (1.0f / sampleFreq)); - gz *= (0.5f * (1.0f / sampleFreq)); - qa = q0; - qb = q1; - qc = q2; - q0 += (-qb * gx - qc * gy - q3 * gz); - q1 += (qa * gx + qc * gz - q3 * gy); - q2 += (qa * gy - qb * gz + q3 * gx); - q3 += (qa * gz + qb * gy - qc * gx); - - // Normalise quaternion - recipNorm = sqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); - q0 *= recipNorm; - q1 *= recipNorm; - q2 *= recipNorm; - q3 *= recipNorm; -} - -//--------------------------------------------------------------------------------------------------- -// IMU algorithm update - -void MahonyAHRSupdateIMU(float gx, float gy, float gz, float ax, float ay, float az,float *pitch,float *roll,float *yaw) { - float recipNorm; - float halfvx, halfvy, halfvz; - float halfex, halfey, halfez; - float qa, qb, qc; - - - // Compute feedback only if accelerometer measurement valid (avoids NaN in accelerometer normalisation) - if(!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) { - - // Normalise accelerometer measurement - recipNorm = invSqrt(ax * ax + ay * ay + az * az); - ax *= recipNorm; - ay *= recipNorm; - az *= recipNorm; - - // Estimated direction of gravity and vector perpendicular to magnetic flux - halfvx = q1 * q3 - q0 * q2; - halfvy = q0 * q1 + q2 * q3; - halfvz = q0 * q0 - 0.5f + q3 * q3; - - - - // Error is sum of cross product between estimated and measured direction of gravity - halfex = (ay * halfvz - az * halfvy); - halfey = (az * halfvx - ax * halfvz); - halfez = (ax * halfvy - ay * halfvx); - - // Compute and apply integral feedback if enabled - if(twoKi > 0.0f) { - integralFBx += twoKi * halfex * (1.0f / sampleFreq); // integral error scaled by Ki - integralFBy += twoKi * halfey * (1.0f / sampleFreq); - integralFBz += twoKi * halfez * (1.0f / sampleFreq); - gx += integralFBx; // apply integral feedback - gy += integralFBy; - gz += integralFBz; - } - else { - integralFBx = 0.0f; // prevent integral windup - integralFBy = 0.0f; - integralFBz = 0.0f; - } - - // Apply proportional feedback - gx += twoKp * halfex; - gy += twoKp * halfey; - gz += twoKp * halfez; - } - - // Integrate rate of change of quaternion - gx *= (0.5f * (1.0f / sampleFreq)); // pre-multiply common factors - gy *= (0.5f * (1.0f / sampleFreq)); - gz *= (0.5f * (1.0f / sampleFreq)); - qa = q0; - qb = q1; - qc = q2; - q0 += (-qb * gx - qc * gy - q3 * gz); - q1 += (qa * gx + qc * gz - q3 * gy); - q2 += (qa * gy - qb * gz + q3 * gx); - q3 += (qa * gz + qb * gy - qc * gx); - - // Normalise quaternion - recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); - q0 *= recipNorm; - q1 *= recipNorm; - q2 *= recipNorm; - q3 *= recipNorm; - - - *pitch = asin(-2 * q1 * q3 + 2 * q0* q2); // pitch - *roll = atan2(2 * q2 * q3 + 2 * q0 * q1, -2 * q1 * q1 - 2 * q2* q2 + 1); // roll - *yaw = atan2(2*(q1*q2 + q0*q3),q0*q0+q1*q1-q2*q2-q3*q3); //yaw - - *pitch *= RAD_TO_DEG; - *yaw *= RAD_TO_DEG; - // Declination of SparkFun Electronics (40°05'26.6"N 105°11'05.9"W) is - // 8° 30' E ± 0° 21' (or 8.5°) on 2016-07-19 - // - http://www.ngdc.noaa.gov/geomag-web/#declination - *yaw -= 8.5; - *roll *= RAD_TO_DEG; - - ///Serial.printf("%f %f %f \r\n", pitch, roll, yaw); -} - -//--------------------------------------------------------------------------------------------------- -// Fast inverse square-root -// See: http://en.wikipedia.org/wiki/Fast_inverse_square_root - -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wstrict-aliasing" -float invSqrt(float x) { - float halfx = 0.5f * x; - float y = x; - long i = *(long*)&y; - i = 0x5f3759df - (i>>1); - y = *(float*)&i; - y = y * (1.5f - (halfx * y * y)); - return y; -} -#pragma GCC diagnostic pop -//==================================================================================================== -// END OF CODE -//==================================================================================================== diff --git a/lib/libesp32/CORE2_Library/MahonyAHRS.h b/lib/libesp32/CORE2_Library/MahonyAHRS.h deleted file mode 100755 index bae082d24..000000000 --- a/lib/libesp32/CORE2_Library/MahonyAHRS.h +++ /dev/null @@ -1,33 +0,0 @@ -//===================================================================================================== -// MahonyAHRS.h -//===================================================================================================== -// -// Madgwick's implementation of Mayhony's AHRS algorithm. -// See: http://www.x-io.co.uk/node/8#open_source_ahrs_and_imu_algorithms -// -// Date Author Notes -// 29/09/2011 SOH Madgwick Initial release -// 02/10/2011 SOH Madgwick Optimised for reduced CPU load -// -//===================================================================================================== -#ifndef MahonyAHRS_h -#define MahonyAHRS_h - -//---------------------------------------------------------------------------------------------------- -// Variable declaration - -extern volatile float twoKp; // 2 * proportional gain (Kp) -extern volatile float twoKi; // 2 * integral gain (Ki) -//volatile float q0, q1, q2, q3; // quaternion of sensor frame relative to auxiliary frame - -//--------------------------------------------------------------------------------------------------- -// Function declarations - -void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz); -//void MahonyAHRSupdateIMU(float gx, float gy, float gz, float ax, float ay, float az); -void MahonyAHRSupdateIMU(float gx, float gy, float gz, float ax, float ay, float az,float *pitch,float *roll,float *yaw); -float invSqrt(float x); -#endif -//===================================================================================================== -// End of file -//===================================================================================================== diff --git a/tasmota/i18n.h b/tasmota/i18n.h index 061b240b4..da0893f89 100644 --- a/tasmota/i18n.h +++ b/tasmota/i18n.h @@ -782,6 +782,7 @@ const char JSON_SNS_RANGE[] PROGMEM = ",\"%s\":{\"" D_JSON_RANGE "\":%d}"; const char JSON_SNS_GNGPM[] PROGMEM = ",\"%s\":{\"" D_JSON_TOTAL_USAGE "\":%s,\"" D_JSON_FLOWRATE "\":%s}"; const char S_LOG_I2C_FOUND_AT[] PROGMEM = D_LOG_I2C "%s " D_FOUND_AT " 0x%x"; +const char S_LOG_I2C_FOUND_AT_PORT[] PROGMEM = D_LOG_I2C "%s " D_FOUND_AT " 0x%x (" D_PORT " %d)"; const char S_RSLT_POWER[] PROGMEM = D_RSLT_POWER; const char S_RSLT_RESULT[] PROGMEM = D_RSLT_RESULT; diff --git a/tasmota/my_user_config.h b/tasmota/my_user_config.h index b4bd5dfae..e33e5bf3c 100644 --- a/tasmota/my_user_config.h +++ b/tasmota/my_user_config.h @@ -607,6 +607,7 @@ // #define USE_EZORGB // [I2cDriver55] Enable support for EZO's RGB sensor (+0k5 code) - Shared EZO code required for any EZO device (+1k2 code) // #define USE_EZOPMP // [I2cDriver55] Enable support for EZO's PMP sensor (+0k3 code) - Shared EZO code required for any EZO device (+1k2 code) // #define USE_SEESAW_SOIL // [I2cDriver56] Enable Capacitice Soil Moisture & Temperature Sensor (I2C addresses 0x36 - 0x39) (+1k3 code) +// #define USE_MPU6886 // [I2cDriver58] Enable MPU6686 - found in M5Stack - support 2 I2C buses on ESP32 (I2C address 0x68) (+2k code) // #define USE_DISPLAY // Add I2C Display Support (+2k code) #define USE_DISPLAY_MODES1TO5 // Enable display mode 1 to 5 in addition to mode 0 diff --git a/tasmota/support.ino b/tasmota/support.ino index f4d030def..b1653ff2a 100644 --- a/tasmota/support.ino +++ b/tasmota/support.ino @@ -2053,10 +2053,19 @@ void I2cSetActive(uint32_t addr, uint32_t count = 1) // AddLog(LOG_LEVEL_DEBUG, PSTR("I2C: Active %08X,%08X,%08X,%08X"), i2c_active[0], i2c_active[1], i2c_active[2], i2c_active[3]); } -void I2cSetActiveFound(uint32_t addr, const char *types) +void I2cSetActiveFound(uint32_t addr, const char *types, uint32_t bus = 0); +void I2cSetActiveFound(uint32_t addr, const char *types, uint32_t bus) { I2cSetActive(addr); +#ifdef ESP32 + if (0 == bus) { + AddLog(LOG_LEVEL_INFO, S_LOG_I2C_FOUND_AT, types, addr); + } else { + AddLog(LOG_LEVEL_INFO, S_LOG_I2C_FOUND_AT_PORT, types, addr, bus); + } +#else AddLog(LOG_LEVEL_INFO, S_LOG_I2C_FOUND_AT, types, addr); +#endif // ESP32 } bool I2cActive(uint32_t addr) @@ -2068,14 +2077,24 @@ bool I2cActive(uint32_t addr) return false; } +#ifdef ESP32 +bool I2cSetDevice(uint32_t addr, uint32_t bus = 0); +bool I2cSetDevice(uint32_t addr, uint32_t bus) +#else bool I2cSetDevice(uint32_t addr) +#endif { +#ifdef ESP32 + TwoWire & myWire = (bus == 0) ? Wire : Wire1; +#else + TwoWire & myWire = Wire; +#endif addr &= 0x7F; // Max I2C address is 127 if (I2cActive(addr)) { return false; // If already active report as not present; } - Wire.beginTransmission((uint8_t)addr); - return (0 == Wire.endTransmission()); + myWire.beginTransmission((uint8_t)addr); + return (0 == myWire.endTransmission()); } #endif // USE_I2C diff --git a/tasmota/tasmota_configurations_ESP32.h b/tasmota/tasmota_configurations_ESP32.h index 3b0f969a4..7f7a8d01b 100644 --- a/tasmota/tasmota_configurations_ESP32.h +++ b/tasmota/tasmota_configurations_ESP32.h @@ -81,12 +81,12 @@ #define USE_M5STACK_CORE2 // Add support for M5Stack Core2 #define USE_I2S_SAY_TIME #define USE_I2S_WEBRADIO - #define USE_MPU6886 #define USE_UFILESYS #define USE_SDCARD #define GUI_TRASH_FILE #define USE_I2C #define USE_BMA423 + #define USE_MPU6886 #define USE_SPI #define USE_DISPLAY #define USE_DISPLAY_ILI9342 diff --git a/tasmota/xdrv_52_3_berry_wire.ino b/tasmota/xdrv_52_3_berry_wire.ino index a5fccb44e..5959b98b9 100644 --- a/tasmota/xdrv_52_3_berry_wire.ino +++ b/tasmota/xdrv_52_3_berry_wire.ino @@ -185,7 +185,7 @@ extern "C" { be_raise(vm, kTypeError, nullptr); } - // Berry: `validwrite(address:int, reg:int, val:int, size:int) -> bool or nil` + // Berry: `write(address:int, reg:int, val:int, size:int) -> bool or nil` int32_t b_wire_validwrite(struct bvm *vm); int32_t b_wire_validwrite(struct bvm *vm) { int32_t top = be_top(vm); // Get the number of arguments @@ -202,7 +202,7 @@ extern "C" { be_raise(vm, kTypeError, nullptr); } - // Berry: `validread(address:int, reg:int, size:int) -> int or nil` + // Berry: `read(address:int, reg:int, size:int) -> int or nil` int32_t b_wire_validread(struct bvm *vm); int32_t b_wire_validread(struct bvm *vm) { int32_t top = be_top(vm); // Get the number of arguments diff --git a/tasmota/xdrv_84_esp32_core2.ino b/tasmota/xdrv_84_esp32_core2.ino index dc196536c..9f0d3cc60 100644 --- a/tasmota/xdrv_84_esp32_core2.ino +++ b/tasmota/xdrv_84_esp32_core2.ino @@ -32,15 +32,14 @@ rtc better sync #include #include -#include #include #include +#include #define XDRV_84 84 struct CORE2_globs { AXP192 Axp; - MPU6886 Mpu; BM8563_RTC Rtc; bool ready; bool tset; @@ -56,9 +55,6 @@ struct CORE2_ADC { float vbus_c; float batt_c; float temp; - int16_t x; - int16_t y; - int16_t z; } core2_adc; // cause SC card is needed by scripter @@ -75,9 +71,6 @@ void CORE2_Module_Init(void) { // motor voltage core2_globs.Axp.SetLDOVoltage(3,2000); - core2_globs.Mpu.Init(); - I2cSetActiveFound(MPU6886_ADDRESS, "MPU6886"); - core2_globs.Rtc.begin(); I2cSetActiveFound(RTC_ADRESS, "RTC"); @@ -119,12 +112,6 @@ const char HTTP_CORE2[] PROGMEM = "{s}BATT Voltage" "{m}%s V" "{e}" "{s}BATT Current" "{m}%s mA" "{e}" "{s}Chip Temperature" "{m}%s C" "{e}"; -#ifdef USE_MPU6886 -const char HTTP_CORE2_MPU[] PROGMEM = - "{s}MPU x" "{m}%d mg" "{e}" - "{s}MPU y" "{m}%d mg" "{e}" - "{s}MPU z" "{m}%d mg" "{e}"; -#endif // USE_MPU6886 #endif // USE_WEBSERVER @@ -146,18 +133,9 @@ void CORE2_WebShow(uint32_t json) { dtostrfd(core2_adc.temp, 2, tstring); if (json) { - ResponseAppend_P(PSTR(",\"CORE2\":{\"VBV\":%s,\"BV\":%s,\"VBC\":%s,\"BC\":%s,\"CT\":%s"), vstring, cstring, bvstring, bcstring, tstring); - -#ifdef USE_MPU6886 - ResponseAppend_P(PSTR(",\"MPUX\":%d,\"MPUY\":%d,\"MPUZ\":%d"), core2_adc.x, core2_adc.y, core2_adc.z); -#endif - ResponseJsonEnd(); + ResponseAppend_P(PSTR(",\"CORE2\":{\"VBV\":%s,\"BV\":%s,\"VBC\":%s,\"BC\":%s,\"CT\":%s}"), vstring, cstring, bvstring, bcstring, tstring); } else { WSContentSend_PD(HTTP_CORE2, vstring, cstring, bvstring, bcstring, tstring); - -#ifdef USE_MPU6886 - WSContentSend_PD(HTTP_CORE2_MPU, core2_adc.x, core2_adc.y, core2_adc.z); -#endif // USE_MPU6886 } } @@ -342,15 +320,6 @@ void CORE2_GetADC(void) { core2_adc.batt_c = core2_globs.Axp.GetBatCurrent(); core2_adc.temp = core2_globs.Axp.GetTempInAXP192(); -#ifdef USE_MPU6886 - float x; - float y; - float z; - core2_globs.Mpu.getAccelData(&x, &y, &z); - core2_adc.x=x*1000; - core2_adc.y=y*1000; - core2_adc.z=z*1000; -#endif // USE_MPU6886 } /*********************************************************************************************\ diff --git a/tasmota/xsns_85_mpu6886.ino b/tasmota/xsns_85_mpu6886.ino new file mode 100644 index 000000000..0cbe317f9 --- /dev/null +++ b/tasmota/xsns_85_mpu6886.ino @@ -0,0 +1,128 @@ +/* + xsns_84_tof10120.ino - TOF10120 sensor support for Tasmota + + Copyright (C) 2021 Stephan Hadinger and Theo Arends + + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . +*/ + +#ifdef USE_I2C +#ifdef USE_MPU6886 + +#include +/*********************************************************************************************\ + * MPU6886 + * Internal chip found in M5Stack devices, using `Wire1` internal I2C bus + * + * I2C Address: 0x68 + * +\*********************************************************************************************/ + +#define XSNS_85 85 +#define XI2C_58 58 // See I2CDEVICES.md + +#define MPU6886_ADDRESS 0x68 + +struct { + MPU6886 Mpu; + bool ready = false; + int16_t ax=0, ay=0, az=0; // accelerator data + int16_t gyx=0, gyy=0, gyz=0; // accelerator data +} mpu6886_sensor; + +/********************************************************************************************/ + +const char HTTP_MPU6686[] PROGMEM = + "{s}MPU6686 acc_x" "{m}%3_f G" "{e}" + "{s}MPU6686 acc_y" "{m}%3_f G" "{e}" + "{s}MPU6686 acc_z" "{m}%3_f G" "{e}" + "{s}MPU6686 gyr_x" "{m}%i dps" "{e}" + "{s}MPU6686 gyr_y" "{m}%i dps" "{e}" + "{s}MPU6686 gyr_z" "{m}%i dps" "{e}" + ; + +void MPU6686_Show(uint32_t json) { + if (json) { + ResponseAppend_P(PSTR(",\"MPU6686\":{\"AX\":%i,\"AY\":%i,\"AZ\":%i,\"GX\":%i,\"GY\":%i,\"GZ\":%i}"), + mpu6886_sensor.ax, mpu6886_sensor.ay, mpu6886_sensor.az, + mpu6886_sensor.gyx, mpu6886_sensor.gyy, mpu6886_sensor.gyz); + } else { + float ax = mpu6886_sensor.ax / 1000.0f; + float ay = mpu6886_sensor.ay / 1000.0f; + float az = mpu6886_sensor.az / 1000.0f; + WSContentSend_PD(HTTP_MPU6686, &ax, &ay, &az, + mpu6886_sensor.gyx, mpu6886_sensor.gyy, mpu6886_sensor.gyz); + + } +} + +void MPU6686Detect(void) { +#ifdef ESP32 + if (!I2cSetDevice(MPU6886_ADDRESS, 0)) { + if (!I2cSetDevice(MPU6886_ADDRESS, 1)) { return; } // check on bus 1 + mpu6886_sensor.Mpu.setBus(1); // switch to bus 1 + I2cSetActiveFound(MPU6886_ADDRESS, "MPU6886", 1); + } else { + I2cSetActiveFound(MPU6886_ADDRESS, "MPU6886", 0); + } +#else + if (!I2cSetDevice(MPU6886_ADDRESS)) { return; } + I2cSetActiveFound(MPU6886_ADDRESS, "MPU6886"); +#endif + + mpu6886_sensor.Mpu.Init(); + mpu6886_sensor.ready = true; +} + +void MPU6886Every_Second(void) { + mpu6886_sensor.Mpu.getAccelDataInt(&mpu6886_sensor.ax, &mpu6886_sensor.ay, &mpu6886_sensor.az); + mpu6886_sensor.Mpu.getGyroDataInt(&mpu6886_sensor.gyx, &mpu6886_sensor.gyy, &mpu6886_sensor.gyz); + + // AddLog(LOG_LEVEL_DEBUG, PSTR(">> Acc x=%i y=%i z=%i gx=%i gy=%i gz=%i"), mpu6886_sensor.ax, mpu6886_sensor.ay, mpu6886_sensor.az, + // mpu6886_sensor.gyx, mpu6886_sensor.gyy, mpu6886_sensor.gyz); + +} + +/*********************************************************************************************\ + * Interface +\*********************************************************************************************/ + +bool Xsns85(uint8_t function) { + if (!I2cEnabled(XI2C_58)) { return false; } + + bool result = false; + + if (FUNC_INIT == function) { + MPU6686Detect(); + } + else if (mpu6886_sensor.ready) { + switch (function) { + case FUNC_EVERY_SECOND: + MPU6886Every_Second(); + break; + case FUNC_JSON_APPEND: + MPU6686_Show(1); + break; +#ifdef USE_WEBSERVER + case FUNC_WEB_SENSOR: + MPU6686_Show(0); + break; +#endif // USE_WEBSERVER + } + } + return result; +} + +#endif // USE_MPU6886 +#endif // USE_I2C \ No newline at end of file