Added SensorsLib
This commit is contained in:
parent
aae1df111f
commit
672a563dc3
42 changed files with 7819 additions and 0 deletions
5
lib/SensorsLib/CMakeLists.txt
Normal file
5
lib/SensorsLib/CMakeLists.txt
Normal file
|
|
@ -0,0 +1,5 @@
|
|||
set(src_dirs ./src)
|
||||
set(include_dirs ./src
|
||||
./src/REG)
|
||||
idf_component_register(SRC_DIRS ${src_dirs} INCLUDE_DIRS ${include_dirs})
|
||||
|
||||
21
lib/SensorsLib/LICENSE
Normal file
21
lib/SensorsLib/LICENSE
Normal file
|
|
@ -0,0 +1,21 @@
|
|||
MIT License
|
||||
|
||||
Copyright (c) 2022 lewis he
|
||||
|
||||
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.
|
||||
17
lib/SensorsLib/README.md
Normal file
17
lib/SensorsLib/README.md
Normal file
|
|
@ -0,0 +1,17 @@
|
|||
```
|
||||
_____ _ _ _
|
||||
/ ____| | | (_) |
|
||||
| (___ ___ _ __ ___ ___ _ __ ___| | _| |__
|
||||
\___ \ / _ \ '_ \/ __|/ _ \| '__/ __| | | | '_ \
|
||||
____) | __/ | | \__ \ (_) | | \__ \ |____| | |_) |
|
||||
|_____/ \___|_| |_|___/\___/|_| |___/______|_|_.__/
|
||||
|
||||
|
||||
```
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
BIN
lib/SensorsLib/datasheet/QMC6310 Datasheet Rev.C.pdf
Normal file
BIN
lib/SensorsLib/datasheet/QMC6310 Datasheet Rev.C.pdf
Normal file
Binary file not shown.
BIN
lib/SensorsLib/datasheet/QMI8658A Datasheet Rev1.0.pdf
Normal file
BIN
lib/SensorsLib/datasheet/QMI8658A Datasheet Rev1.0.pdf
Normal file
Binary file not shown.
|
|
@ -0,0 +1,237 @@
|
|||
/**
|
||||
*
|
||||
* @license MIT License
|
||||
*
|
||||
* Copyright (c) 2022 lewis he
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
* @file QMC6310_CalibrateExample.ino
|
||||
* @author Lewis He (lewishe@outlook.com)
|
||||
* @date 2022-10-16
|
||||
*
|
||||
*/
|
||||
#include <Wire.h>
|
||||
#include <SPI.h>
|
||||
#include <Arduino.h>
|
||||
#include "SensorQMC6310.hpp"
|
||||
|
||||
#define I2C1_SDA 17
|
||||
#define I2C1_SCL 18
|
||||
|
||||
SensorQMC6310 qmc;
|
||||
|
||||
|
||||
void calibrate()
|
||||
{
|
||||
qmc.setDataOutputRate(SensorQMC6310::DATARATE_200HZ);
|
||||
|
||||
int32_t x_min = 65535;
|
||||
int32_t x_max = -65535;
|
||||
int32_t y_min = 65535;
|
||||
int32_t y_max = -65535;
|
||||
int32_t z_min = 65535;
|
||||
int32_t z_max = -65535;
|
||||
Serial.println("Place the sensor on the plane and slowly rotate the sensor...");
|
||||
|
||||
int32_t range = 1000;
|
||||
int32_t i = 0;
|
||||
int32_t x = 0, y = 0, z = 0;;
|
||||
float a = 0.5 ;
|
||||
float x_offset = 0;
|
||||
float y_offset = 0;
|
||||
float z_offset = 0;
|
||||
|
||||
while (i < range) {
|
||||
i += 1;
|
||||
|
||||
if (qmc.isDataReady()) {
|
||||
|
||||
qmc.readData();
|
||||
|
||||
x = a * qmc.getRawX() + (1 - a) * x;
|
||||
y = a * qmc.getRawY() + (1 - a) * y;
|
||||
z = a * qmc.getRawZ() + (1 - a) * z;
|
||||
if (x < x_min) {
|
||||
x_min = x;
|
||||
i = 0;
|
||||
}
|
||||
if (x > x_max) {
|
||||
x_max = x;
|
||||
i = 0;
|
||||
}
|
||||
if (y < y_min) {
|
||||
y_min = y;
|
||||
i = 0;
|
||||
}
|
||||
if (y > y_max) {
|
||||
y_max = y;
|
||||
i = 0;
|
||||
}
|
||||
if (z < z_min) {
|
||||
z_min = z;
|
||||
i = 0;
|
||||
}
|
||||
if (z > z_max) {
|
||||
z_max = z;
|
||||
i = 0;
|
||||
}
|
||||
int j = round(10 * i / range);
|
||||
|
||||
Serial.print("[");
|
||||
for (int k = 0; k < j; ++k) {
|
||||
Serial.print("*");
|
||||
}
|
||||
Serial.println("]");
|
||||
}
|
||||
delay(5);
|
||||
}
|
||||
|
||||
x_offset = (x_max + x_min) / 2;
|
||||
y_offset = (y_max + y_min) / 2;
|
||||
z_offset = (z_max + z_min) / 2;
|
||||
|
||||
Serial.printf("x_min:%d x_max:%d y_min:%d y_max:%d z_min:%d z_max:%d\n", x_min, x_max, y_min, y_max, z_min, z_max);
|
||||
Serial.printf("x_offset:%.2f y_offset:%.2f z_offset:%.2f \n", x_offset, y_offset, z_offset);
|
||||
|
||||
// Set the calibration value and the user calculates the deviation
|
||||
qmc.setOffset(x_offset, y_offset, z_offset);
|
||||
}
|
||||
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(115200);
|
||||
while (!Serial);
|
||||
|
||||
#ifdef LILYGO_TBEAM_SUPREME_V3_0
|
||||
extern bool setupPower();
|
||||
setupPower();
|
||||
#endif
|
||||
|
||||
if (!qmc.begin(Wire, QMC6310_SLAVE_ADDRESS, I2C1_SDA, I2C1_SCL)) {
|
||||
Serial.println("Failed to find QMC6310 - check your wiring!");
|
||||
while (1) {
|
||||
delay(1000);
|
||||
}
|
||||
}
|
||||
|
||||
/* Get Magnetometer chip id*/
|
||||
Serial.print("Device ID:");
|
||||
Serial.println(qmc.getChipID(), HEX);
|
||||
|
||||
/* Config Magnetometer */
|
||||
qmc.configMagnetometer(
|
||||
/*
|
||||
* Run Mode
|
||||
* MODE_SUSPEND
|
||||
* MODE_NORMAL
|
||||
* MODE_SINGLE
|
||||
* MODE_CONTINUOUS
|
||||
* * */
|
||||
SensorQMC6310::MODE_CONTINUOUS,
|
||||
/*
|
||||
* Full Range
|
||||
* RANGE_30G
|
||||
* RANGE_12G
|
||||
* RANGE_8G
|
||||
* RANGE_2G
|
||||
* * */
|
||||
SensorQMC6310::RANGE_8G,
|
||||
/*
|
||||
* Output data rate
|
||||
* DATARATE_10HZ
|
||||
* DATARATE_50HZ
|
||||
* DATARATE_100HZ
|
||||
* DATARATE_200HZ
|
||||
* * */
|
||||
SensorQMC6310::DATARATE_200HZ,
|
||||
/*
|
||||
* Over sample Ratio1
|
||||
* OSR_8
|
||||
* OSR_4
|
||||
* OSR_2
|
||||
* OSR_1
|
||||
* * * */
|
||||
SensorQMC6310::OSR_1,
|
||||
|
||||
/*
|
||||
* Down sample Ratio1
|
||||
* DSR_8
|
||||
* DSR_4
|
||||
* DSR_2
|
||||
* DSR_1
|
||||
* * */
|
||||
SensorQMC6310::DSR_1);
|
||||
|
||||
|
||||
|
||||
|
||||
// Calibration algorithm reference from
|
||||
// https://github.com/CoreElectronics/CE-PiicoDev-QMC6310-MicroPython-Module
|
||||
calibrate();
|
||||
|
||||
Serial.println("Calibration done .");
|
||||
delay(5000);
|
||||
|
||||
Serial.println("Read data now...");
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
|
||||
//Wiat data ready
|
||||
if (qmc.isDataReady()) {
|
||||
|
||||
qmc.readData();
|
||||
|
||||
Serial.print("GYR: ");
|
||||
Serial.print("X:");
|
||||
Serial.print(qmc.getX());
|
||||
Serial.print(" Y:");
|
||||
Serial.print(qmc.getY());
|
||||
Serial.print(" Z:");
|
||||
Serial.print(qmc.getZ());
|
||||
Serial.println(" uT");
|
||||
Serial.print("RAW: ");
|
||||
Serial.print("X:");
|
||||
Serial.print(qmc.getRawX());
|
||||
Serial.print(" Y:");
|
||||
Serial.print(qmc.getRawY());
|
||||
Serial.print(" Z:");
|
||||
Serial.println(qmc.getRawZ());
|
||||
|
||||
/*
|
||||
float x, y, z;
|
||||
qmc.getMag(x, y, z);
|
||||
Serial.print("X:");
|
||||
Serial.print(x);
|
||||
Serial.print(" Y:");
|
||||
Serial.print(y);
|
||||
Serial.print(" Z:");
|
||||
Serial.println(x);
|
||||
*/
|
||||
}
|
||||
|
||||
|
||||
delay(100);
|
||||
}
|
||||
|
||||
|
||||
|
||||
167
lib/SensorsLib/examples/QMC6310_CalibrateExample/power.cpp
Normal file
167
lib/SensorsLib/examples/QMC6310_CalibrateExample/power.cpp
Normal file
|
|
@ -0,0 +1,167 @@
|
|||
/**
|
||||
* @file power.cpp
|
||||
* @author Lewis He (lewishe@outlook.com)
|
||||
* @license MIT
|
||||
* @copyright Copyright (c) 2022
|
||||
* @date 2022-10-25
|
||||
*
|
||||
*/
|
||||
|
||||
|
||||
#ifdef LILYGO_TBEAM_SUPREME_V3_0
|
||||
#include <Wire.h>
|
||||
#include "XPowersAXP2101.tpp"
|
||||
#include "XPowersAXP192.tpp"
|
||||
|
||||
|
||||
|
||||
#define I2C_SDA 42
|
||||
#define I2C_SCL 41
|
||||
#define PMU_IRQ 40
|
||||
|
||||
XPowersLibInterface *PMU = NULL;
|
||||
|
||||
bool setupPower()
|
||||
{
|
||||
Serial.println("setupPower");
|
||||
|
||||
if (!PMU) {
|
||||
PMU = new XPowersAXP2101(Wire1, I2C_SDA, I2C_SCL);
|
||||
if (!PMU->init()) {
|
||||
Serial.println("Warning: Failed to find AXP2101 power management");
|
||||
delete PMU;
|
||||
PMU = NULL;
|
||||
} else {
|
||||
Serial.println("AXP2101 PMU init succeeded, using AXP2101 PMU");
|
||||
}
|
||||
}
|
||||
|
||||
if (!PMU) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (PMU->getChipModel() == XPOWERS_AXP2101) {
|
||||
|
||||
#if defined(LILYGO_TBEAM_V1_2)
|
||||
|
||||
PMU->setProtectedChannel(XPOWERS_DCDC1);
|
||||
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC2);
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC3);
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC4);
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC5);
|
||||
|
||||
// PMU->disablePowerOutput(XPOWERS_ALDO1);
|
||||
// PMU->disablePowerOutput(XPOWERS_ALDO2);
|
||||
// PMU->disablePowerOutput(XPOWERS_ALDO3);
|
||||
PMU->disablePowerOutput(XPOWERS_ALDO4);
|
||||
|
||||
PMU->disablePowerOutput(XPOWERS_BLDO1);
|
||||
PMU->disablePowerOutput(XPOWERS_BLDO2);
|
||||
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO1);
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO2);
|
||||
|
||||
PMU->enablePowerOutput(XPOWERS_VBACKUP);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO1);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO2);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO3);
|
||||
|
||||
PMU->setChargeTargetVoltage(XPOWERS_AXP2101_CHG_VOL_4V4);
|
||||
|
||||
#elif defined(LILYGO_TBEAM_SUPREME_V3_0)
|
||||
|
||||
//t-beam m.2 inface
|
||||
//gps
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO4, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO4);
|
||||
|
||||
// lora
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO3, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO3);
|
||||
|
||||
// Sensor
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO1, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO1);
|
||||
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO2, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO2);
|
||||
|
||||
//Sdcard
|
||||
PMU->setPowerChannelVoltage(XPOWERS_BLDO1, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_BLDO1);
|
||||
|
||||
//face m.2
|
||||
PMU->setPowerChannelVoltage(XPOWERS_DCDC3, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_DCDC3);
|
||||
|
||||
PMU->setPowerChannelVoltage(XPOWERS_DCDC4, XPOWERS_AXP2101_DCDC4_VOL2_MAX);
|
||||
PMU->enablePowerOutput(XPOWERS_DCDC4);
|
||||
|
||||
PMU->setPowerChannelVoltage(XPOWERS_DCDC5, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_DCDC5);
|
||||
|
||||
|
||||
//not use channel
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC2);
|
||||
// PMU->disablePowerOutput(XPOWERS_DCDC4);
|
||||
// PMU->disablePowerOutput(XPOWERS_DCDC5);
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO1);
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO2);
|
||||
PMU->disablePowerOutput(XPOWERS_VBACKUP);
|
||||
|
||||
#endif
|
||||
}
|
||||
|
||||
PMU->enableSystemVoltageMeasure();
|
||||
PMU->enableVbusVoltageMeasure();
|
||||
PMU->enableBattVoltageMeasure();
|
||||
PMU->disableTSPinMeasure();
|
||||
|
||||
Serial.printf("=========================================\n");
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC1)) {
|
||||
Serial.printf("DC1 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC1) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC1));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC2)) {
|
||||
Serial.printf("DC2 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC2));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC3)) {
|
||||
Serial.printf("DC3 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC3) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC3));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC4)) {
|
||||
Serial.printf("DC4 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC4) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC4));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC5)) {
|
||||
Serial.printf("DC5 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC5) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC5));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_LDO2)) {
|
||||
Serial.printf("LDO2 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_LDO2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_LDO2));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_LDO3)) {
|
||||
Serial.printf("LDO3 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_LDO3) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_LDO3));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO1)) {
|
||||
Serial.printf("ALDO1: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO1) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO1));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO2)) {
|
||||
Serial.printf("ALDO2: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO2));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO3)) {
|
||||
Serial.printf("ALDO3: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO3) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO3));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO4)) {
|
||||
Serial.printf("ALDO4: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO4) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO4));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_BLDO1)) {
|
||||
Serial.printf("BLDO1: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_BLDO1) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_BLDO1));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_BLDO2)) {
|
||||
Serial.printf("BLDO2: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_BLDO2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_BLDO2));
|
||||
}
|
||||
Serial.printf("=========================================\n");
|
||||
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
@ -0,0 +1,212 @@
|
|||
/**
|
||||
*
|
||||
* @license MIT License
|
||||
*
|
||||
* Copyright (c) 2022 lewis he
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
* @file QMC6310_GetDataExample.ino
|
||||
* @author Lewis He (lewishe@outlook.com)
|
||||
* @date 2022-10-16
|
||||
*
|
||||
*/
|
||||
#include <Wire.h>
|
||||
#include <SPI.h>
|
||||
#include <Arduino.h>
|
||||
#include "SensorQMC6310.hpp"
|
||||
#include "SH1106Wire.h" //Oled display from https://github.com/ThingPulse/esp8266-oled-ssd1306
|
||||
|
||||
#define I2C1_SDA 17
|
||||
#define I2C1_SCL 18
|
||||
|
||||
SH1106Wire display(0x3c, I2C1_SDA, I2C1_SCL);
|
||||
SensorQMC6310 qmc;
|
||||
|
||||
int last_dx, last_dy, dx, dy, angle;
|
||||
|
||||
const int centreX = 32;
|
||||
const int centreY = 30;
|
||||
const int radius = 22;
|
||||
|
||||
//Compass application from https://github.com/G6EJD/ESP8266_micro_compass_HMC5883_OLED
|
||||
void arrow(int x2, int y2, int x1, int y1, int alength, int awidth, OLEDDISPLAY_COLOR color)
|
||||
{
|
||||
display.setColor(color);
|
||||
float distance;
|
||||
int dx, dy, x2o, y2o, x3, y3, x4, y4, k;
|
||||
distance = sqrt(pow((x1 - x2), 2) + pow((y1 - y2), 2));
|
||||
dx = x2 + (x1 - x2) * alength / distance;
|
||||
dy = y2 + (y1 - y2) * alength / distance;
|
||||
k = awidth / alength;
|
||||
x2o = x2 - dx;
|
||||
y2o = dy - y2;
|
||||
x3 = y2o * k + dx;
|
||||
y3 = x2o * k + dy;
|
||||
x4 = dx - y2o * k;
|
||||
y4 = dy - x2o * k;
|
||||
display.drawLine(x1, y1, x2, y2);
|
||||
display.drawLine(x1, y1, dx, dy);
|
||||
display.drawLine(x3, y3, x4, y4);
|
||||
display.drawLine(x3, y3, x2, y2);
|
||||
display.drawLine(x2, y2, x4, y4);
|
||||
}
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(115200);
|
||||
while (!Serial);
|
||||
|
||||
#ifdef LILYGO_TBEAM_SUPREME_V3_0
|
||||
extern bool setupPower();
|
||||
setupPower();
|
||||
#endif
|
||||
|
||||
if (!qmc.begin(Wire, QMC6310_SLAVE_ADDRESS, I2C1_SDA, I2C1_SCL)) {
|
||||
Serial.println("Failed to find QMC6310 - check your wiring!");
|
||||
while (1) {
|
||||
delay(1000);
|
||||
}
|
||||
}
|
||||
|
||||
display.init();
|
||||
|
||||
last_dx = centreX;
|
||||
last_dy = centreY;
|
||||
|
||||
/* Get Magnetometer chip id*/
|
||||
Serial.print("Device ID:");
|
||||
Serial.println(qmc.getChipID(), HEX);
|
||||
|
||||
/* Config Magnetometer */
|
||||
int r = qmc.configMagnetometer(
|
||||
/*
|
||||
* Run Mode
|
||||
* MODE_SUSPEND
|
||||
* MODE_NORMAL
|
||||
* MODE_SINGLE
|
||||
* MODE_CONTINUOUS
|
||||
* * */
|
||||
SensorQMC6310::MODE_NORMAL,
|
||||
/*
|
||||
* Full Range
|
||||
* RANGE_30G
|
||||
* RANGE_12G
|
||||
* RANGE_8G
|
||||
* RANGE_2G
|
||||
* * */
|
||||
SensorQMC6310::RANGE_2G,
|
||||
/*
|
||||
* Output data rate
|
||||
* DATARATE_10HZ
|
||||
* DATARATE_50HZ
|
||||
* DATARATE_100HZ
|
||||
* DATARATE_200HZ
|
||||
* * */
|
||||
SensorQMC6310::DATARATE_100HZ,
|
||||
/*
|
||||
* Over sample Ratio1
|
||||
* OSR_8
|
||||
* OSR_4
|
||||
* OSR_2
|
||||
* OSR_1
|
||||
* * * */
|
||||
SensorQMC6310::OSR_1,
|
||||
|
||||
/*
|
||||
* Down sample Ratio1
|
||||
* DSR_8
|
||||
* DSR_4
|
||||
* DSR_2
|
||||
* DSR_1
|
||||
* * */
|
||||
SensorQMC6310::DSR_1);
|
||||
|
||||
if (r != DEV_WIRE_NONE) {
|
||||
Serial.println("Device config failed!");
|
||||
while (1)delay(1000);
|
||||
}
|
||||
|
||||
// Print register configuration information
|
||||
qmc.dumpCtrlRegister();
|
||||
|
||||
Serial.println("Read data now...");
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
|
||||
//Wiat data ready
|
||||
if (qmc.isDataReady()) {
|
||||
|
||||
qmc.readData();
|
||||
|
||||
|
||||
display.drawString(29, 0, "N");
|
||||
display.drawString( 0, 28, "W");
|
||||
display.drawString(60, 28, "E");
|
||||
display.drawString(29, 53, "S");
|
||||
|
||||
display.drawLine(1, 1, 7, 7);
|
||||
display.drawLine(62, 1, 56, 7);
|
||||
display.drawLine(1, 62, 7, 56);
|
||||
display.drawLine(56, 56, 62, 62);
|
||||
|
||||
//Compass application from https://github.com/G6EJD/ESP8266_micro_compass_HMC5883_OLED
|
||||
float heading = atan2(qmc.getY(), qmc.getX()); // Result is in radians
|
||||
// Now add the 'Declination Angle' for you location. Declination is the variation in magnetic field at your location.
|
||||
// Find your declination here: http://www.magnetic-declination.com/
|
||||
// At my location it is : -2° 20' W, or -2.33 Degrees, which needs to be in radians so = -2.33 / 180 * PI = -0.041 West is + E is -
|
||||
// Make declination = 0 if you can't find your Declination value, the error is negible for nearly all locations
|
||||
float declination = -0.041;
|
||||
heading = heading + declination;
|
||||
|
||||
if (heading < 0) heading += 2 * PI; // Correct for when signs are reversed.
|
||||
if (heading > 2 * PI) heading -= 2 * PI; // Correct for when heading exceeds 360-degree, especially when declination is included
|
||||
angle = int(heading * 180 / M_PI); // Convert radians to degrees for more a more usual result
|
||||
// For the screen -X = up and +X = down and -Y = left and +Y = right, so does not follow coordinate conventions
|
||||
dx = (0.7 * radius * cos((angle - 90) * 3.14 / 180)) + centreX; // calculate X position for the screen coordinates - can be confusing!
|
||||
dy = (0.7 * radius * sin((angle - 90) * 3.14 / 180)) + centreY; // calculate Y position for the screen coordinates - can be confusing!
|
||||
arrow(last_dx, last_dy, centreX, centreY, 2, 2, BLACK); // Erase last arrow
|
||||
arrow(dx, dy, centreX, centreY, 2, 2, WHITE); // Draw arrow in new position
|
||||
|
||||
display.setColor(BLACK);
|
||||
display.fillRect(80, 50, 25, 48);
|
||||
display.setColor(WHITE);
|
||||
display.drawString(80, 50, String(angle) + "°");
|
||||
display.display();
|
||||
|
||||
last_dx = dx;
|
||||
last_dy = dy;
|
||||
|
||||
// for debug.
|
||||
Serial.print("GYR: ");
|
||||
Serial.print("X:");
|
||||
Serial.print(qmc.getX());
|
||||
Serial.print(" Y:");
|
||||
Serial.print(qmc.getY());
|
||||
Serial.print(" Z:");
|
||||
Serial.print(qmc.getZ());
|
||||
Serial.println(" uT");
|
||||
}
|
||||
|
||||
|
||||
delay(100);
|
||||
}
|
||||
|
||||
167
lib/SensorsLib/examples/QMC6310_CompassExample/power.cpp
Normal file
167
lib/SensorsLib/examples/QMC6310_CompassExample/power.cpp
Normal file
|
|
@ -0,0 +1,167 @@
|
|||
/**
|
||||
* @file power.cpp
|
||||
* @author Lewis He (lewishe@outlook.com)
|
||||
* @license MIT
|
||||
* @copyright Copyright (c) 2022
|
||||
* @date 2022-10-25
|
||||
*
|
||||
*/
|
||||
|
||||
|
||||
#ifdef LILYGO_TBEAM_SUPREME_V3_0
|
||||
#include <Wire.h>
|
||||
#include "XPowersAXP2101.tpp"
|
||||
#include "XPowersAXP192.tpp"
|
||||
|
||||
|
||||
|
||||
#define I2C_SDA 42
|
||||
#define I2C_SCL 41
|
||||
#define PMU_IRQ 40
|
||||
|
||||
XPowersLibInterface *PMU = NULL;
|
||||
|
||||
bool setupPower()
|
||||
{
|
||||
Serial.println("setupPower");
|
||||
|
||||
if (!PMU) {
|
||||
PMU = new XPowersAXP2101(Wire1, I2C_SDA, I2C_SCL);
|
||||
if (!PMU->init()) {
|
||||
Serial.println("Warning: Failed to find AXP2101 power management");
|
||||
delete PMU;
|
||||
PMU = NULL;
|
||||
} else {
|
||||
Serial.println("AXP2101 PMU init succeeded, using AXP2101 PMU");
|
||||
}
|
||||
}
|
||||
|
||||
if (!PMU) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (PMU->getChipModel() == XPOWERS_AXP2101) {
|
||||
|
||||
#if defined(LILYGO_TBEAM_V1_2)
|
||||
|
||||
PMU->setProtectedChannel(XPOWERS_DCDC1);
|
||||
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC2);
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC3);
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC4);
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC5);
|
||||
|
||||
// PMU->disablePowerOutput(XPOWERS_ALDO1);
|
||||
// PMU->disablePowerOutput(XPOWERS_ALDO2);
|
||||
// PMU->disablePowerOutput(XPOWERS_ALDO3);
|
||||
PMU->disablePowerOutput(XPOWERS_ALDO4);
|
||||
|
||||
PMU->disablePowerOutput(XPOWERS_BLDO1);
|
||||
PMU->disablePowerOutput(XPOWERS_BLDO2);
|
||||
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO1);
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO2);
|
||||
|
||||
PMU->enablePowerOutput(XPOWERS_VBACKUP);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO1);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO2);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO3);
|
||||
|
||||
PMU->setChargeTargetVoltage(XPOWERS_AXP2101_CHG_VOL_4V4);
|
||||
|
||||
#elif defined(LILYGO_TBEAM_SUPREME_V3_0)
|
||||
|
||||
//t-beam m.2 inface
|
||||
//gps
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO4, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO4);
|
||||
|
||||
// lora
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO3, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO3);
|
||||
|
||||
// Sensor
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO1, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO1);
|
||||
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO2, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO2);
|
||||
|
||||
//Sdcard
|
||||
PMU->setPowerChannelVoltage(XPOWERS_BLDO1, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_BLDO1);
|
||||
|
||||
//face m.2
|
||||
PMU->setPowerChannelVoltage(XPOWERS_DCDC3, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_DCDC3);
|
||||
|
||||
PMU->setPowerChannelVoltage(XPOWERS_DCDC4, XPOWERS_AXP2101_DCDC4_VOL2_MAX);
|
||||
PMU->enablePowerOutput(XPOWERS_DCDC4);
|
||||
|
||||
PMU->setPowerChannelVoltage(XPOWERS_DCDC5, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_DCDC5);
|
||||
|
||||
|
||||
//not use channel
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC2);
|
||||
// PMU->disablePowerOutput(XPOWERS_DCDC4);
|
||||
// PMU->disablePowerOutput(XPOWERS_DCDC5);
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO1);
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO2);
|
||||
PMU->disablePowerOutput(XPOWERS_VBACKUP);
|
||||
|
||||
#endif
|
||||
}
|
||||
|
||||
PMU->enableSystemVoltageMeasure();
|
||||
PMU->enableVbusVoltageMeasure();
|
||||
PMU->enableBattVoltageMeasure();
|
||||
PMU->disableTSPinMeasure();
|
||||
|
||||
Serial.printf("=========================================\n");
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC1)) {
|
||||
Serial.printf("DC1 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC1) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC1));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC2)) {
|
||||
Serial.printf("DC2 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC2));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC3)) {
|
||||
Serial.printf("DC3 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC3) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC3));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC4)) {
|
||||
Serial.printf("DC4 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC4) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC4));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC5)) {
|
||||
Serial.printf("DC5 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC5) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC5));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_LDO2)) {
|
||||
Serial.printf("LDO2 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_LDO2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_LDO2));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_LDO3)) {
|
||||
Serial.printf("LDO3 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_LDO3) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_LDO3));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO1)) {
|
||||
Serial.printf("ALDO1: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO1) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO1));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO2)) {
|
||||
Serial.printf("ALDO2: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO2));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO3)) {
|
||||
Serial.printf("ALDO3: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO3) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO3));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO4)) {
|
||||
Serial.printf("ALDO4: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO4) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO4));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_BLDO1)) {
|
||||
Serial.printf("BLDO1: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_BLDO1) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_BLDO1));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_BLDO2)) {
|
||||
Serial.printf("BLDO2: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_BLDO2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_BLDO2));
|
||||
}
|
||||
Serial.printf("=========================================\n");
|
||||
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
@ -0,0 +1,149 @@
|
|||
/**
|
||||
*
|
||||
* @license MIT License
|
||||
*
|
||||
* Copyright (c) 2022 lewis he
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
* @file QMC6310_GetDataExample.ino
|
||||
* @author Lewis He (lewishe@outlook.com)
|
||||
* @date 2022-10-16
|
||||
*
|
||||
*/
|
||||
#include <Wire.h>
|
||||
#include <SPI.h>
|
||||
#include <Arduino.h>
|
||||
#include "SensorQMC6310.hpp"
|
||||
|
||||
#define I2C1_SDA 17
|
||||
#define I2C1_SCL 18
|
||||
|
||||
SensorQMC6310 qmc;
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(115200);
|
||||
while (!Serial);
|
||||
|
||||
#ifdef LILYGO_TBEAM_SUPREME_V3_0
|
||||
extern bool setupPower();
|
||||
setupPower();
|
||||
#endif
|
||||
|
||||
if (!qmc.begin(Wire, QMC6310_SLAVE_ADDRESS, I2C1_SDA, I2C1_SCL)) {
|
||||
Serial.println("Failed to find QMC6310 - check your wiring!");
|
||||
while (1) {
|
||||
delay(1000);
|
||||
}
|
||||
}
|
||||
|
||||
/* Get Magnetometer chip id*/
|
||||
Serial.print("Device ID:");
|
||||
Serial.println(qmc.getChipID(), HEX);
|
||||
|
||||
/* Config Magnetometer */
|
||||
qmc.configMagnetometer(
|
||||
/*
|
||||
* Run Mode
|
||||
* MODE_SUSPEND
|
||||
* MODE_NORMAL
|
||||
* MODE_SINGLE
|
||||
* MODE_CONTINUOUS
|
||||
* * */
|
||||
SensorQMC6310::MODE_CONTINUOUS,
|
||||
/*
|
||||
* Full Range
|
||||
* RANGE_30G
|
||||
* RANGE_12G
|
||||
* RANGE_8G
|
||||
* RANGE_2G
|
||||
* * */
|
||||
SensorQMC6310::RANGE_8G,
|
||||
/*
|
||||
* Output data rate
|
||||
* DATARATE_10HZ
|
||||
* DATARATE_50HZ
|
||||
* DATARATE_100HZ
|
||||
* DATARATE_200HZ
|
||||
* * */
|
||||
SensorQMC6310::DATARATE_200HZ,
|
||||
/*
|
||||
* Over sample Ratio1
|
||||
* OSR_8
|
||||
* OSR_4
|
||||
* OSR_2
|
||||
* OSR_1
|
||||
* * * */
|
||||
SensorQMC6310::OSR_1,
|
||||
|
||||
/*
|
||||
* Down sample Ratio1
|
||||
* DSR_8
|
||||
* DSR_4
|
||||
* DSR_2
|
||||
* DSR_1
|
||||
* * */
|
||||
SensorQMC6310::DSR_1);
|
||||
|
||||
Serial.println("Read data now...");
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
|
||||
//Wiat data ready
|
||||
if (qmc.isDataReady()) {
|
||||
|
||||
qmc.readData();
|
||||
|
||||
Serial.print("GYR: ");
|
||||
Serial.print("X:");
|
||||
Serial.print(qmc.getX());
|
||||
Serial.print(" Y:");
|
||||
Serial.print(qmc.getY());
|
||||
Serial.print(" Z:");
|
||||
Serial.print(qmc.getZ());
|
||||
Serial.println(" uT");
|
||||
Serial.print("RAW: ");
|
||||
Serial.print("X:");
|
||||
Serial.print(qmc.getRawX());
|
||||
Serial.print(" Y:");
|
||||
Serial.print(qmc.getRawY());
|
||||
Serial.print(" Z:");
|
||||
Serial.println(qmc.getRawZ());
|
||||
|
||||
/*
|
||||
float x, y, z;
|
||||
qmc.getMag(x, y, z);
|
||||
Serial.print("X:");
|
||||
Serial.print(x);
|
||||
Serial.print(" Y:");
|
||||
Serial.print(y);
|
||||
Serial.print(" Z:");
|
||||
Serial.println(x);
|
||||
*/
|
||||
}
|
||||
|
||||
|
||||
delay(100);
|
||||
}
|
||||
|
||||
|
||||
|
||||
167
lib/SensorsLib/examples/QMC6310_GetDataExample/power.cpp
Normal file
167
lib/SensorsLib/examples/QMC6310_GetDataExample/power.cpp
Normal file
|
|
@ -0,0 +1,167 @@
|
|||
/**
|
||||
* @file power.cpp
|
||||
* @author Lewis He (lewishe@outlook.com)
|
||||
* @license MIT
|
||||
* @copyright Copyright (c) 2022
|
||||
* @date 2022-10-25
|
||||
*
|
||||
*/
|
||||
|
||||
|
||||
#ifdef LILYGO_TBEAM_SUPREME_V3_0
|
||||
#include <Wire.h>
|
||||
#include "XPowersAXP2101.tpp"
|
||||
#include "XPowersAXP192.tpp"
|
||||
|
||||
|
||||
|
||||
#define I2C_SDA 42
|
||||
#define I2C_SCL 41
|
||||
#define PMU_IRQ 40
|
||||
|
||||
XPowersLibInterface *PMU = NULL;
|
||||
|
||||
bool setupPower()
|
||||
{
|
||||
Serial.println("setupPower");
|
||||
|
||||
if (!PMU) {
|
||||
PMU = new XPowersAXP2101(Wire1, I2C_SDA, I2C_SCL);
|
||||
if (!PMU->init()) {
|
||||
Serial.println("Warning: Failed to find AXP2101 power management");
|
||||
delete PMU;
|
||||
PMU = NULL;
|
||||
} else {
|
||||
Serial.println("AXP2101 PMU init succeeded, using AXP2101 PMU");
|
||||
}
|
||||
}
|
||||
|
||||
if (!PMU) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (PMU->getChipModel() == XPOWERS_AXP2101) {
|
||||
|
||||
#if defined(LILYGO_TBEAM_V1_2)
|
||||
|
||||
PMU->setProtectedChannel(XPOWERS_DCDC1);
|
||||
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC2);
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC3);
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC4);
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC5);
|
||||
|
||||
// PMU->disablePowerOutput(XPOWERS_ALDO1);
|
||||
// PMU->disablePowerOutput(XPOWERS_ALDO2);
|
||||
// PMU->disablePowerOutput(XPOWERS_ALDO3);
|
||||
PMU->disablePowerOutput(XPOWERS_ALDO4);
|
||||
|
||||
PMU->disablePowerOutput(XPOWERS_BLDO1);
|
||||
PMU->disablePowerOutput(XPOWERS_BLDO2);
|
||||
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO1);
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO2);
|
||||
|
||||
PMU->enablePowerOutput(XPOWERS_VBACKUP);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO1);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO2);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO3);
|
||||
|
||||
PMU->setChargeTargetVoltage(XPOWERS_AXP2101_CHG_VOL_4V4);
|
||||
|
||||
#elif defined(LILYGO_TBEAM_SUPREME_V3_0)
|
||||
|
||||
//t-beam m.2 inface
|
||||
//gps
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO4, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO4);
|
||||
|
||||
// lora
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO3, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO3);
|
||||
|
||||
// Sensor
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO1, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO1);
|
||||
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO2, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO2);
|
||||
|
||||
//Sdcard
|
||||
PMU->setPowerChannelVoltage(XPOWERS_BLDO1, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_BLDO1);
|
||||
|
||||
//face m.2
|
||||
PMU->setPowerChannelVoltage(XPOWERS_DCDC3, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_DCDC3);
|
||||
|
||||
PMU->setPowerChannelVoltage(XPOWERS_DCDC4, XPOWERS_AXP2101_DCDC4_VOL2_MAX);
|
||||
PMU->enablePowerOutput(XPOWERS_DCDC4);
|
||||
|
||||
PMU->setPowerChannelVoltage(XPOWERS_DCDC5, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_DCDC5);
|
||||
|
||||
|
||||
//not use channel
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC2);
|
||||
// PMU->disablePowerOutput(XPOWERS_DCDC4);
|
||||
// PMU->disablePowerOutput(XPOWERS_DCDC5);
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO1);
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO2);
|
||||
PMU->disablePowerOutput(XPOWERS_VBACKUP);
|
||||
|
||||
#endif
|
||||
}
|
||||
|
||||
PMU->enableSystemVoltageMeasure();
|
||||
PMU->enableVbusVoltageMeasure();
|
||||
PMU->enableBattVoltageMeasure();
|
||||
PMU->disableTSPinMeasure();
|
||||
|
||||
Serial.printf("=========================================\n");
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC1)) {
|
||||
Serial.printf("DC1 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC1) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC1));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC2)) {
|
||||
Serial.printf("DC2 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC2));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC3)) {
|
||||
Serial.printf("DC3 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC3) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC3));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC4)) {
|
||||
Serial.printf("DC4 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC4) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC4));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC5)) {
|
||||
Serial.printf("DC5 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC5) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC5));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_LDO2)) {
|
||||
Serial.printf("LDO2 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_LDO2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_LDO2));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_LDO3)) {
|
||||
Serial.printf("LDO3 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_LDO3) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_LDO3));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO1)) {
|
||||
Serial.printf("ALDO1: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO1) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO1));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO2)) {
|
||||
Serial.printf("ALDO2: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO2));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO3)) {
|
||||
Serial.printf("ALDO3: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO3) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO3));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO4)) {
|
||||
Serial.printf("ALDO4: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO4) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO4));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_BLDO1)) {
|
||||
Serial.printf("BLDO1: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_BLDO1) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_BLDO1));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_BLDO2)) {
|
||||
Serial.printf("BLDO2: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_BLDO2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_BLDO2));
|
||||
}
|
||||
Serial.printf("=========================================\n");
|
||||
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
@ -0,0 +1,127 @@
|
|||
/**
|
||||
*
|
||||
* @license MIT License
|
||||
*
|
||||
* Copyright (c) 2022 lewis he
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
* @file QMC6310_GetPolarExample.ino
|
||||
* @author Lewis He (lewishe@outlook.com)
|
||||
* @date 2022-10-16
|
||||
*
|
||||
*/
|
||||
#include <Wire.h>
|
||||
#include <SPI.h>
|
||||
#include <Arduino.h>
|
||||
#include "SensorQMC6310.hpp"
|
||||
|
||||
#define I2C1_SDA 17
|
||||
#define I2C1_SCL 18
|
||||
|
||||
SensorQMC6310 qmc;
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(115200);
|
||||
while (!Serial);
|
||||
|
||||
#ifdef LILYGO_TBEAM_SUPREME_V3_0
|
||||
extern bool setupPower();
|
||||
setupPower();
|
||||
#endif
|
||||
|
||||
if (!qmc.begin(Wire, QMC6310_SLAVE_ADDRESS, I2C1_SDA, I2C1_SCL)) {
|
||||
Serial.println("Failed to find QMC6310 - check your wiring!");
|
||||
while (1) {
|
||||
delay(1000);
|
||||
}
|
||||
}
|
||||
|
||||
/* Get Magnetometer chip id*/
|
||||
Serial.print("Device ID:");
|
||||
Serial.println(qmc.getChipID(), HEX);
|
||||
|
||||
/* Config Magnetometer */
|
||||
qmc.configMagnetometer(
|
||||
/*
|
||||
* Run Mode
|
||||
* MODE_SUSPEND
|
||||
* MODE_NORMAL
|
||||
* MODE_SINGLE
|
||||
* MODE_CONTINUOUS
|
||||
* * */
|
||||
SensorQMC6310::MODE_NORMAL,
|
||||
/*
|
||||
* Full Range
|
||||
* RANGE_30G
|
||||
* RANGE_12G
|
||||
* RANGE_8G
|
||||
* RANGE_2G
|
||||
* * */
|
||||
SensorQMC6310::RANGE_8G,
|
||||
/*
|
||||
* Output data rate
|
||||
* DATARATE_10HZ
|
||||
* DATARATE_50HZ
|
||||
* DATARATE_100HZ
|
||||
* DATARATE_200HZ
|
||||
* * */
|
||||
SensorQMC6310::DATARATE_200HZ,
|
||||
/*
|
||||
* Over sample Ratio1
|
||||
* OSR_8
|
||||
* OSR_4
|
||||
* OSR_2
|
||||
* OSR_1
|
||||
* * * */
|
||||
SensorQMC6310::OSR_8,
|
||||
|
||||
/*
|
||||
* Down sample Ratio1
|
||||
* DSR_8
|
||||
* DSR_4
|
||||
* DSR_2
|
||||
* DSR_1
|
||||
* * */
|
||||
SensorQMC6310::DSR_1);
|
||||
|
||||
qmc.dumpCtrlRegister();
|
||||
|
||||
// Declination is the difference between magnetic-north and true-north ("heading") and depends on location
|
||||
qmc.setDeclination(-2.77); // Found with: https://www.magnetic-declination.com/CHINA/SHENZHEN/475119.html
|
||||
|
||||
Serial.println("Read data now...");
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
Polar data;
|
||||
// Wait for data ready
|
||||
if (qmc.readPolar(data)) {
|
||||
Serial.print(" polar:"); Serial.print(data.polar); Serial.print("°");
|
||||
Serial.print(" Gauss:"); Serial.print(data.Gauss);
|
||||
Serial.print(" uT:"); Serial.println(data.uT);
|
||||
}
|
||||
|
||||
delay(100);
|
||||
}
|
||||
|
||||
|
||||
|
||||
167
lib/SensorsLib/examples/QMC6310_GetPolarExample/power.cpp
Normal file
167
lib/SensorsLib/examples/QMC6310_GetPolarExample/power.cpp
Normal file
|
|
@ -0,0 +1,167 @@
|
|||
/**
|
||||
* @file power.cpp
|
||||
* @author Lewis He (lewishe@outlook.com)
|
||||
* @license MIT
|
||||
* @copyright Copyright (c) 2022
|
||||
* @date 2022-10-25
|
||||
*
|
||||
*/
|
||||
|
||||
|
||||
#ifdef LILYGO_TBEAM_SUPREME_V3_0
|
||||
#include <Wire.h>
|
||||
#include "XPowersAXP2101.tpp"
|
||||
#include "XPowersAXP192.tpp"
|
||||
|
||||
|
||||
|
||||
#define I2C_SDA 42
|
||||
#define I2C_SCL 41
|
||||
#define PMU_IRQ 40
|
||||
|
||||
XPowersLibInterface *PMU = NULL;
|
||||
|
||||
bool setupPower()
|
||||
{
|
||||
Serial.println("setupPower");
|
||||
|
||||
if (!PMU) {
|
||||
PMU = new XPowersAXP2101(Wire1, I2C_SDA, I2C_SCL);
|
||||
if (!PMU->init()) {
|
||||
Serial.println("Warning: Failed to find AXP2101 power management");
|
||||
delete PMU;
|
||||
PMU = NULL;
|
||||
} else {
|
||||
Serial.println("AXP2101 PMU init succeeded, using AXP2101 PMU");
|
||||
}
|
||||
}
|
||||
|
||||
if (!PMU) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (PMU->getChipModel() == XPOWERS_AXP2101) {
|
||||
|
||||
#if defined(LILYGO_TBEAM_V1_2)
|
||||
|
||||
PMU->setProtectedChannel(XPOWERS_DCDC1);
|
||||
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC2);
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC3);
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC4);
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC5);
|
||||
|
||||
// PMU->disablePowerOutput(XPOWERS_ALDO1);
|
||||
// PMU->disablePowerOutput(XPOWERS_ALDO2);
|
||||
// PMU->disablePowerOutput(XPOWERS_ALDO3);
|
||||
PMU->disablePowerOutput(XPOWERS_ALDO4);
|
||||
|
||||
PMU->disablePowerOutput(XPOWERS_BLDO1);
|
||||
PMU->disablePowerOutput(XPOWERS_BLDO2);
|
||||
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO1);
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO2);
|
||||
|
||||
PMU->enablePowerOutput(XPOWERS_VBACKUP);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO1);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO2);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO3);
|
||||
|
||||
PMU->setChargeTargetVoltage(XPOWERS_AXP2101_CHG_VOL_4V4);
|
||||
|
||||
#elif defined(LILYGO_TBEAM_SUPREME_V3_0)
|
||||
|
||||
//t-beam m.2 inface
|
||||
//gps
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO4, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO4);
|
||||
|
||||
// lora
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO3, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO3);
|
||||
|
||||
// Sensor
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO1, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO1);
|
||||
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO2, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO2);
|
||||
|
||||
//Sdcard
|
||||
PMU->setPowerChannelVoltage(XPOWERS_BLDO1, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_BLDO1);
|
||||
|
||||
//face m.2
|
||||
PMU->setPowerChannelVoltage(XPOWERS_DCDC3, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_DCDC3);
|
||||
|
||||
PMU->setPowerChannelVoltage(XPOWERS_DCDC4, XPOWERS_AXP2101_DCDC4_VOL2_MAX);
|
||||
PMU->enablePowerOutput(XPOWERS_DCDC4);
|
||||
|
||||
PMU->setPowerChannelVoltage(XPOWERS_DCDC5, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_DCDC5);
|
||||
|
||||
|
||||
//not use channel
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC2);
|
||||
// PMU->disablePowerOutput(XPOWERS_DCDC4);
|
||||
// PMU->disablePowerOutput(XPOWERS_DCDC5);
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO1);
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO2);
|
||||
PMU->disablePowerOutput(XPOWERS_VBACKUP);
|
||||
|
||||
#endif
|
||||
}
|
||||
|
||||
PMU->enableSystemVoltageMeasure();
|
||||
PMU->enableVbusVoltageMeasure();
|
||||
PMU->enableBattVoltageMeasure();
|
||||
PMU->disableTSPinMeasure();
|
||||
|
||||
Serial.printf("=========================================\n");
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC1)) {
|
||||
Serial.printf("DC1 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC1) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC1));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC2)) {
|
||||
Serial.printf("DC2 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC2));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC3)) {
|
||||
Serial.printf("DC3 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC3) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC3));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC4)) {
|
||||
Serial.printf("DC4 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC4) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC4));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC5)) {
|
||||
Serial.printf("DC5 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC5) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC5));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_LDO2)) {
|
||||
Serial.printf("LDO2 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_LDO2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_LDO2));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_LDO3)) {
|
||||
Serial.printf("LDO3 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_LDO3) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_LDO3));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO1)) {
|
||||
Serial.printf("ALDO1: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO1) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO1));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO2)) {
|
||||
Serial.printf("ALDO2: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO2));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO3)) {
|
||||
Serial.printf("ALDO3: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO3) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO3));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO4)) {
|
||||
Serial.printf("ALDO4: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO4) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO4));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_BLDO1)) {
|
||||
Serial.printf("BLDO1: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_BLDO1) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_BLDO1));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_BLDO2)) {
|
||||
Serial.printf("BLDO2: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_BLDO2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_BLDO2));
|
||||
}
|
||||
Serial.printf("=========================================\n");
|
||||
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
@ -0,0 +1,242 @@
|
|||
/**
|
||||
*
|
||||
* @license MIT License
|
||||
*
|
||||
* Copyright (c) 2022 lewis he
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
* @file QMI8658_BlockExample.ino
|
||||
* @author Lewis He (lewishe@outlook.com)
|
||||
* @date 2022-10-16
|
||||
*
|
||||
*/
|
||||
#include <Arduino.h>
|
||||
#include <Wire.h>
|
||||
#include <SPI.h>
|
||||
#include "SensorQMI8658.hpp"
|
||||
#include <MadgwickAHRS.h> //MadgwickAHRS from https://github.com/arduino-libraries/MadgwickAHRS
|
||||
#include "SH1106Wire.h" //Oled display from https://github.com/ThingPulse/esp8266-oled-ssd1306
|
||||
|
||||
// #define USE_WIRE
|
||||
|
||||
#define I2C1_SDA 17
|
||||
#define I2C1_SCL 18
|
||||
|
||||
SH1106Wire display(0x3c, I2C1_SDA, I2C1_SCL);
|
||||
SensorQMI8658 qmi;
|
||||
|
||||
IMUdata acc;
|
||||
IMUdata gyr;
|
||||
|
||||
Madgwick filter;
|
||||
unsigned long microsPerReading, microsPrevious;
|
||||
|
||||
float posX = 64;
|
||||
float posY = 32;
|
||||
float lastPosX = posX;
|
||||
float lastPosY = posY;
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(115200);
|
||||
while (!Serial);
|
||||
|
||||
#ifdef LILYGO_TBEAM_SUPREME_V3_0
|
||||
extern bool setupPower();
|
||||
setupPower();
|
||||
#endif
|
||||
|
||||
display.init();
|
||||
|
||||
|
||||
#ifdef USE_WIRE
|
||||
//Using WIRE !!
|
||||
if (!qmi.begin(Wire, QMI8658_L_SLAVE_ADDRESS, I2C1_SDA, I2C1_SCL)) {
|
||||
Serial.println("Failed to find QMI8658 - check your wiring!");
|
||||
while (1) {
|
||||
delay(1000);
|
||||
}
|
||||
}
|
||||
#else
|
||||
|
||||
#ifndef CONFIG_IDF_TARGET_ESP32
|
||||
//Use tbeams3 defalut spi pin
|
||||
#define SPI_MOSI (35)
|
||||
#define SPI_SCK (36)
|
||||
#define SPI_MISO (37)
|
||||
#define SPI_CS (47)
|
||||
#define IMU_CS (34)
|
||||
#define IMU_INT1 (33) //INTERRUPT PIN1 & PIN2 ,Use or logic to form a pin
|
||||
|
||||
SPI.begin(SPI_SCK, SPI_MISO, SPI_MOSI);
|
||||
pinMode(SPI_CS, OUTPUT); //sdcard pin set high
|
||||
digitalWrite(SPI_CS, HIGH);
|
||||
if (!qmi.begin(IMU_CS, SPI_MOSI, SPI_MISO, SPI_SCK)) {
|
||||
|
||||
#else
|
||||
//Use esp32dev module defalut spi pin
|
||||
#define IMU_CS (5)
|
||||
#define IMU_INT1 (15)
|
||||
#define IMU_INT2 (22)
|
||||
if (!qmi.begin(IMU_CS)) {
|
||||
#endif
|
||||
Serial.println("Failed to find QMI8658 - check your wiring!");
|
||||
while (1) {
|
||||
delay(1000);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
/* Get chip id*/
|
||||
Serial.print("Device ID:");
|
||||
Serial.println(qmi.getChipID(), HEX);
|
||||
|
||||
display.flipScreenVertically();
|
||||
|
||||
qmi.configAccelerometer(
|
||||
/*
|
||||
* ACC_RANGE_2G
|
||||
* ACC_RANGE_4G
|
||||
* ACC_RANGE_8G
|
||||
* ACC_RANGE_16G
|
||||
* */
|
||||
SensorQMI8658::ACC_RANGE_2G,
|
||||
/*
|
||||
* ACC_ODR_1000H
|
||||
* ACC_ODR_500Hz
|
||||
* ACC_ODR_250Hz
|
||||
* ACC_ODR_125Hz
|
||||
* ACC_ODR_62_5Hz
|
||||
* ACC_ODR_31_25Hz
|
||||
* ACC_ODR_LOWPOWER_128Hz
|
||||
* ACC_ODR_LOWPOWER_21Hz
|
||||
* ACC_ODR_LOWPOWER_11Hz
|
||||
* ACC_ODR_LOWPOWER_3H
|
||||
* */
|
||||
SensorQMI8658::ACC_ODR_1000Hz,
|
||||
/*
|
||||
* LPF_MODE_0 //2.66% of ODR
|
||||
* LPF_MODE_1 //3.63% of ODR
|
||||
* LPF_MODE_2 //5.39% of ODR
|
||||
* LPF_MODE_3 //13.37% of ODR
|
||||
* */
|
||||
SensorQMI8658::LPF_MODE_0,
|
||||
// selfTest enable
|
||||
true);
|
||||
|
||||
|
||||
qmi.configGyroscope(
|
||||
/*
|
||||
* GYR_RANGE_16DPS
|
||||
* GYR_RANGE_32DPS
|
||||
* GYR_RANGE_64DPS
|
||||
* GYR_RANGE_128DPS
|
||||
* GYR_RANGE_256DPS
|
||||
* GYR_RANGE_512DPS
|
||||
* GYR_RANGE_1024DPS
|
||||
* */
|
||||
SensorQMI8658::GYR_RANGE_256DPS,
|
||||
/*
|
||||
* GYR_ODR_7174_4Hz
|
||||
* GYR_ODR_3587_2Hz
|
||||
* GYR_ODR_1793_6Hz
|
||||
* GYR_ODR_896_8Hz
|
||||
* GYR_ODR_448_4Hz
|
||||
* GYR_ODR_224_2Hz
|
||||
* GYR_ODR_112_1Hz
|
||||
* GYR_ODR_56_05Hz
|
||||
* GYR_ODR_28_025H
|
||||
* */
|
||||
SensorQMI8658::GYR_ODR_896_8Hz,
|
||||
/*
|
||||
* LPF_MODE_0 //2.66% of ODR
|
||||
* LPF_MODE_1 //3.63% of ODR
|
||||
* LPF_MODE_2 //5.39% of ODR
|
||||
* LPF_MODE_3 //13.37% of ODR
|
||||
* */
|
||||
SensorQMI8658::LPF_MODE_3,
|
||||
// selfTest enable
|
||||
true);
|
||||
|
||||
|
||||
// In 6DOF mode (accelerometer and gyroscope are both enabled),
|
||||
// the output data rate is derived from the nature frequency of gyroscope
|
||||
qmi.enableGyroscope();
|
||||
qmi.enableAccelerometer();
|
||||
|
||||
// Print register configuration information
|
||||
qmi.dumpCtrlRegister();
|
||||
|
||||
// start filter
|
||||
filter.begin(25);
|
||||
|
||||
// initialize variables to pace updates to correct rate
|
||||
microsPerReading = 1000000 / 25;
|
||||
microsPrevious = micros();
|
||||
|
||||
Serial.println("Read data now...");
|
||||
}
|
||||
|
||||
const uint8_t rectWidth = 10;
|
||||
|
||||
void loop()
|
||||
{
|
||||
float roll, pitch, heading;
|
||||
|
||||
// check if it's time to read data and update the filter
|
||||
if (micros() - microsPrevious >= microsPerReading) {
|
||||
|
||||
// read raw data from IMU
|
||||
if (qmi.getDataReady()) {
|
||||
|
||||
qmi.getAccelerometer(acc.x, acc.y, acc.z);
|
||||
qmi.getGyroscope(gyr.x, gyr.y, gyr.z);
|
||||
|
||||
// update the filter, which computes orientation
|
||||
filter.updateIMU(gyr.x, gyr.y, gyr.z, acc.x, acc.y, acc.z);
|
||||
|
||||
// print the heading, pitch and roll
|
||||
roll = filter.getRoll();
|
||||
pitch = filter.getPitch();
|
||||
heading = filter.getYaw();
|
||||
|
||||
posX -= roll * 2;
|
||||
posY += pitch;
|
||||
|
||||
Serial.printf("x:%.2f y:%.2f \n", posX, posY);
|
||||
posX = constrain(posX, 0, display.width() - rectWidth);
|
||||
posY = constrain(posY, 0, display.height() - rectWidth);
|
||||
|
||||
display.setColor(BLACK);
|
||||
display.fillRect(lastPosX, lastPosY, 10, 10);
|
||||
display.setColor(WHITE);
|
||||
display.fillRect(posX, posY, 10, 10);
|
||||
display.display();
|
||||
|
||||
lastPosX = posX;
|
||||
lastPosY = posY;
|
||||
}
|
||||
// increment previous time, so we keep proper pace
|
||||
microsPrevious = microsPrevious + microsPerReading;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
167
lib/SensorsLib/examples/QMI8658_BlockExample/power.cpp
Normal file
167
lib/SensorsLib/examples/QMI8658_BlockExample/power.cpp
Normal file
|
|
@ -0,0 +1,167 @@
|
|||
/**
|
||||
* @file power.cpp
|
||||
* @author Lewis He (lewishe@outlook.com)
|
||||
* @license MIT
|
||||
* @copyright Copyright (c) 2022
|
||||
* @date 2022-10-25
|
||||
*
|
||||
*/
|
||||
|
||||
|
||||
#ifdef LILYGO_TBEAM_SUPREME_V3_0
|
||||
#include <Wire.h>
|
||||
#include "XPowersAXP2101.tpp"
|
||||
#include "XPowersAXP192.tpp"
|
||||
|
||||
|
||||
|
||||
#define I2C_SDA 42
|
||||
#define I2C_SCL 41
|
||||
#define PMU_IRQ 40
|
||||
|
||||
XPowersLibInterface *PMU = NULL;
|
||||
|
||||
bool setupPower()
|
||||
{
|
||||
Serial.println("setupPower");
|
||||
|
||||
if (!PMU) {
|
||||
PMU = new XPowersAXP2101(Wire1, I2C_SDA, I2C_SCL);
|
||||
if (!PMU->init()) {
|
||||
Serial.println("Warning: Failed to find AXP2101 power management");
|
||||
delete PMU;
|
||||
PMU = NULL;
|
||||
} else {
|
||||
Serial.println("AXP2101 PMU init succeeded, using AXP2101 PMU");
|
||||
}
|
||||
}
|
||||
|
||||
if (!PMU) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (PMU->getChipModel() == XPOWERS_AXP2101) {
|
||||
|
||||
#if defined(LILYGO_TBEAM_V1_2)
|
||||
|
||||
PMU->setProtectedChannel(XPOWERS_DCDC1);
|
||||
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC2);
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC3);
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC4);
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC5);
|
||||
|
||||
// PMU->disablePowerOutput(XPOWERS_ALDO1);
|
||||
// PMU->disablePowerOutput(XPOWERS_ALDO2);
|
||||
// PMU->disablePowerOutput(XPOWERS_ALDO3);
|
||||
PMU->disablePowerOutput(XPOWERS_ALDO4);
|
||||
|
||||
PMU->disablePowerOutput(XPOWERS_BLDO1);
|
||||
PMU->disablePowerOutput(XPOWERS_BLDO2);
|
||||
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO1);
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO2);
|
||||
|
||||
PMU->enablePowerOutput(XPOWERS_VBACKUP);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO1);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO2);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO3);
|
||||
|
||||
PMU->setChargeTargetVoltage(XPOWERS_AXP2101_CHG_VOL_4V4);
|
||||
|
||||
#elif defined(LILYGO_TBEAM_SUPREME_V3_0)
|
||||
|
||||
//t-beam m.2 inface
|
||||
//gps
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO4, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO4);
|
||||
|
||||
// lora
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO3, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO3);
|
||||
|
||||
// Sensor
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO1, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO1);
|
||||
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO2, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO2);
|
||||
|
||||
//Sdcard
|
||||
PMU->setPowerChannelVoltage(XPOWERS_BLDO1, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_BLDO1);
|
||||
|
||||
//face m.2
|
||||
PMU->setPowerChannelVoltage(XPOWERS_DCDC3, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_DCDC3);
|
||||
|
||||
PMU->setPowerChannelVoltage(XPOWERS_DCDC4, XPOWERS_AXP2101_DCDC4_VOL2_MAX);
|
||||
PMU->enablePowerOutput(XPOWERS_DCDC4);
|
||||
|
||||
PMU->setPowerChannelVoltage(XPOWERS_DCDC5, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_DCDC5);
|
||||
|
||||
|
||||
//not use channel
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC2);
|
||||
// PMU->disablePowerOutput(XPOWERS_DCDC4);
|
||||
// PMU->disablePowerOutput(XPOWERS_DCDC5);
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO1);
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO2);
|
||||
PMU->disablePowerOutput(XPOWERS_VBACKUP);
|
||||
|
||||
#endif
|
||||
}
|
||||
|
||||
PMU->enableSystemVoltageMeasure();
|
||||
PMU->enableVbusVoltageMeasure();
|
||||
PMU->enableBattVoltageMeasure();
|
||||
PMU->disableTSPinMeasure();
|
||||
|
||||
Serial.printf("=========================================\n");
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC1)) {
|
||||
Serial.printf("DC1 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC1) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC1));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC2)) {
|
||||
Serial.printf("DC2 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC2));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC3)) {
|
||||
Serial.printf("DC3 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC3) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC3));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC4)) {
|
||||
Serial.printf("DC4 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC4) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC4));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC5)) {
|
||||
Serial.printf("DC5 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC5) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC5));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_LDO2)) {
|
||||
Serial.printf("LDO2 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_LDO2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_LDO2));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_LDO3)) {
|
||||
Serial.printf("LDO3 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_LDO3) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_LDO3));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO1)) {
|
||||
Serial.printf("ALDO1: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO1) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO1));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO2)) {
|
||||
Serial.printf("ALDO2: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO2));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO3)) {
|
||||
Serial.printf("ALDO3: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO3) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO3));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO4)) {
|
||||
Serial.printf("ALDO4: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO4) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO4));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_BLDO1)) {
|
||||
Serial.printf("BLDO1: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_BLDO1) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_BLDO1));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_BLDO2)) {
|
||||
Serial.printf("BLDO2: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_BLDO2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_BLDO2));
|
||||
}
|
||||
Serial.printf("=========================================\n");
|
||||
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
@ -0,0 +1,188 @@
|
|||
/**
|
||||
*
|
||||
* @license MIT License
|
||||
*
|
||||
* Copyright (c) 2022 lewis he
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
* @file QMI8658_GetDataExample.ino
|
||||
* @author Lewis He (lewishe@outlook.com)
|
||||
* @date 2022-10-16
|
||||
*
|
||||
*/
|
||||
#include <Arduino.h>
|
||||
#include <Wire.h>
|
||||
#include <SPI.h>
|
||||
#include "SensorQMI8658.hpp"
|
||||
|
||||
#define USE_WIRE
|
||||
|
||||
#define I2C1_SDA 17
|
||||
#define I2C1_SCL 18
|
||||
|
||||
#define IMU_CS 5
|
||||
|
||||
SensorQMI8658 qmi;
|
||||
|
||||
IMUdata acc;
|
||||
IMUdata gyr;
|
||||
|
||||
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(115200);
|
||||
while (!Serial);
|
||||
|
||||
#ifdef LILYGO_TBEAM_SUPREME_V3_0
|
||||
extern bool setupPower();
|
||||
setupPower();
|
||||
#endif
|
||||
|
||||
#ifdef USE_WIRE
|
||||
//Using WIRE !!
|
||||
if (!qmi.begin(Wire, QMI8658_L_SLAVE_ADDRESS, I2C1_SDA, I2C1_SCL)) {
|
||||
Serial.println("Failed to find QMI8658 - check your wiring!");
|
||||
while (1) {
|
||||
delay(1000);
|
||||
}
|
||||
}
|
||||
#else
|
||||
if (!qmi.begin(IMU_CS)) {
|
||||
Serial.println("Failed to find QMI8658 - check your wiring!");
|
||||
while (1) {
|
||||
delay(1000);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
/* Get chip id*/
|
||||
Serial.print("Device ID:");
|
||||
Serial.println(qmi.getChipID(), HEX);
|
||||
|
||||
qmi.configAccelerometer(
|
||||
/*
|
||||
* ACC_RANGE_2G
|
||||
* ACC_RANGE_4G
|
||||
* ACC_RANGE_8G
|
||||
* ACC_RANGE_16G
|
||||
* */
|
||||
SensorQMI8658::ACC_RANGE_4G,
|
||||
/*
|
||||
* ACC_ODR_1000H
|
||||
* ACC_ODR_500Hz
|
||||
* ACC_ODR_250Hz
|
||||
* ACC_ODR_125Hz
|
||||
* ACC_ODR_62_5Hz
|
||||
* ACC_ODR_31_25Hz
|
||||
* ACC_ODR_LOWPOWER_128Hz
|
||||
* ACC_ODR_LOWPOWER_21Hz
|
||||
* ACC_ODR_LOWPOWER_11Hz
|
||||
* ACC_ODR_LOWPOWER_3H
|
||||
* */
|
||||
SensorQMI8658::ACC_ODR_1000Hz,
|
||||
/*
|
||||
* LPF_MODE_0 //2.66% of ODR
|
||||
* LPF_MODE_1 //3.63% of ODR
|
||||
* LPF_MODE_2 //5.39% of ODR
|
||||
* LPF_MODE_3 //13.37% of ODR
|
||||
* */
|
||||
SensorQMI8658::LPF_MODE_0,
|
||||
// selfTest enable
|
||||
true);
|
||||
|
||||
|
||||
qmi.configGyroscope(
|
||||
/*
|
||||
* GYR_RANGE_16DPS
|
||||
* GYR_RANGE_32DPS
|
||||
* GYR_RANGE_64DPS
|
||||
* GYR_RANGE_128DPS
|
||||
* GYR_RANGE_256DPS
|
||||
* GYR_RANGE_512DPS
|
||||
* GYR_RANGE_1024DPS
|
||||
* */
|
||||
SensorQMI8658::GYR_RANGE_64DPS,
|
||||
/*
|
||||
* GYR_ODR_7174_4Hz
|
||||
* GYR_ODR_3587_2Hz
|
||||
* GYR_ODR_1793_6Hz
|
||||
* GYR_ODR_896_8Hz
|
||||
* GYR_ODR_448_4Hz
|
||||
* GYR_ODR_224_2Hz
|
||||
* GYR_ODR_112_1Hz
|
||||
* GYR_ODR_56_05Hz
|
||||
* GYR_ODR_28_025H
|
||||
* */
|
||||
SensorQMI8658::GYR_ODR_896_8Hz,
|
||||
/*
|
||||
* LPF_MODE_0 //2.66% of ODR
|
||||
* LPF_MODE_1 //3.63% of ODR
|
||||
* LPF_MODE_2 //5.39% of ODR
|
||||
* LPF_MODE_3 //13.37% of ODR
|
||||
* */
|
||||
SensorQMI8658::LPF_MODE_3,
|
||||
// selfTest enable
|
||||
true);
|
||||
|
||||
|
||||
// In 6DOF mode (accelerometer and gyroscope are both enabled),
|
||||
// the output data rate is derived from the nature frequency of gyroscope
|
||||
qmi.enableGyroscope();
|
||||
qmi.enableAccelerometer();
|
||||
|
||||
// Print register configuration information
|
||||
qmi.dumpCtrlRegister();
|
||||
|
||||
Serial.println("Read data now...");
|
||||
}
|
||||
|
||||
|
||||
void loop()
|
||||
{
|
||||
|
||||
if (qmi.getDataReady()) {
|
||||
|
||||
if (qmi.getAccelerometer(acc.x, acc.y, acc.z)) {
|
||||
Serial.print("{ACCEL: ");
|
||||
Serial.print(acc.x);
|
||||
Serial.print(",");
|
||||
Serial.print(acc.y);
|
||||
Serial.print(",");
|
||||
Serial.print(acc.z);
|
||||
Serial.println("}");
|
||||
}
|
||||
|
||||
if (qmi.getGyroscope(gyr.x, gyr.y, gyr.z)) {
|
||||
Serial.print("{GYRO: ");
|
||||
Serial.print(gyr.x);
|
||||
Serial.print(",");
|
||||
Serial.print(gyr.y );
|
||||
Serial.print(",");
|
||||
Serial.print(gyr.z);
|
||||
Serial.println("}");
|
||||
}
|
||||
Serial.printf("\t\t\t\t > %lu %.2f *C\n", qmi.getTimestamp(), qmi.getTemperature_C());
|
||||
}
|
||||
delay(100);
|
||||
}
|
||||
|
||||
|
||||
|
||||
167
lib/SensorsLib/examples/QMI8658_GetDataExample/power.cpp
Normal file
167
lib/SensorsLib/examples/QMI8658_GetDataExample/power.cpp
Normal file
|
|
@ -0,0 +1,167 @@
|
|||
/**
|
||||
* @file power.cpp
|
||||
* @author Lewis He (lewishe@outlook.com)
|
||||
* @license MIT
|
||||
* @copyright Copyright (c) 2022
|
||||
* @date 2022-10-25
|
||||
*
|
||||
*/
|
||||
|
||||
|
||||
#ifdef LILYGO_TBEAM_SUPREME_V3_0
|
||||
#include <Wire.h>
|
||||
#include "XPowersAXP2101.tpp"
|
||||
#include "XPowersAXP192.tpp"
|
||||
|
||||
|
||||
|
||||
#define I2C_SDA 42
|
||||
#define I2C_SCL 41
|
||||
#define PMU_IRQ 40
|
||||
|
||||
XPowersLibInterface *PMU = NULL;
|
||||
|
||||
bool setupPower()
|
||||
{
|
||||
Serial.println("setupPower");
|
||||
|
||||
if (!PMU) {
|
||||
PMU = new XPowersAXP2101(Wire1, I2C_SDA, I2C_SCL);
|
||||
if (!PMU->init()) {
|
||||
Serial.println("Warning: Failed to find AXP2101 power management");
|
||||
delete PMU;
|
||||
PMU = NULL;
|
||||
} else {
|
||||
Serial.println("AXP2101 PMU init succeeded, using AXP2101 PMU");
|
||||
}
|
||||
}
|
||||
|
||||
if (!PMU) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (PMU->getChipModel() == XPOWERS_AXP2101) {
|
||||
|
||||
#if defined(LILYGO_TBEAM_V1_2)
|
||||
|
||||
PMU->setProtectedChannel(XPOWERS_DCDC1);
|
||||
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC2);
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC3);
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC4);
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC5);
|
||||
|
||||
// PMU->disablePowerOutput(XPOWERS_ALDO1);
|
||||
// PMU->disablePowerOutput(XPOWERS_ALDO2);
|
||||
// PMU->disablePowerOutput(XPOWERS_ALDO3);
|
||||
PMU->disablePowerOutput(XPOWERS_ALDO4);
|
||||
|
||||
PMU->disablePowerOutput(XPOWERS_BLDO1);
|
||||
PMU->disablePowerOutput(XPOWERS_BLDO2);
|
||||
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO1);
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO2);
|
||||
|
||||
PMU->enablePowerOutput(XPOWERS_VBACKUP);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO1);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO2);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO3);
|
||||
|
||||
PMU->setChargeTargetVoltage(XPOWERS_AXP2101_CHG_VOL_4V4);
|
||||
|
||||
#elif defined(LILYGO_TBEAM_SUPREME_V3_0)
|
||||
|
||||
//t-beam m.2 inface
|
||||
//gps
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO4, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO4);
|
||||
|
||||
// lora
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO3, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO3);
|
||||
|
||||
// Sensor
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO1, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO1);
|
||||
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO2, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO2);
|
||||
|
||||
//Sdcard
|
||||
PMU->setPowerChannelVoltage(XPOWERS_BLDO1, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_BLDO1);
|
||||
|
||||
//face m.2
|
||||
PMU->setPowerChannelVoltage(XPOWERS_DCDC3, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_DCDC3);
|
||||
|
||||
PMU->setPowerChannelVoltage(XPOWERS_DCDC4, XPOWERS_AXP2101_DCDC4_VOL2_MAX);
|
||||
PMU->enablePowerOutput(XPOWERS_DCDC4);
|
||||
|
||||
PMU->setPowerChannelVoltage(XPOWERS_DCDC5, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_DCDC5);
|
||||
|
||||
|
||||
//not use channel
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC2);
|
||||
// PMU->disablePowerOutput(XPOWERS_DCDC4);
|
||||
// PMU->disablePowerOutput(XPOWERS_DCDC5);
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO1);
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO2);
|
||||
PMU->disablePowerOutput(XPOWERS_VBACKUP);
|
||||
|
||||
#endif
|
||||
}
|
||||
|
||||
PMU->enableSystemVoltageMeasure();
|
||||
PMU->enableVbusVoltageMeasure();
|
||||
PMU->enableBattVoltageMeasure();
|
||||
PMU->disableTSPinMeasure();
|
||||
|
||||
Serial.printf("=========================================\n");
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC1)) {
|
||||
Serial.printf("DC1 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC1) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC1));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC2)) {
|
||||
Serial.printf("DC2 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC2));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC3)) {
|
||||
Serial.printf("DC3 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC3) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC3));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC4)) {
|
||||
Serial.printf("DC4 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC4) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC4));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC5)) {
|
||||
Serial.printf("DC5 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC5) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC5));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_LDO2)) {
|
||||
Serial.printf("LDO2 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_LDO2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_LDO2));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_LDO3)) {
|
||||
Serial.printf("LDO3 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_LDO3) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_LDO3));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO1)) {
|
||||
Serial.printf("ALDO1: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO1) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO1));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO2)) {
|
||||
Serial.printf("ALDO2: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO2));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO3)) {
|
||||
Serial.printf("ALDO3: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO3) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO3));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO4)) {
|
||||
Serial.printf("ALDO4: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO4) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO4));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_BLDO1)) {
|
||||
Serial.printf("BLDO1: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_BLDO1) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_BLDO1));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_BLDO2)) {
|
||||
Serial.printf("BLDO2: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_BLDO2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_BLDO2));
|
||||
}
|
||||
Serial.printf("=========================================\n");
|
||||
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
@ -0,0 +1,252 @@
|
|||
/**
|
||||
*
|
||||
* @license MIT License
|
||||
*
|
||||
* Copyright (c) 2022 lewis he
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
* @file QMI8658_InterruptBlockExample.ino
|
||||
* @author Lewis He (lewishe@outlook.com)
|
||||
* @date 2022-10-16
|
||||
*
|
||||
*/
|
||||
#include <Arduino.h>
|
||||
#include <Wire.h>
|
||||
#include <SPI.h>
|
||||
#include "SensorQMI8658.hpp"
|
||||
#include <MadgwickAHRS.h> //MadgwickAHRS from https://github.com/arduino-libraries/MadgwickAHRS
|
||||
#include "SH1106Wire.h" //Oled display from https://github.com/ThingPulse/esp8266-oled-ssd1306
|
||||
|
||||
// #define USE_WIRE
|
||||
|
||||
#define I2C1_SDA 17
|
||||
#define I2C1_SCL 18
|
||||
|
||||
|
||||
SH1106Wire display(0x3c, I2C1_SDA, I2C1_SCL);
|
||||
SensorQMI8658 qmi;
|
||||
|
||||
IMUdata acc;
|
||||
IMUdata gyr;
|
||||
|
||||
Madgwick filter;
|
||||
unsigned long microsPerReading, microsPrevious;
|
||||
|
||||
float posX = 64;
|
||||
float posY = 32;
|
||||
float lastPosX = posX;
|
||||
float lastPosY = posY;
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(115200);
|
||||
while (!Serial);
|
||||
|
||||
#ifdef LILYGO_TBEAM_SUPREME_V3_0
|
||||
extern bool setupPower();
|
||||
setupPower();
|
||||
#endif
|
||||
|
||||
display.init();
|
||||
display.flipScreenVertically();
|
||||
|
||||
#ifdef USE_WIRE
|
||||
//Using WIRE !!
|
||||
if (!qmi.begin(Wire, QMI8658_L_SLAVE_ADDRESS, I2C1_SDA, I2C1_SCL)) {
|
||||
Serial.println("Failed to find QMI8658 - check your wiring!");
|
||||
while (1) {
|
||||
delay(1000);
|
||||
}
|
||||
}
|
||||
#else
|
||||
|
||||
#ifndef CONFIG_IDF_TARGET_ESP32
|
||||
//Use tbeams3 defalut spi pin
|
||||
#define SPI_MOSI (35)
|
||||
#define SPI_SCK (36)
|
||||
#define SPI_MISO (37)
|
||||
#define SPI_CS (47)
|
||||
#define IMU_CS (34)
|
||||
#define IMU_INT1 (33) //INTERRUPT PIN1 & PIN2 ,Use or logic to form a pin
|
||||
|
||||
SPI.begin(SPI_SCK, SPI_MISO, SPI_MOSI);
|
||||
pinMode(SPI_CS, OUTPUT); //sdcard pin set high
|
||||
digitalWrite(SPI_CS, HIGH);
|
||||
if (!qmi.begin(IMU_CS, SPI_MOSI, SPI_MISO, SPI_SCK)) {
|
||||
|
||||
#else
|
||||
//Use esp32dev module defalut spi pin
|
||||
#define IMU_CS (5)
|
||||
#define IMU_INT1 (15)
|
||||
#define IMU_INT2 (22)
|
||||
if (!qmi.begin(IMU_CS)) {
|
||||
#endif
|
||||
Serial.println("Failed to find QMI8658 - check your wiring!");
|
||||
while (1) {
|
||||
delay(1000);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
/* Get chip id*/
|
||||
Serial.print("Device ID:");
|
||||
Serial.println(qmi.getChipID(), HEX);
|
||||
|
||||
|
||||
qmi.configAccelerometer(
|
||||
/*
|
||||
* ACC_RANGE_2G
|
||||
* ACC_RANGE_4G
|
||||
* ACC_RANGE_8G
|
||||
* ACC_RANGE_16G
|
||||
* */
|
||||
SensorQMI8658::ACC_RANGE_2G,
|
||||
/*
|
||||
* ACC_ODR_1000H
|
||||
* ACC_ODR_500Hz
|
||||
* ACC_ODR_250Hz
|
||||
* ACC_ODR_125Hz
|
||||
* ACC_ODR_62_5Hz
|
||||
* ACC_ODR_31_25Hz
|
||||
* ACC_ODR_LOWPOWER_128Hz
|
||||
* ACC_ODR_LOWPOWER_21Hz
|
||||
* ACC_ODR_LOWPOWER_11Hz
|
||||
* ACC_ODR_LOWPOWER_3H
|
||||
* */
|
||||
SensorQMI8658::ACC_ODR_1000Hz,
|
||||
/*
|
||||
* LPF_MODE_0 //2.66% of ODR
|
||||
* LPF_MODE_1 //3.63% of ODR
|
||||
* LPF_MODE_2 //5.39% of ODR
|
||||
* LPF_MODE_3 //13.37% of ODR
|
||||
* */
|
||||
SensorQMI8658::LPF_MODE_0,
|
||||
// selfTest enable
|
||||
true);
|
||||
|
||||
|
||||
qmi.configGyroscope(
|
||||
/*
|
||||
* GYR_RANGE_16DPS
|
||||
* GYR_RANGE_32DPS
|
||||
* GYR_RANGE_64DPS
|
||||
* GYR_RANGE_128DPS
|
||||
* GYR_RANGE_256DPS
|
||||
* GYR_RANGE_512DPS
|
||||
* GYR_RANGE_1024DPS
|
||||
* */
|
||||
SensorQMI8658::GYR_RANGE_256DPS,
|
||||
/*
|
||||
* GYR_ODR_7174_4Hz
|
||||
* GYR_ODR_3587_2Hz
|
||||
* GYR_ODR_1793_6Hz
|
||||
* GYR_ODR_896_8Hz
|
||||
* GYR_ODR_448_4Hz
|
||||
* GYR_ODR_224_2Hz
|
||||
* GYR_ODR_112_1Hz
|
||||
* GYR_ODR_56_05Hz
|
||||
* GYR_ODR_28_025H
|
||||
* */
|
||||
SensorQMI8658::GYR_ODR_896_8Hz,
|
||||
/*
|
||||
* LPF_MODE_0 //2.66% of ODR
|
||||
* LPF_MODE_1 //3.63% of ODR
|
||||
* LPF_MODE_2 //5.39% of ODR
|
||||
* LPF_MODE_3 //13.37% of ODR
|
||||
* */
|
||||
SensorQMI8658::LPF_MODE_3,
|
||||
// selfTest enable
|
||||
true);
|
||||
|
||||
|
||||
// In 6DOF mode (accelerometer and gyroscope are both enabled),
|
||||
// the output data rate is derived from the nature frequency of gyroscope
|
||||
qmi.enableGyroscope();
|
||||
qmi.enableAccelerometer();
|
||||
|
||||
pinMode(IMU_INT1, INPUT);
|
||||
#ifdef IMU_INT2
|
||||
pinMode(IMU_INT2, INPUT);
|
||||
#endif
|
||||
|
||||
// qmi.enableINT(SensorQMI8658::IntPin1); //no use
|
||||
// Enable data ready to interrupt pin2
|
||||
qmi.enableINT(SensorQMI8658::IntPin2);
|
||||
qmi.enableDataReadyINT();
|
||||
|
||||
// Print register configuration information
|
||||
qmi.dumpCtrlRegister();
|
||||
|
||||
// start filter
|
||||
filter.begin(25);
|
||||
|
||||
// initialize variables to pace updates to correct rate
|
||||
microsPerReading = 1000000 / 25;
|
||||
microsPrevious = micros();
|
||||
|
||||
Serial.println("Read data now...");
|
||||
}
|
||||
|
||||
const uint8_t rectWidth = 10;
|
||||
|
||||
void loop()
|
||||
{
|
||||
float roll, pitch, heading;
|
||||
|
||||
// check if it's time to read data and update the filter
|
||||
if (micros() - microsPrevious >= microsPerReading) {
|
||||
|
||||
// read raw data from IMU
|
||||
if (digitalRead(IMU_INT1) == HIGH) {
|
||||
|
||||
qmi.getAccelerometer(acc.x, acc.y, acc.z);
|
||||
qmi.getGyroscope(gyr.x, gyr.y, gyr.z);
|
||||
|
||||
// update the filter, which computes orientation
|
||||
filter.updateIMU(gyr.x, gyr.y, gyr.z, acc.x, acc.y, acc.z);
|
||||
|
||||
// print the heading, pitch and roll
|
||||
roll = filter.getRoll();
|
||||
pitch = filter.getPitch();
|
||||
heading = filter.getYaw();
|
||||
|
||||
posX -= roll * 2;
|
||||
posY += pitch;
|
||||
|
||||
Serial.printf("x:%.2f y:%.2f \n", posX, posY);
|
||||
posX = constrain(posX, 0, display.width() - rectWidth);
|
||||
posY = constrain(posY, 0, display.height() - rectWidth);
|
||||
|
||||
display.setColor(BLACK);
|
||||
display.fillRect(lastPosX, lastPosY, 10, 10);
|
||||
display.setColor(WHITE);
|
||||
display.fillRect(posX, posY, 10, 10);
|
||||
display.display();
|
||||
|
||||
lastPosX = posX;
|
||||
lastPosY = posY;
|
||||
}
|
||||
// increment previous time, so we keep proper pace
|
||||
microsPrevious = microsPrevious + microsPerReading;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
167
lib/SensorsLib/examples/QMI8658_InterruptBlockExample/power.cpp
Normal file
167
lib/SensorsLib/examples/QMI8658_InterruptBlockExample/power.cpp
Normal file
|
|
@ -0,0 +1,167 @@
|
|||
/**
|
||||
* @file power.cpp
|
||||
* @author Lewis He (lewishe@outlook.com)
|
||||
* @license MIT
|
||||
* @copyright Copyright (c) 2022
|
||||
* @date 2022-10-25
|
||||
*
|
||||
*/
|
||||
|
||||
|
||||
#ifdef LILYGO_TBEAM_SUPREME_V3_0
|
||||
#include <Wire.h>
|
||||
#include "XPowersAXP2101.tpp"
|
||||
#include "XPowersAXP192.tpp"
|
||||
|
||||
|
||||
|
||||
#define I2C_SDA 42
|
||||
#define I2C_SCL 41
|
||||
#define PMU_IRQ 40
|
||||
|
||||
XPowersLibInterface *PMU = NULL;
|
||||
|
||||
bool setupPower()
|
||||
{
|
||||
Serial.println("setupPower");
|
||||
|
||||
if (!PMU) {
|
||||
PMU = new XPowersAXP2101(Wire1, I2C_SDA, I2C_SCL);
|
||||
if (!PMU->init()) {
|
||||
Serial.println("Warning: Failed to find AXP2101 power management");
|
||||
delete PMU;
|
||||
PMU = NULL;
|
||||
} else {
|
||||
Serial.println("AXP2101 PMU init succeeded, using AXP2101 PMU");
|
||||
}
|
||||
}
|
||||
|
||||
if (!PMU) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (PMU->getChipModel() == XPOWERS_AXP2101) {
|
||||
|
||||
#if defined(LILYGO_TBEAM_V1_2)
|
||||
|
||||
PMU->setProtectedChannel(XPOWERS_DCDC1);
|
||||
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC2);
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC3);
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC4);
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC5);
|
||||
|
||||
// PMU->disablePowerOutput(XPOWERS_ALDO1);
|
||||
// PMU->disablePowerOutput(XPOWERS_ALDO2);
|
||||
// PMU->disablePowerOutput(XPOWERS_ALDO3);
|
||||
PMU->disablePowerOutput(XPOWERS_ALDO4);
|
||||
|
||||
PMU->disablePowerOutput(XPOWERS_BLDO1);
|
||||
PMU->disablePowerOutput(XPOWERS_BLDO2);
|
||||
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO1);
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO2);
|
||||
|
||||
PMU->enablePowerOutput(XPOWERS_VBACKUP);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO1);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO2);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO3);
|
||||
|
||||
PMU->setChargeTargetVoltage(XPOWERS_AXP2101_CHG_VOL_4V4);
|
||||
|
||||
#elif defined(LILYGO_TBEAM_SUPREME_V3_0)
|
||||
|
||||
//t-beam m.2 inface
|
||||
//gps
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO4, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO4);
|
||||
|
||||
// lora
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO3, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO3);
|
||||
|
||||
// Sensor
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO1, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO1);
|
||||
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO2, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO2);
|
||||
|
||||
//Sdcard
|
||||
PMU->setPowerChannelVoltage(XPOWERS_BLDO1, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_BLDO1);
|
||||
|
||||
//face m.2
|
||||
PMU->setPowerChannelVoltage(XPOWERS_DCDC3, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_DCDC3);
|
||||
|
||||
PMU->setPowerChannelVoltage(XPOWERS_DCDC4, XPOWERS_AXP2101_DCDC4_VOL2_MAX);
|
||||
PMU->enablePowerOutput(XPOWERS_DCDC4);
|
||||
|
||||
PMU->setPowerChannelVoltage(XPOWERS_DCDC5, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_DCDC5);
|
||||
|
||||
|
||||
//not use channel
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC2);
|
||||
// PMU->disablePowerOutput(XPOWERS_DCDC4);
|
||||
// PMU->disablePowerOutput(XPOWERS_DCDC5);
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO1);
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO2);
|
||||
PMU->disablePowerOutput(XPOWERS_VBACKUP);
|
||||
|
||||
#endif
|
||||
}
|
||||
|
||||
PMU->enableSystemVoltageMeasure();
|
||||
PMU->enableVbusVoltageMeasure();
|
||||
PMU->enableBattVoltageMeasure();
|
||||
PMU->disableTSPinMeasure();
|
||||
|
||||
Serial.printf("=========================================\n");
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC1)) {
|
||||
Serial.printf("DC1 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC1) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC1));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC2)) {
|
||||
Serial.printf("DC2 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC2));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC3)) {
|
||||
Serial.printf("DC3 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC3) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC3));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC4)) {
|
||||
Serial.printf("DC4 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC4) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC4));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC5)) {
|
||||
Serial.printf("DC5 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC5) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC5));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_LDO2)) {
|
||||
Serial.printf("LDO2 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_LDO2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_LDO2));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_LDO3)) {
|
||||
Serial.printf("LDO3 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_LDO3) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_LDO3));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO1)) {
|
||||
Serial.printf("ALDO1: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO1) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO1));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO2)) {
|
||||
Serial.printf("ALDO2: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO2));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO3)) {
|
||||
Serial.printf("ALDO3: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO3) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO3));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO4)) {
|
||||
Serial.printf("ALDO4: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO4) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO4));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_BLDO1)) {
|
||||
Serial.printf("BLDO1: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_BLDO1) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_BLDO1));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_BLDO2)) {
|
||||
Serial.printf("BLDO2: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_BLDO2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_BLDO2));
|
||||
}
|
||||
Serial.printf("=========================================\n");
|
||||
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
@ -0,0 +1,241 @@
|
|||
/**
|
||||
*
|
||||
* @license MIT License
|
||||
*
|
||||
* Copyright (c) 2022 lewis he
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
* @file QMI8658_InterruptExample.ino
|
||||
* @author Lewis He (lewishe@outlook.com)
|
||||
* @date 2022-11-03
|
||||
*
|
||||
*/
|
||||
#include <Arduino.h>
|
||||
#include <Wire.h>
|
||||
#include <SPI.h>
|
||||
#include "SensorQMI8658.hpp"
|
||||
|
||||
// #define USE_WIRE
|
||||
|
||||
#define I2C1_SDA 17
|
||||
#define I2C1_SCL 18
|
||||
|
||||
SensorQMI8658 qmi;
|
||||
|
||||
IMUdata acc;
|
||||
IMUdata gyr;
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(115200);
|
||||
while (!Serial);
|
||||
|
||||
#ifdef LILYGO_TBEAM_SUPREME_V3_0
|
||||
extern bool setupPower();
|
||||
setupPower();
|
||||
#endif
|
||||
|
||||
#ifdef USE_WIRE
|
||||
//Using WIRE !!
|
||||
if (!qmi.begin(Wire, QMI8658_L_SLAVE_ADDRESS, I2C1_SDA, I2C1_SCL)) {
|
||||
Serial.println("Failed to find QMI8658 - check your wiring!");
|
||||
while (1) {
|
||||
delay(1000);
|
||||
}
|
||||
}
|
||||
#else
|
||||
|
||||
#ifndef CONFIG_IDF_TARGET_ESP32
|
||||
//Use tbeams3 defalut spi pin
|
||||
#define SPI_MOSI (35)
|
||||
#define SPI_SCK (36)
|
||||
#define SPI_MISO (37)
|
||||
#define SPI_CS (47)
|
||||
#define IMU_CS (34)
|
||||
#define IMU_INT1 (33)
|
||||
|
||||
SPI.begin(SPI_SCK, SPI_MISO, SPI_MOSI);
|
||||
pinMode(SPI_CS, OUTPUT); //sdcard pin set high
|
||||
digitalWrite(SPI_CS, HIGH);
|
||||
if (!qmi.begin(IMU_CS, SPI_MOSI, SPI_MISO, SPI_SCK)) {
|
||||
|
||||
#else
|
||||
//Use esp32dev module defalut spi pin
|
||||
#define IMU_CS (5)
|
||||
#define IMU_INT1 (15)
|
||||
#define IMU_INT2 (22)
|
||||
if (!qmi.begin(IMU_CS)) {
|
||||
#endif
|
||||
Serial.println("Failed to find QMI8658 - check your wiring!");
|
||||
while (1) {
|
||||
delay(1000);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
/* Get chip id*/
|
||||
Serial.print("Device ID:");
|
||||
Serial.println(qmi.getChipID(), HEX);
|
||||
|
||||
qmi.configAccelerometer(
|
||||
/*
|
||||
* ACC_RANGE_2G
|
||||
* ACC_RANGE_4G
|
||||
* ACC_RANGE_8G
|
||||
* ACC_RANGE_16G
|
||||
* */
|
||||
SensorQMI8658::ACC_RANGE_4G,
|
||||
/*
|
||||
* ACC_ODR_1000H
|
||||
* ACC_ODR_500Hz
|
||||
* ACC_ODR_250Hz
|
||||
* ACC_ODR_125Hz
|
||||
* ACC_ODR_62_5Hz
|
||||
* ACC_ODR_31_25Hz
|
||||
* ACC_ODR_LOWPOWER_128Hz
|
||||
* ACC_ODR_LOWPOWER_21Hz
|
||||
* ACC_ODR_LOWPOWER_11Hz
|
||||
* ACC_ODR_LOWPOWER_3H
|
||||
* */
|
||||
SensorQMI8658::ACC_ODR_1000Hz,
|
||||
/*
|
||||
* LPF_MODE_0 //2.66% of ODR
|
||||
* LPF_MODE_1 //3.63% of ODR
|
||||
* LPF_MODE_2 //5.39% of ODR
|
||||
* LPF_MODE_3 //13.37% of ODR
|
||||
* */
|
||||
SensorQMI8658::LPF_MODE_0,
|
||||
// selfTest enable
|
||||
true);
|
||||
|
||||
|
||||
qmi.configGyroscope(
|
||||
/*
|
||||
* GYR_RANGE_16DPS
|
||||
* GYR_RANGE_32DPS
|
||||
* GYR_RANGE_64DPS
|
||||
* GYR_RANGE_128DPS
|
||||
* GYR_RANGE_256DPS
|
||||
* GYR_RANGE_512DPS
|
||||
* GYR_RANGE_1024DPS
|
||||
* */
|
||||
SensorQMI8658::GYR_RANGE_64DPS,
|
||||
/*
|
||||
* GYR_ODR_7174_4Hz
|
||||
* GYR_ODR_3587_2Hz
|
||||
* GYR_ODR_1793_6Hz
|
||||
* GYR_ODR_896_8Hz
|
||||
* GYR_ODR_448_4Hz
|
||||
* GYR_ODR_224_2Hz
|
||||
* GYR_ODR_112_1Hz
|
||||
* GYR_ODR_56_05Hz
|
||||
* GYR_ODR_28_025H
|
||||
* */
|
||||
SensorQMI8658::GYR_ODR_896_8Hz,
|
||||
/*
|
||||
* LPF_MODE_0 //2.66% of ODR
|
||||
* LPF_MODE_1 //3.63% of ODR
|
||||
* LPF_MODE_2 //5.39% of ODR
|
||||
* LPF_MODE_3 //13.37% of ODR
|
||||
* */
|
||||
SensorQMI8658::LPF_MODE_3,
|
||||
// selfTest enable
|
||||
true);
|
||||
|
||||
|
||||
// In 6DOF mode (accelerometer and gyroscope are both enabled),
|
||||
// the output data rate is derived from the nature frequency of gyroscope
|
||||
qmi.enableGyroscope();
|
||||
qmi.enableAccelerometer();
|
||||
|
||||
|
||||
pinMode(IMU_INT1, INPUT);
|
||||
#ifdef IMU_INT2
|
||||
pinMode(IMU_INT2, INPUT);
|
||||
#endif
|
||||
|
||||
// qmi.enableINT(SensorQMI8658::IntPin1); //no use
|
||||
// Enable data ready to interrupt pin2
|
||||
qmi.enableINT(SensorQMI8658::IntPin2);
|
||||
qmi.enableDataReadyINT();
|
||||
|
||||
// Print register configuration information
|
||||
qmi.dumpCtrlRegister();
|
||||
|
||||
Serial.println("Read data now...");
|
||||
}
|
||||
|
||||
void readSensorData(const char *name)
|
||||
{
|
||||
uint8_t status = qmi.getIrqStatus();
|
||||
// status == 0x01
|
||||
// If syncSmpl (CTRL7.bit7) = 1:
|
||||
// 0: Sensor Data is not available
|
||||
// 1: Sensor Data is available for reading
|
||||
// If syncSmpl = 0, this bit shows the same value of INT2 level
|
||||
Serial.print(name);
|
||||
Serial.print(" -> [");
|
||||
Serial.print(millis());
|
||||
Serial.print("]: -<HEX> ");
|
||||
Serial.print(status);
|
||||
Serial.print(" -<BIN> ");
|
||||
Serial.println(status, BIN);
|
||||
if (status & 0x01) {
|
||||
if (qmi.getAccelerometer(acc.x, acc.y, acc.z)) {
|
||||
Serial.print("{ACCEL: ");
|
||||
Serial.print(acc.x);
|
||||
Serial.print(",");
|
||||
Serial.print(acc.y);
|
||||
Serial.print(",");
|
||||
Serial.print(acc.z);
|
||||
Serial.println("}");
|
||||
}
|
||||
|
||||
if (qmi.getGyroscope(gyr.x, gyr.y, gyr.z)) {
|
||||
Serial.print("{GYRO: ");
|
||||
Serial.print(gyr.x);
|
||||
Serial.print(",");
|
||||
Serial.print(gyr.y );
|
||||
Serial.print(",");
|
||||
Serial.print(gyr.z);
|
||||
Serial.println("}");
|
||||
}
|
||||
Serial.printf("\t\t\t\t > %lu %.2f *C\n", qmi.getTimestamp(), qmi.getTemperature_C());
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
if (digitalRead(IMU_INT1) == HIGH) {
|
||||
readSensorData("INT1");
|
||||
}
|
||||
|
||||
#ifdef IMU_INT2
|
||||
if (digitalRead(IMU_INT2) == HIGH) {
|
||||
readSensorData("INT2");
|
||||
}
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
167
lib/SensorsLib/examples/QMI8658_InterruptExample/power.cpp
Normal file
167
lib/SensorsLib/examples/QMI8658_InterruptExample/power.cpp
Normal file
|
|
@ -0,0 +1,167 @@
|
|||
/**
|
||||
* @file power.cpp
|
||||
* @author Lewis He (lewishe@outlook.com)
|
||||
* @license MIT
|
||||
* @copyright Copyright (c) 2022
|
||||
* @date 2022-10-25
|
||||
*
|
||||
*/
|
||||
|
||||
|
||||
#ifdef LILYGO_TBEAM_SUPREME_V3_0
|
||||
#include <Wire.h>
|
||||
#include "XPowersAXP2101.tpp"
|
||||
#include "XPowersAXP192.tpp"
|
||||
|
||||
|
||||
|
||||
#define I2C_SDA 42
|
||||
#define I2C_SCL 41
|
||||
#define PMU_IRQ 40
|
||||
|
||||
XPowersLibInterface *PMU = NULL;
|
||||
|
||||
bool setupPower()
|
||||
{
|
||||
Serial.println("setupPower");
|
||||
|
||||
if (!PMU) {
|
||||
PMU = new XPowersAXP2101(Wire1, I2C_SDA, I2C_SCL);
|
||||
if (!PMU->init()) {
|
||||
Serial.println("Warning: Failed to find AXP2101 power management");
|
||||
delete PMU;
|
||||
PMU = NULL;
|
||||
} else {
|
||||
Serial.println("AXP2101 PMU init succeeded, using AXP2101 PMU");
|
||||
}
|
||||
}
|
||||
|
||||
if (!PMU) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (PMU->getChipModel() == XPOWERS_AXP2101) {
|
||||
|
||||
#if defined(LILYGO_TBEAM_V1_2)
|
||||
|
||||
PMU->setProtectedChannel(XPOWERS_DCDC1);
|
||||
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC2);
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC3);
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC4);
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC5);
|
||||
|
||||
// PMU->disablePowerOutput(XPOWERS_ALDO1);
|
||||
// PMU->disablePowerOutput(XPOWERS_ALDO2);
|
||||
// PMU->disablePowerOutput(XPOWERS_ALDO3);
|
||||
PMU->disablePowerOutput(XPOWERS_ALDO4);
|
||||
|
||||
PMU->disablePowerOutput(XPOWERS_BLDO1);
|
||||
PMU->disablePowerOutput(XPOWERS_BLDO2);
|
||||
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO1);
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO2);
|
||||
|
||||
PMU->enablePowerOutput(XPOWERS_VBACKUP);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO1);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO2);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO3);
|
||||
|
||||
PMU->setChargeTargetVoltage(XPOWERS_AXP2101_CHG_VOL_4V4);
|
||||
|
||||
#elif defined(LILYGO_TBEAM_SUPREME_V3_0)
|
||||
|
||||
//t-beam m.2 inface
|
||||
//gps
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO4, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO4);
|
||||
|
||||
// lora
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO3, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO3);
|
||||
|
||||
// Sensor
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO1, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO1);
|
||||
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO2, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO2);
|
||||
|
||||
//Sdcard
|
||||
PMU->setPowerChannelVoltage(XPOWERS_BLDO1, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_BLDO1);
|
||||
|
||||
//face m.2
|
||||
PMU->setPowerChannelVoltage(XPOWERS_DCDC3, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_DCDC3);
|
||||
|
||||
PMU->setPowerChannelVoltage(XPOWERS_DCDC4, XPOWERS_AXP2101_DCDC4_VOL2_MAX);
|
||||
PMU->enablePowerOutput(XPOWERS_DCDC4);
|
||||
|
||||
PMU->setPowerChannelVoltage(XPOWERS_DCDC5, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_DCDC5);
|
||||
|
||||
|
||||
//not use channel
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC2);
|
||||
// PMU->disablePowerOutput(XPOWERS_DCDC4);
|
||||
// PMU->disablePowerOutput(XPOWERS_DCDC5);
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO1);
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO2);
|
||||
PMU->disablePowerOutput(XPOWERS_VBACKUP);
|
||||
|
||||
#endif
|
||||
}
|
||||
|
||||
PMU->enableSystemVoltageMeasure();
|
||||
PMU->enableVbusVoltageMeasure();
|
||||
PMU->enableBattVoltageMeasure();
|
||||
PMU->disableTSPinMeasure();
|
||||
|
||||
Serial.printf("=========================================\n");
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC1)) {
|
||||
Serial.printf("DC1 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC1) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC1));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC2)) {
|
||||
Serial.printf("DC2 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC2));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC3)) {
|
||||
Serial.printf("DC3 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC3) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC3));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC4)) {
|
||||
Serial.printf("DC4 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC4) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC4));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC5)) {
|
||||
Serial.printf("DC5 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC5) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC5));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_LDO2)) {
|
||||
Serial.printf("LDO2 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_LDO2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_LDO2));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_LDO3)) {
|
||||
Serial.printf("LDO3 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_LDO3) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_LDO3));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO1)) {
|
||||
Serial.printf("ALDO1: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO1) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO1));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO2)) {
|
||||
Serial.printf("ALDO2: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO2));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO3)) {
|
||||
Serial.printf("ALDO3: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO3) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO3));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO4)) {
|
||||
Serial.printf("ALDO4: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO4) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO4));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_BLDO1)) {
|
||||
Serial.printf("BLDO1: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_BLDO1) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_BLDO1));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_BLDO2)) {
|
||||
Serial.printf("BLDO2: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_BLDO2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_BLDO2));
|
||||
}
|
||||
Serial.printf("=========================================\n");
|
||||
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
@ -0,0 +1,241 @@
|
|||
/**
|
||||
*
|
||||
* @license MIT License
|
||||
*
|
||||
* Copyright (c) 2022 lewis he
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
* @file QMI8658_LockingMechanismExample.ino
|
||||
* @author Lewis He (lewishe@outlook.com)
|
||||
* @date 2022-11-07
|
||||
*
|
||||
*/
|
||||
#include <Arduino.h>
|
||||
#include <Wire.h>
|
||||
#include <SPI.h>
|
||||
#include "SensorQMI8658.hpp"
|
||||
|
||||
// #define USE_WIRE
|
||||
|
||||
#define I2C1_SDA 17
|
||||
#define I2C1_SCL 18
|
||||
|
||||
SensorQMI8658 qmi;
|
||||
|
||||
IMUdata acc;
|
||||
IMUdata gyr;
|
||||
|
||||
bool interruptFlag = false;
|
||||
|
||||
void setFlag(void)
|
||||
{
|
||||
interruptFlag = true;
|
||||
}
|
||||
|
||||
// Callback when data is locked
|
||||
void lockingMechanismHandler()
|
||||
{
|
||||
if (qmi.getAccelerometer(acc.x, acc.y, acc.z)) {
|
||||
Serial.print("{ACCEL: ");
|
||||
Serial.print(acc.x);
|
||||
Serial.print(",");
|
||||
Serial.print(acc.y);
|
||||
Serial.print(",");
|
||||
Serial.print(acc.z);
|
||||
Serial.println("}");
|
||||
}
|
||||
|
||||
if (qmi.getGyroscope(gyr.x, gyr.y, gyr.z)) {
|
||||
Serial.print("{GYRO: ");
|
||||
Serial.print(gyr.x);
|
||||
Serial.print(",");
|
||||
Serial.print(gyr.y );
|
||||
Serial.print(",");
|
||||
Serial.print(gyr.z);
|
||||
Serial.println("}");
|
||||
}
|
||||
Serial.printf("\t\t\t\t > %lu %.2f *C\n", qmi.getTimestamp(), qmi.getTemperature_C());
|
||||
}
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(115200);
|
||||
while (!Serial);
|
||||
|
||||
#ifdef LILYGO_TBEAM_SUPREME_V3_0
|
||||
extern bool setupPower();
|
||||
setupPower();
|
||||
#endif
|
||||
|
||||
#ifdef USE_WIRE
|
||||
//Using WIRE !!
|
||||
if (!qmi.begin(Wire, QMI8658_L_SLAVE_ADDRESS, I2C1_SDA, I2C1_SCL)) {
|
||||
Serial.println("Failed to find QMI8658 - check your wiring!");
|
||||
while (1) {
|
||||
delay(1000);
|
||||
}
|
||||
}
|
||||
#else
|
||||
|
||||
#ifndef CONFIG_IDF_TARGET_ESP32
|
||||
//Use tbeams3 defalut spi pin
|
||||
#define SPI_MOSI (35)
|
||||
#define SPI_SCK (36)
|
||||
#define SPI_MISO (37)
|
||||
#define SPI_CS (47)
|
||||
#define IMU_CS (34)
|
||||
#define IMU_INT1 (33)
|
||||
|
||||
SPI.begin(SPI_SCK, SPI_MISO, SPI_MOSI);
|
||||
pinMode(SPI_CS, OUTPUT); //sdcard pin set high
|
||||
digitalWrite(SPI_CS, HIGH);
|
||||
if (!qmi.begin(IMU_CS, SPI_MOSI, SPI_MISO, SPI_SCK)) {
|
||||
|
||||
#else
|
||||
//Use esp32dev module defalut spi pin
|
||||
#define IMU_CS (5)
|
||||
#define IMU_INT1 (15)
|
||||
#define IMU_INT2 (22)
|
||||
if (!qmi.begin(IMU_CS)) {
|
||||
#endif
|
||||
Serial.println("Failed to find QMI8658 - check your wiring!");
|
||||
while (1) {
|
||||
delay(1000);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
/* Get chip id*/
|
||||
Serial.print("Device ID:");
|
||||
Serial.println(qmi.getChipID(), HEX);
|
||||
|
||||
qmi.configAccelerometer(
|
||||
/*
|
||||
* ACC_RANGE_2G
|
||||
* ACC_RANGE_4G
|
||||
* ACC_RANGE_8G
|
||||
* ACC_RANGE_16G
|
||||
* */
|
||||
SensorQMI8658::ACC_RANGE_4G,
|
||||
/*
|
||||
* ACC_ODR_1000H
|
||||
* ACC_ODR_500Hz
|
||||
* ACC_ODR_250Hz
|
||||
* ACC_ODR_125Hz
|
||||
* ACC_ODR_62_5Hz
|
||||
* ACC_ODR_31_25Hz
|
||||
* ACC_ODR_LOWPOWER_128Hz
|
||||
* ACC_ODR_LOWPOWER_21Hz
|
||||
* ACC_ODR_LOWPOWER_11Hz
|
||||
* ACC_ODR_LOWPOWER_3H
|
||||
* */
|
||||
SensorQMI8658::ACC_ODR_1000Hz,
|
||||
/*
|
||||
* LPF_MODE_0 //2.66% of ODR
|
||||
* LPF_MODE_1 //3.63% of ODR
|
||||
* LPF_MODE_2 //5.39% of ODR
|
||||
* LPF_MODE_3 //13.37% of ODR
|
||||
* */
|
||||
SensorQMI8658::LPF_MODE_0,
|
||||
// selfTest enable
|
||||
true);
|
||||
|
||||
|
||||
qmi.configGyroscope(
|
||||
/*
|
||||
* GYR_RANGE_16DPS
|
||||
* GYR_RANGE_32DPS
|
||||
* GYR_RANGE_64DPS
|
||||
* GYR_RANGE_128DPS
|
||||
* GYR_RANGE_256DPS
|
||||
* GYR_RANGE_512DPS
|
||||
* GYR_RANGE_1024DPS
|
||||
* */
|
||||
SensorQMI8658::GYR_RANGE_64DPS,
|
||||
/*
|
||||
* GYR_ODR_7174_4Hz
|
||||
* GYR_ODR_3587_2Hz
|
||||
* GYR_ODR_1793_6Hz
|
||||
* GYR_ODR_896_8Hz
|
||||
* GYR_ODR_448_4Hz
|
||||
* GYR_ODR_224_2Hz
|
||||
* GYR_ODR_112_1Hz
|
||||
* GYR_ODR_56_05Hz
|
||||
* GYR_ODR_28_025H
|
||||
* */
|
||||
SensorQMI8658::GYR_ODR_896_8Hz,
|
||||
/*
|
||||
* LPF_MODE_0 //2.66% of ODR
|
||||
* LPF_MODE_1 //3.63% of ODR
|
||||
* LPF_MODE_2 //5.39% of ODR
|
||||
* LPF_MODE_3 //13.37% of ODR
|
||||
* */
|
||||
SensorQMI8658::LPF_MODE_3,
|
||||
// selfTest enable
|
||||
true);
|
||||
|
||||
// In 6DOF mode (accelerometer and gyroscope are both enabled),
|
||||
// the output data rate is derived from the nature frequency of gyroscope
|
||||
qmi.enableGyroscope();
|
||||
qmi.enableAccelerometer();
|
||||
|
||||
//Enable Locking Mechanism
|
||||
qmi.enableLockingMechanism();
|
||||
|
||||
// Set locking data event callback
|
||||
qmi.setDataLockingEvevntCallBack(lockingMechanismHandler);
|
||||
|
||||
|
||||
// Use interrupt .
|
||||
// QMI8658 interrupt always outputs low level by default,
|
||||
// and the interrupt is triggered when the rising edge
|
||||
pinMode(IMU_INT1, INPUT_PULLUP);
|
||||
#ifdef IMU_INT2
|
||||
pinMode(IMU_INT2, INPUT_PULLUP);
|
||||
attachInterrupt(IMU_INT2, setFlag, RISING);
|
||||
#else
|
||||
attachInterrupt(IMU_INT1, setFlag, RISING);
|
||||
#endif
|
||||
|
||||
// qmi.enableINT(SensorQMI8658::IntPin1); //no use
|
||||
// Enable data ready to interrupt pin2
|
||||
qmi.enableINT(SensorQMI8658::IntPin2);
|
||||
|
||||
|
||||
// Print register configuration information
|
||||
qmi.dumpCtrlRegister();
|
||||
|
||||
|
||||
Serial.println("Read data now...");
|
||||
}
|
||||
|
||||
|
||||
void loop()
|
||||
{
|
||||
if (interruptFlag) {
|
||||
interruptFlag = false;
|
||||
qmi.readSensorStatus();
|
||||
}
|
||||
delay(100);
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
|
|
@ -0,0 +1,167 @@
|
|||
/**
|
||||
* @file power.cpp
|
||||
* @author Lewis He (lewishe@outlook.com)
|
||||
* @license MIT
|
||||
* @copyright Copyright (c) 2022
|
||||
* @date 2022-10-25
|
||||
*
|
||||
*/
|
||||
|
||||
|
||||
#ifdef LILYGO_TBEAM_SUPREME_V3_0
|
||||
#include <Wire.h>
|
||||
#include "XPowersAXP2101.tpp"
|
||||
#include "XPowersAXP192.tpp"
|
||||
|
||||
|
||||
|
||||
#define I2C_SDA 42
|
||||
#define I2C_SCL 41
|
||||
#define PMU_IRQ 40
|
||||
|
||||
XPowersLibInterface *PMU = NULL;
|
||||
|
||||
bool setupPower()
|
||||
{
|
||||
Serial.println("setupPower");
|
||||
|
||||
if (!PMU) {
|
||||
PMU = new XPowersAXP2101(Wire1, I2C_SDA, I2C_SCL);
|
||||
if (!PMU->init()) {
|
||||
Serial.println("Warning: Failed to find AXP2101 power management");
|
||||
delete PMU;
|
||||
PMU = NULL;
|
||||
} else {
|
||||
Serial.println("AXP2101 PMU init succeeded, using AXP2101 PMU");
|
||||
}
|
||||
}
|
||||
|
||||
if (!PMU) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (PMU->getChipModel() == XPOWERS_AXP2101) {
|
||||
|
||||
#if defined(LILYGO_TBEAM_V1_2)
|
||||
|
||||
PMU->setProtectedChannel(XPOWERS_DCDC1);
|
||||
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC2);
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC3);
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC4);
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC5);
|
||||
|
||||
// PMU->disablePowerOutput(XPOWERS_ALDO1);
|
||||
// PMU->disablePowerOutput(XPOWERS_ALDO2);
|
||||
// PMU->disablePowerOutput(XPOWERS_ALDO3);
|
||||
PMU->disablePowerOutput(XPOWERS_ALDO4);
|
||||
|
||||
PMU->disablePowerOutput(XPOWERS_BLDO1);
|
||||
PMU->disablePowerOutput(XPOWERS_BLDO2);
|
||||
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO1);
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO2);
|
||||
|
||||
PMU->enablePowerOutput(XPOWERS_VBACKUP);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO1);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO2);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO3);
|
||||
|
||||
PMU->setChargeTargetVoltage(XPOWERS_AXP2101_CHG_VOL_4V4);
|
||||
|
||||
#elif defined(LILYGO_TBEAM_SUPREME_V3_0)
|
||||
|
||||
//t-beam m.2 inface
|
||||
//gps
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO4, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO4);
|
||||
|
||||
// lora
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO3, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO3);
|
||||
|
||||
// Sensor
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO1, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO1);
|
||||
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO2, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO2);
|
||||
|
||||
//Sdcard
|
||||
PMU->setPowerChannelVoltage(XPOWERS_BLDO1, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_BLDO1);
|
||||
|
||||
//face m.2
|
||||
PMU->setPowerChannelVoltage(XPOWERS_DCDC3, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_DCDC3);
|
||||
|
||||
PMU->setPowerChannelVoltage(XPOWERS_DCDC4, XPOWERS_AXP2101_DCDC4_VOL2_MAX);
|
||||
PMU->enablePowerOutput(XPOWERS_DCDC4);
|
||||
|
||||
PMU->setPowerChannelVoltage(XPOWERS_DCDC5, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_DCDC5);
|
||||
|
||||
|
||||
//not use channel
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC2);
|
||||
// PMU->disablePowerOutput(XPOWERS_DCDC4);
|
||||
// PMU->disablePowerOutput(XPOWERS_DCDC5);
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO1);
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO2);
|
||||
PMU->disablePowerOutput(XPOWERS_VBACKUP);
|
||||
|
||||
#endif
|
||||
}
|
||||
|
||||
PMU->enableSystemVoltageMeasure();
|
||||
PMU->enableVbusVoltageMeasure();
|
||||
PMU->enableBattVoltageMeasure();
|
||||
PMU->disableTSPinMeasure();
|
||||
|
||||
Serial.printf("=========================================\n");
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC1)) {
|
||||
Serial.printf("DC1 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC1) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC1));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC2)) {
|
||||
Serial.printf("DC2 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC2));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC3)) {
|
||||
Serial.printf("DC3 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC3) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC3));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC4)) {
|
||||
Serial.printf("DC4 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC4) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC4));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC5)) {
|
||||
Serial.printf("DC5 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC5) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC5));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_LDO2)) {
|
||||
Serial.printf("LDO2 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_LDO2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_LDO2));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_LDO3)) {
|
||||
Serial.printf("LDO3 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_LDO3) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_LDO3));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO1)) {
|
||||
Serial.printf("ALDO1: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO1) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO1));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO2)) {
|
||||
Serial.printf("ALDO2: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO2));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO3)) {
|
||||
Serial.printf("ALDO3: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO3) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO3));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO4)) {
|
||||
Serial.printf("ALDO4: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO4) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO4));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_BLDO1)) {
|
||||
Serial.printf("BLDO1: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_BLDO1) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_BLDO1));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_BLDO2)) {
|
||||
Serial.printf("BLDO2: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_BLDO2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_BLDO2));
|
||||
}
|
||||
Serial.printf("=========================================\n");
|
||||
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
@ -0,0 +1,198 @@
|
|||
/**
|
||||
*
|
||||
* @license MIT License
|
||||
*
|
||||
* Copyright (c) 2022 lewis he
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
* @file QMI8658_MadgwickAHRS.ino
|
||||
* @author Lewis He (lewishe@outlook.com)
|
||||
* @date 2022-10-16
|
||||
*
|
||||
*/
|
||||
#include <Arduino.h>
|
||||
#include <Wire.h>
|
||||
#include <SPI.h>
|
||||
#include "SensorQMI8658.hpp"
|
||||
#include <MadgwickAHRS.h> //MadgwickAHRS from https://github.com/arduino-libraries/MadgwickAHRS
|
||||
|
||||
#define USE_WIRE
|
||||
|
||||
#define I2C1_SDA 17
|
||||
#define I2C1_SCL 18
|
||||
|
||||
#define IMU_CS 5
|
||||
|
||||
SensorQMI8658 qmi;
|
||||
|
||||
IMUdata acc;
|
||||
IMUdata gyr;
|
||||
|
||||
Madgwick filter;
|
||||
unsigned long microsPerReading, microsPrevious;
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(115200);
|
||||
while (!Serial);
|
||||
|
||||
#ifdef LILYGO_TBEAM_SUPREME_V3_0
|
||||
extern bool setupPower();
|
||||
setupPower();
|
||||
#endif
|
||||
|
||||
#ifdef USE_WIRE
|
||||
//Using WIRE !!
|
||||
if (!qmi.begin(Wire, QMI8658_L_SLAVE_ADDRESS, I2C1_SDA, I2C1_SCL)) {
|
||||
Serial.println("Failed to find QMI8658 - check your wiring!");
|
||||
while (1) {
|
||||
delay(1000);
|
||||
}
|
||||
}
|
||||
#else
|
||||
if (!qmi.begin(IMU_CS)) {
|
||||
Serial.println("Failed to find QMI8658 - check your wiring!");
|
||||
while (1) {
|
||||
delay(1000);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
/* Get chip id*/
|
||||
Serial.print("Device ID:");
|
||||
Serial.println(qmi.getChipID(), HEX);
|
||||
|
||||
qmi.configAccelerometer(
|
||||
/*
|
||||
* ACC_RANGE_2G
|
||||
* ACC_RANGE_4G
|
||||
* ACC_RANGE_8G
|
||||
* ACC_RANGE_16G
|
||||
* */
|
||||
SensorQMI8658::ACC_RANGE_2G,
|
||||
/*
|
||||
* ACC_ODR_1000H
|
||||
* ACC_ODR_500Hz
|
||||
* ACC_ODR_250Hz
|
||||
* ACC_ODR_125Hz
|
||||
* ACC_ODR_62_5Hz
|
||||
* ACC_ODR_31_25Hz
|
||||
* ACC_ODR_LOWPOWER_128Hz
|
||||
* ACC_ODR_LOWPOWER_21Hz
|
||||
* ACC_ODR_LOWPOWER_11Hz
|
||||
* ACC_ODR_LOWPOWER_3H
|
||||
* */
|
||||
SensorQMI8658::ACC_ODR_1000Hz,
|
||||
/*
|
||||
* LPF_MODE_0 //2.66% of ODR
|
||||
* LPF_MODE_1 //3.63% of ODR
|
||||
* LPF_MODE_2 //5.39% of ODR
|
||||
* LPF_MODE_3 //13.37% of ODR
|
||||
* */
|
||||
SensorQMI8658::LPF_MODE_0,
|
||||
// selfTest enable
|
||||
true);
|
||||
|
||||
|
||||
qmi.configGyroscope(
|
||||
/*
|
||||
* GYR_RANGE_16DPS
|
||||
* GYR_RANGE_32DPS
|
||||
* GYR_RANGE_64DPS
|
||||
* GYR_RANGE_128DPS
|
||||
* GYR_RANGE_256DPS
|
||||
* GYR_RANGE_512DPS
|
||||
* GYR_RANGE_1024DPS
|
||||
* */
|
||||
SensorQMI8658::GYR_RANGE_256DPS,
|
||||
/*
|
||||
* GYR_ODR_7174_4Hz
|
||||
* GYR_ODR_3587_2Hz
|
||||
* GYR_ODR_1793_6Hz
|
||||
* GYR_ODR_896_8Hz
|
||||
* GYR_ODR_448_4Hz
|
||||
* GYR_ODR_224_2Hz
|
||||
* GYR_ODR_112_1Hz
|
||||
* GYR_ODR_56_05Hz
|
||||
* GYR_ODR_28_025H
|
||||
* */
|
||||
SensorQMI8658::GYR_ODR_896_8Hz,
|
||||
/*
|
||||
* LPF_MODE_0 //2.66% of ODR
|
||||
* LPF_MODE_1 //3.63% of ODR
|
||||
* LPF_MODE_2 //5.39% of ODR
|
||||
* LPF_MODE_3 //13.37% of ODR
|
||||
* */
|
||||
SensorQMI8658::LPF_MODE_3,
|
||||
// selfTest enable
|
||||
true);
|
||||
|
||||
|
||||
// In 6DOF mode (accelerometer and gyroscope are both enabled),
|
||||
// the output data rate is derived from the nature frequency of gyroscope
|
||||
qmi.enableGyroscope();
|
||||
qmi.enableAccelerometer();
|
||||
|
||||
// Print register configuration information
|
||||
qmi.dumpCtrlRegister();
|
||||
|
||||
// start filter
|
||||
filter.begin(25);
|
||||
|
||||
// initialize variables to pace updates to correct rate
|
||||
microsPerReading = 1000000 / 25;
|
||||
microsPrevious = micros();
|
||||
|
||||
Serial.println("Read data now...");
|
||||
}
|
||||
|
||||
|
||||
void loop()
|
||||
{
|
||||
float roll, pitch, heading;
|
||||
|
||||
// check if it's time to read data and update the filter
|
||||
if (micros() - microsPrevious >= microsPerReading) {
|
||||
|
||||
// read raw data from IMU
|
||||
if (qmi.getDataReady()) {
|
||||
qmi.getAccelerometer(acc.x, acc.y, acc.z);
|
||||
qmi.getGyroscope(gyr.x, gyr.y, gyr.z);
|
||||
// update the filter, which computes orientation
|
||||
filter.updateIMU(gyr.x, gyr.y, gyr.z, acc.x, acc.y, acc.z);
|
||||
|
||||
// print the heading, pitch and roll
|
||||
roll = filter.getRoll();
|
||||
pitch = filter.getPitch();
|
||||
heading = filter.getYaw();
|
||||
Serial.print("Orientation: ");
|
||||
Serial.print(heading);
|
||||
Serial.print(" ");
|
||||
Serial.print(pitch);
|
||||
Serial.print(" ");
|
||||
Serial.println(roll);
|
||||
}
|
||||
// increment previous time, so we keep proper pace
|
||||
microsPrevious = microsPrevious + microsPerReading;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
167
lib/SensorsLib/examples/QMI8658_MadgwickAHRS/power.cpp
Normal file
167
lib/SensorsLib/examples/QMI8658_MadgwickAHRS/power.cpp
Normal file
|
|
@ -0,0 +1,167 @@
|
|||
/**
|
||||
* @file power.cpp
|
||||
* @author Lewis He (lewishe@outlook.com)
|
||||
* @license MIT
|
||||
* @copyright Copyright (c) 2022
|
||||
* @date 2022-10-25
|
||||
*
|
||||
*/
|
||||
|
||||
|
||||
#ifdef LILYGO_TBEAM_SUPREME_V3_0
|
||||
#include <Wire.h>
|
||||
#include "XPowersAXP2101.tpp"
|
||||
#include "XPowersAXP192.tpp"
|
||||
|
||||
|
||||
|
||||
#define I2C_SDA 42
|
||||
#define I2C_SCL 41
|
||||
#define PMU_IRQ 40
|
||||
|
||||
XPowersLibInterface *PMU = NULL;
|
||||
|
||||
bool setupPower()
|
||||
{
|
||||
Serial.println("setupPower");
|
||||
|
||||
if (!PMU) {
|
||||
PMU = new XPowersAXP2101(Wire1, I2C_SDA, I2C_SCL);
|
||||
if (!PMU->init()) {
|
||||
Serial.println("Warning: Failed to find AXP2101 power management");
|
||||
delete PMU;
|
||||
PMU = NULL;
|
||||
} else {
|
||||
Serial.println("AXP2101 PMU init succeeded, using AXP2101 PMU");
|
||||
}
|
||||
}
|
||||
|
||||
if (!PMU) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (PMU->getChipModel() == XPOWERS_AXP2101) {
|
||||
|
||||
#if defined(LILYGO_TBEAM_V1_2)
|
||||
|
||||
PMU->setProtectedChannel(XPOWERS_DCDC1);
|
||||
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC2);
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC3);
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC4);
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC5);
|
||||
|
||||
// PMU->disablePowerOutput(XPOWERS_ALDO1);
|
||||
// PMU->disablePowerOutput(XPOWERS_ALDO2);
|
||||
// PMU->disablePowerOutput(XPOWERS_ALDO3);
|
||||
PMU->disablePowerOutput(XPOWERS_ALDO4);
|
||||
|
||||
PMU->disablePowerOutput(XPOWERS_BLDO1);
|
||||
PMU->disablePowerOutput(XPOWERS_BLDO2);
|
||||
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO1);
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO2);
|
||||
|
||||
PMU->enablePowerOutput(XPOWERS_VBACKUP);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO1);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO2);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO3);
|
||||
|
||||
PMU->setChargeTargetVoltage(XPOWERS_AXP2101_CHG_VOL_4V4);
|
||||
|
||||
#elif defined(LILYGO_TBEAM_SUPREME_V3_0)
|
||||
|
||||
//t-beam m.2 inface
|
||||
//gps
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO4, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO4);
|
||||
|
||||
// lora
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO3, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO3);
|
||||
|
||||
// Sensor
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO1, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO1);
|
||||
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO2, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO2);
|
||||
|
||||
//Sdcard
|
||||
PMU->setPowerChannelVoltage(XPOWERS_BLDO1, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_BLDO1);
|
||||
|
||||
//face m.2
|
||||
PMU->setPowerChannelVoltage(XPOWERS_DCDC3, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_DCDC3);
|
||||
|
||||
PMU->setPowerChannelVoltage(XPOWERS_DCDC4, XPOWERS_AXP2101_DCDC4_VOL2_MAX);
|
||||
PMU->enablePowerOutput(XPOWERS_DCDC4);
|
||||
|
||||
PMU->setPowerChannelVoltage(XPOWERS_DCDC5, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_DCDC5);
|
||||
|
||||
|
||||
//not use channel
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC2);
|
||||
// PMU->disablePowerOutput(XPOWERS_DCDC4);
|
||||
// PMU->disablePowerOutput(XPOWERS_DCDC5);
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO1);
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO2);
|
||||
PMU->disablePowerOutput(XPOWERS_VBACKUP);
|
||||
|
||||
#endif
|
||||
}
|
||||
|
||||
PMU->enableSystemVoltageMeasure();
|
||||
PMU->enableVbusVoltageMeasure();
|
||||
PMU->enableBattVoltageMeasure();
|
||||
PMU->disableTSPinMeasure();
|
||||
|
||||
Serial.printf("=========================================\n");
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC1)) {
|
||||
Serial.printf("DC1 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC1) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC1));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC2)) {
|
||||
Serial.printf("DC2 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC2));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC3)) {
|
||||
Serial.printf("DC3 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC3) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC3));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC4)) {
|
||||
Serial.printf("DC4 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC4) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC4));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC5)) {
|
||||
Serial.printf("DC5 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC5) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC5));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_LDO2)) {
|
||||
Serial.printf("LDO2 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_LDO2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_LDO2));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_LDO3)) {
|
||||
Serial.printf("LDO3 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_LDO3) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_LDO3));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO1)) {
|
||||
Serial.printf("ALDO1: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO1) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO1));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO2)) {
|
||||
Serial.printf("ALDO2: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO2));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO3)) {
|
||||
Serial.printf("ALDO3: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO3) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO3));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO4)) {
|
||||
Serial.printf("ALDO4: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO4) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO4));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_BLDO1)) {
|
||||
Serial.printf("BLDO1: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_BLDO1) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_BLDO1));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_BLDO2)) {
|
||||
Serial.printf("BLDO2: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_BLDO2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_BLDO2));
|
||||
}
|
||||
Serial.printf("=========================================\n");
|
||||
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
@ -0,0 +1,191 @@
|
|||
/**
|
||||
*
|
||||
* @license MIT License
|
||||
*
|
||||
* Copyright (c) 2022 lewis he
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
* @file QMI8658_GetDataExample.ino
|
||||
* @author Lewis He (lewishe@outlook.com)
|
||||
* @date 2022-10-16
|
||||
*
|
||||
*/
|
||||
#include <Arduino.h>
|
||||
#include <Wire.h>
|
||||
#include <SPI.h>
|
||||
#include "SensorQMI8658.hpp"
|
||||
|
||||
#define USE_WIRE
|
||||
|
||||
#define I2C1_SDA 17
|
||||
#define I2C1_SCL 18
|
||||
|
||||
#define IMU_CS 5
|
||||
|
||||
SensorQMI8658 qmi;
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(115200);
|
||||
while (!Serial);
|
||||
|
||||
|
||||
#ifdef LILYGO_TBEAM_SUPREME_V3_0
|
||||
extern bool setupPower();
|
||||
setupPower();
|
||||
#endif
|
||||
|
||||
#ifdef USE_WIRE
|
||||
//Using WIRE !!
|
||||
if (!qmi.begin(Wire, QMI8658_L_SLAVE_ADDRESS, I2C1_SDA, I2C1_SCL)) {
|
||||
Serial.println("Failed to find QMI8658 - check your wiring!");
|
||||
while (1) {
|
||||
delay(1000);
|
||||
}
|
||||
}
|
||||
#else
|
||||
if (!qmi.begin(IMU_CS)) {
|
||||
Serial.println("Failed to find QMI8658 - check your wiring!");
|
||||
while (1) {
|
||||
delay(1000);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
/* Get chip id*/
|
||||
Serial.print("Device ID:");
|
||||
Serial.println(qmi.getChipID(), HEX);
|
||||
|
||||
qmi.configAccelerometer(
|
||||
/*
|
||||
* ACC_RANGE_2G
|
||||
* ACC_RANGE_4G
|
||||
* ACC_RANGE_8G
|
||||
* ACC_RANGE_16G
|
||||
* */
|
||||
SensorQMI8658::ACC_RANGE_4G,
|
||||
/*
|
||||
* ACC_ODR_1000H
|
||||
* ACC_ODR_500Hz
|
||||
* ACC_ODR_250Hz
|
||||
* ACC_ODR_125Hz
|
||||
* ACC_ODR_62_5Hz
|
||||
* ACC_ODR_31_25Hz
|
||||
* ACC_ODR_LOWPOWER_128Hz
|
||||
* ACC_ODR_LOWPOWER_21Hz
|
||||
* ACC_ODR_LOWPOWER_11Hz
|
||||
* ACC_ODR_LOWPOWER_3H
|
||||
* */
|
||||
SensorQMI8658::ACC_ODR_125Hz,
|
||||
/*
|
||||
* LPF_MODE_0 //2.66% of ODR
|
||||
* LPF_MODE_1 //3.63% of ODR
|
||||
* LPF_MODE_2 //5.39% of ODR
|
||||
* LPF_MODE_3 //13.37% of ODR
|
||||
* */
|
||||
SensorQMI8658::LPF_MODE_0,
|
||||
// selfTest enable
|
||||
true);
|
||||
|
||||
|
||||
qmi.configGyroscope(
|
||||
/*
|
||||
* GYR_RANGE_16DPS
|
||||
* GYR_RANGE_32DPS
|
||||
* GYR_RANGE_64DPS
|
||||
* GYR_RANGE_128DPS
|
||||
* GYR_RANGE_256DPS
|
||||
* GYR_RANGE_512DPS
|
||||
* GYR_RANGE_1024DPS
|
||||
* */
|
||||
SensorQMI8658::GYR_RANGE_64DPS,
|
||||
/*
|
||||
* GYR_ODR_7174_4Hz
|
||||
* GYR_ODR_3587_2Hz
|
||||
* GYR_ODR_1793_6Hz
|
||||
* GYR_ODR_896_8Hz
|
||||
* GYR_ODR_448_4Hz
|
||||
* GYR_ODR_224_2Hz
|
||||
* GYR_ODR_112_1Hz
|
||||
* GYR_ODR_56_05Hz
|
||||
* GYR_ODR_28_025H
|
||||
* */
|
||||
SensorQMI8658::GYR_ODR_112_1Hz,
|
||||
/*
|
||||
* LPF_MODE_0 //2.66% of ODR
|
||||
* LPF_MODE_1 //3.63% of ODR
|
||||
* LPF_MODE_2 //5.39% of ODR
|
||||
* LPF_MODE_3 //13.37% of ODR
|
||||
* */
|
||||
SensorQMI8658::LPF_MODE_3,
|
||||
// selfTest enable
|
||||
true);
|
||||
|
||||
|
||||
// In 6DOF mode (accelerometer and gyroscope are both enabled),
|
||||
// the output data rate is derived from the nature frequency of gyroscope
|
||||
qmi.enableGyroscope();
|
||||
qmi.enableAccelerometer();
|
||||
|
||||
|
||||
qmi.configPedometer(0x007D, 0x00CC, 0x0066, 0x00C8, 0x14, 0x0A, 0, 0x04);
|
||||
|
||||
qmi.enablePedometer();
|
||||
|
||||
// Print register configuration information
|
||||
qmi.dumpCtrlRegister();
|
||||
|
||||
Serial.println("Read data now...");
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
||||
void loop()
|
||||
{
|
||||
// Get IMU status
|
||||
uint8_t status = qmi.getStatusRegister();
|
||||
Serial.printf("STATUS:0x%x BIN:", status);
|
||||
Serial.println(status, BIN);
|
||||
|
||||
if (status & SensorQMI8658::EVENT_TAP_MOITON) {
|
||||
Serial.println("Detected TAP event");
|
||||
qmi.getTapStatus();
|
||||
}
|
||||
if (status & SensorQMI8658::EVENT_WOM_MOITON) {
|
||||
Serial.println("Detected Wom event");
|
||||
}
|
||||
if (status & SensorQMI8658::EVENT_PEDOMETER_MOITON) {
|
||||
Serial.println("Detected Pedometer event");
|
||||
uint32_t val = qmi.getPedometerCounter();
|
||||
Serial.println(val);
|
||||
}
|
||||
if (status & SensorQMI8658::EVENT_ANY_MOITON) {
|
||||
Serial.println("Detected Any Motion event");
|
||||
}
|
||||
if (status & SensorQMI8658::EVENT_NO_MOITON) {
|
||||
Serial.println("Detected No Motion event");
|
||||
}
|
||||
if (status & SensorQMI8658::EVENT_SIGNIFICANT_MOITON) {
|
||||
Serial.println("Detected Significant Motion event");
|
||||
}
|
||||
|
||||
delay(500);
|
||||
}
|
||||
167
lib/SensorsLib/examples/QMI8658_PedometerExample/power.cpp
Normal file
167
lib/SensorsLib/examples/QMI8658_PedometerExample/power.cpp
Normal file
|
|
@ -0,0 +1,167 @@
|
|||
/**
|
||||
* @file power.cpp
|
||||
* @author Lewis He (lewishe@outlook.com)
|
||||
* @license MIT
|
||||
* @copyright Copyright (c) 2022
|
||||
* @date 2022-10-25
|
||||
*
|
||||
*/
|
||||
|
||||
|
||||
#ifdef LILYGO_TBEAM_SUPREME_V3_0
|
||||
#include <Wire.h>
|
||||
#include "XPowersAXP2101.tpp"
|
||||
#include "XPowersAXP192.tpp"
|
||||
|
||||
|
||||
|
||||
#define I2C_SDA 42
|
||||
#define I2C_SCL 41
|
||||
#define PMU_IRQ 40
|
||||
|
||||
XPowersLibInterface *PMU = NULL;
|
||||
|
||||
bool setupPower()
|
||||
{
|
||||
Serial.println("setupPower");
|
||||
|
||||
if (!PMU) {
|
||||
PMU = new XPowersAXP2101(Wire1, I2C_SDA, I2C_SCL);
|
||||
if (!PMU->init()) {
|
||||
Serial.println("Warning: Failed to find AXP2101 power management");
|
||||
delete PMU;
|
||||
PMU = NULL;
|
||||
} else {
|
||||
Serial.println("AXP2101 PMU init succeeded, using AXP2101 PMU");
|
||||
}
|
||||
}
|
||||
|
||||
if (!PMU) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (PMU->getChipModel() == XPOWERS_AXP2101) {
|
||||
|
||||
#if defined(LILYGO_TBEAM_V1_2)
|
||||
|
||||
PMU->setProtectedChannel(XPOWERS_DCDC1);
|
||||
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC2);
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC3);
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC4);
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC5);
|
||||
|
||||
// PMU->disablePowerOutput(XPOWERS_ALDO1);
|
||||
// PMU->disablePowerOutput(XPOWERS_ALDO2);
|
||||
// PMU->disablePowerOutput(XPOWERS_ALDO3);
|
||||
PMU->disablePowerOutput(XPOWERS_ALDO4);
|
||||
|
||||
PMU->disablePowerOutput(XPOWERS_BLDO1);
|
||||
PMU->disablePowerOutput(XPOWERS_BLDO2);
|
||||
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO1);
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO2);
|
||||
|
||||
PMU->enablePowerOutput(XPOWERS_VBACKUP);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO1);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO2);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO3);
|
||||
|
||||
PMU->setChargeTargetVoltage(XPOWERS_AXP2101_CHG_VOL_4V4);
|
||||
|
||||
#elif defined(LILYGO_TBEAM_SUPREME_V3_0)
|
||||
|
||||
//t-beam m.2 inface
|
||||
//gps
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO4, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO4);
|
||||
|
||||
// lora
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO3, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO3);
|
||||
|
||||
// Sensor
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO1, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO1);
|
||||
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO2, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO2);
|
||||
|
||||
//Sdcard
|
||||
PMU->setPowerChannelVoltage(XPOWERS_BLDO1, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_BLDO1);
|
||||
|
||||
//face m.2
|
||||
PMU->setPowerChannelVoltage(XPOWERS_DCDC3, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_DCDC3);
|
||||
|
||||
PMU->setPowerChannelVoltage(XPOWERS_DCDC4, XPOWERS_AXP2101_DCDC4_VOL2_MAX);
|
||||
PMU->enablePowerOutput(XPOWERS_DCDC4);
|
||||
|
||||
PMU->setPowerChannelVoltage(XPOWERS_DCDC5, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_DCDC5);
|
||||
|
||||
|
||||
//not use channel
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC2);
|
||||
// PMU->disablePowerOutput(XPOWERS_DCDC4);
|
||||
// PMU->disablePowerOutput(XPOWERS_DCDC5);
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO1);
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO2);
|
||||
PMU->disablePowerOutput(XPOWERS_VBACKUP);
|
||||
|
||||
#endif
|
||||
}
|
||||
|
||||
PMU->enableSystemVoltageMeasure();
|
||||
PMU->enableVbusVoltageMeasure();
|
||||
PMU->enableBattVoltageMeasure();
|
||||
PMU->disableTSPinMeasure();
|
||||
|
||||
Serial.printf("=========================================\n");
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC1)) {
|
||||
Serial.printf("DC1 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC1) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC1));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC2)) {
|
||||
Serial.printf("DC2 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC2));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC3)) {
|
||||
Serial.printf("DC3 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC3) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC3));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC4)) {
|
||||
Serial.printf("DC4 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC4) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC4));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC5)) {
|
||||
Serial.printf("DC5 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC5) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC5));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_LDO2)) {
|
||||
Serial.printf("LDO2 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_LDO2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_LDO2));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_LDO3)) {
|
||||
Serial.printf("LDO3 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_LDO3) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_LDO3));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO1)) {
|
||||
Serial.printf("ALDO1: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO1) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO1));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO2)) {
|
||||
Serial.printf("ALDO2: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO2));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO3)) {
|
||||
Serial.printf("ALDO3: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO3) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO3));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO4)) {
|
||||
Serial.printf("ALDO4: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO4) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO4));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_BLDO1)) {
|
||||
Serial.printf("BLDO1: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_BLDO1) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_BLDO1));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_BLDO2)) {
|
||||
Serial.printf("BLDO2: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_BLDO2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_BLDO2));
|
||||
}
|
||||
Serial.printf("=========================================\n");
|
||||
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
@ -0,0 +1,212 @@
|
|||
/**
|
||||
*
|
||||
* @license MIT License
|
||||
*
|
||||
* Copyright (c) 2022 lewis he
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
* @file QMI8658_ReadFromFifoExample.ino
|
||||
* @author Lewis He (lewishe@outlook.com)
|
||||
* @date 2022-10-16
|
||||
*
|
||||
*/
|
||||
#include <Arduino.h>
|
||||
#include <Wire.h>
|
||||
#include <SPI.h>
|
||||
#include "SensorQMI8658.hpp"
|
||||
|
||||
#define USE_WIRE
|
||||
|
||||
#define I2C1_SDA 17
|
||||
#define I2C1_SCL 18
|
||||
|
||||
#define IMU_CS 5
|
||||
|
||||
SensorQMI8658 qmi;
|
||||
|
||||
|
||||
IMUdata acc[128];
|
||||
IMUdata gyr[128];
|
||||
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(115200);
|
||||
while (!Serial);
|
||||
|
||||
|
||||
#ifdef LILYGO_TBEAM_SUPREME_V3_0
|
||||
extern bool setupPower();
|
||||
setupPower();
|
||||
#endif
|
||||
|
||||
#ifdef USE_WIRE
|
||||
//Using WIRE !!
|
||||
if (!qmi.begin(Wire, QMI8658_L_SLAVE_ADDRESS, I2C1_SDA, I2C1_SCL)) {
|
||||
Serial.println("Failed to find QMI8658 - check your wiring!");
|
||||
while (1) {
|
||||
delay(1000);
|
||||
}
|
||||
}
|
||||
#else
|
||||
//Using SPI !!
|
||||
if (!qmi.begin(IMU_CS)) {
|
||||
Serial.println("Failed to find QMI8658 - check your wiring!");
|
||||
while (1) {
|
||||
delay(1000);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
/* Get chip id*/
|
||||
Serial.print("Device ID:");
|
||||
Serial.println(qmi.getChipID(), HEX);
|
||||
|
||||
|
||||
qmi.configAccelerometer(
|
||||
/*
|
||||
* ACC_RANGE_2G
|
||||
* ACC_RANGE_4G
|
||||
* ACC_RANGE_8G
|
||||
* ACC_RANGE_16G
|
||||
* */
|
||||
SensorQMI8658::ACC_RANGE_4G,
|
||||
/*
|
||||
* ACC_ODR_1000H
|
||||
* ACC_ODR_500Hz
|
||||
* ACC_ODR_250Hz
|
||||
* ACC_ODR_125Hz
|
||||
* ACC_ODR_62_5Hz
|
||||
* ACC_ODR_31_25Hz
|
||||
* ACC_ODR_LOWPOWER_128Hz
|
||||
* ACC_ODR_LOWPOWER_21Hz
|
||||
* ACC_ODR_LOWPOWER_11Hz
|
||||
* ACC_ODR_LOWPOWER_3H
|
||||
* */
|
||||
SensorQMI8658::ACC_ODR_1000Hz,
|
||||
/*
|
||||
* LPF_MODE_0 //2.66% of ODR
|
||||
* LPF_MODE_1 //3.63% of ODR
|
||||
* LPF_MODE_2 //5.39% of ODR
|
||||
* LPF_MODE_3 //13.37% of ODR
|
||||
* */
|
||||
SensorQMI8658::LPF_MODE_0,
|
||||
// selfTest enable
|
||||
true);
|
||||
|
||||
|
||||
qmi.configGyroscope(
|
||||
/*
|
||||
* GYR_RANGE_16DPS
|
||||
* GYR_RANGE_32DPS
|
||||
* GYR_RANGE_64DPS
|
||||
* GYR_RANGE_128DPS
|
||||
* GYR_RANGE_256DPS
|
||||
* GYR_RANGE_512DPS
|
||||
* GYR_RANGE_1024DPS
|
||||
* */
|
||||
SensorQMI8658::GYR_RANGE_64DPS,
|
||||
/*
|
||||
* GYR_ODR_7174_4Hz
|
||||
* GYR_ODR_3587_2Hz
|
||||
* GYR_ODR_1793_6Hz
|
||||
* GYR_ODR_896_8Hz
|
||||
* GYR_ODR_448_4Hz
|
||||
* GYR_ODR_224_2Hz
|
||||
* GYR_ODR_112_1Hz
|
||||
* GYR_ODR_56_05Hz
|
||||
* GYR_ODR_28_025H
|
||||
* */
|
||||
SensorQMI8658::GYR_ODR_896_8Hz,
|
||||
/*
|
||||
* LPF_MODE_0 //2.66% of ODR
|
||||
* LPF_MODE_1 //3.63% of ODR
|
||||
* LPF_MODE_2 //5.39% of ODR
|
||||
* LPF_MODE_3 //13.37% of ODR
|
||||
* */
|
||||
SensorQMI8658::LPF_MODE_3,
|
||||
// selfTest enable
|
||||
true);
|
||||
|
||||
qmi.configFIFO(
|
||||
/**
|
||||
* FIFO_MODE_BYPASS -- Disable fifo
|
||||
* FIFO_MODE_FIFO -- Will not overwrite
|
||||
* FIFO_MODE_STREAM -- Cover
|
||||
*/
|
||||
SensorQMI8658::FIFO_MODE_FIFO,
|
||||
/*
|
||||
* FIFO_SAMPLES_16
|
||||
* FIFO_SAMPLES_32
|
||||
* FIFO_SAMPLES_64
|
||||
* FIFO_SAMPLES_128
|
||||
* */
|
||||
SensorQMI8658::FIFO_SAMPLES_16,
|
||||
|
||||
//FiFo mapped interrupt IO port
|
||||
SensorQMI8658::IntPin1,
|
||||
// watermark level
|
||||
8);
|
||||
|
||||
// In 6DOF mode (accelerometer and gyroscope are both enabled),
|
||||
// the output data rate is derived from the nature frequency of gyroscope
|
||||
qmi.enableGyroscope();
|
||||
qmi.enableAccelerometer();
|
||||
|
||||
// Print register configuration information
|
||||
qmi.dumpCtrlRegister();
|
||||
|
||||
Serial.println("Read data now...");
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
||||
void loop()
|
||||
{
|
||||
// If the reading is successful, true will be returned
|
||||
if (!qmi.readFromFifo(acc, 128, gyr, 128)) {
|
||||
return;
|
||||
}
|
||||
|
||||
for (int i = 0; i < 16; ++i) {
|
||||
Serial.print("ACCEL: ");
|
||||
Serial.print("X:");
|
||||
Serial.print(acc[i].x);
|
||||
Serial.print(" Y:");
|
||||
Serial.print(acc[i].y);
|
||||
Serial.print(" Z:");
|
||||
Serial.println(acc[i].z);
|
||||
Serial.print("GYRO: ");
|
||||
Serial.print(" X:");
|
||||
Serial.print(gyr[i].x);
|
||||
Serial.print(" Y:");
|
||||
Serial.print(gyr[i].y );
|
||||
Serial.print(" Z:");
|
||||
Serial.println(gyr[i].z);
|
||||
}
|
||||
|
||||
delay(100);
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
167
lib/SensorsLib/examples/QMI8658_ReadFromFifoExample/power.cpp
Normal file
167
lib/SensorsLib/examples/QMI8658_ReadFromFifoExample/power.cpp
Normal file
|
|
@ -0,0 +1,167 @@
|
|||
/**
|
||||
* @file power.cpp
|
||||
* @author Lewis He (lewishe@outlook.com)
|
||||
* @license MIT
|
||||
* @copyright Copyright (c) 2022
|
||||
* @date 2022-10-25
|
||||
*
|
||||
*/
|
||||
|
||||
|
||||
#ifdef LILYGO_TBEAM_SUPREME_V3_0
|
||||
#include <Wire.h>
|
||||
#include "XPowersAXP2101.tpp"
|
||||
#include "XPowersAXP192.tpp"
|
||||
|
||||
|
||||
|
||||
#define I2C_SDA 42
|
||||
#define I2C_SCL 41
|
||||
#define PMU_IRQ 40
|
||||
|
||||
XPowersLibInterface *PMU = NULL;
|
||||
|
||||
bool setupPower()
|
||||
{
|
||||
Serial.println("setupPower");
|
||||
|
||||
if (!PMU) {
|
||||
PMU = new XPowersAXP2101(Wire1, I2C_SDA, I2C_SCL);
|
||||
if (!PMU->init()) {
|
||||
Serial.println("Warning: Failed to find AXP2101 power management");
|
||||
delete PMU;
|
||||
PMU = NULL;
|
||||
} else {
|
||||
Serial.println("AXP2101 PMU init succeeded, using AXP2101 PMU");
|
||||
}
|
||||
}
|
||||
|
||||
if (!PMU) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (PMU->getChipModel() == XPOWERS_AXP2101) {
|
||||
|
||||
#if defined(LILYGO_TBEAM_V1_2)
|
||||
|
||||
PMU->setProtectedChannel(XPOWERS_DCDC1);
|
||||
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC2);
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC3);
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC4);
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC5);
|
||||
|
||||
// PMU->disablePowerOutput(XPOWERS_ALDO1);
|
||||
// PMU->disablePowerOutput(XPOWERS_ALDO2);
|
||||
// PMU->disablePowerOutput(XPOWERS_ALDO3);
|
||||
PMU->disablePowerOutput(XPOWERS_ALDO4);
|
||||
|
||||
PMU->disablePowerOutput(XPOWERS_BLDO1);
|
||||
PMU->disablePowerOutput(XPOWERS_BLDO2);
|
||||
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO1);
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO2);
|
||||
|
||||
PMU->enablePowerOutput(XPOWERS_VBACKUP);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO1);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO2);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO3);
|
||||
|
||||
PMU->setChargeTargetVoltage(XPOWERS_AXP2101_CHG_VOL_4V4);
|
||||
|
||||
#elif defined(LILYGO_TBEAM_SUPREME_V3_0)
|
||||
|
||||
//t-beam m.2 inface
|
||||
//gps
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO4, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO4);
|
||||
|
||||
// lora
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO3, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO3);
|
||||
|
||||
// Sensor
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO1, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO1);
|
||||
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO2, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO2);
|
||||
|
||||
//Sdcard
|
||||
PMU->setPowerChannelVoltage(XPOWERS_BLDO1, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_BLDO1);
|
||||
|
||||
//face m.2
|
||||
PMU->setPowerChannelVoltage(XPOWERS_DCDC3, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_DCDC3);
|
||||
|
||||
PMU->setPowerChannelVoltage(XPOWERS_DCDC4, XPOWERS_AXP2101_DCDC4_VOL2_MAX);
|
||||
PMU->enablePowerOutput(XPOWERS_DCDC4);
|
||||
|
||||
PMU->setPowerChannelVoltage(XPOWERS_DCDC5, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_DCDC5);
|
||||
|
||||
|
||||
//not use channel
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC2);
|
||||
// PMU->disablePowerOutput(XPOWERS_DCDC4);
|
||||
// PMU->disablePowerOutput(XPOWERS_DCDC5);
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO1);
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO2);
|
||||
PMU->disablePowerOutput(XPOWERS_VBACKUP);
|
||||
|
||||
#endif
|
||||
}
|
||||
|
||||
PMU->enableSystemVoltageMeasure();
|
||||
PMU->enableVbusVoltageMeasure();
|
||||
PMU->enableBattVoltageMeasure();
|
||||
PMU->disableTSPinMeasure();
|
||||
|
||||
Serial.printf("=========================================\n");
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC1)) {
|
||||
Serial.printf("DC1 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC1) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC1));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC2)) {
|
||||
Serial.printf("DC2 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC2));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC3)) {
|
||||
Serial.printf("DC3 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC3) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC3));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC4)) {
|
||||
Serial.printf("DC4 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC4) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC4));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC5)) {
|
||||
Serial.printf("DC5 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC5) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC5));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_LDO2)) {
|
||||
Serial.printf("LDO2 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_LDO2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_LDO2));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_LDO3)) {
|
||||
Serial.printf("LDO3 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_LDO3) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_LDO3));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO1)) {
|
||||
Serial.printf("ALDO1: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO1) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO1));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO2)) {
|
||||
Serial.printf("ALDO2: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO2));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO3)) {
|
||||
Serial.printf("ALDO3: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO3) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO3));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO4)) {
|
||||
Serial.printf("ALDO4: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO4) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO4));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_BLDO1)) {
|
||||
Serial.printf("BLDO1: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_BLDO1) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_BLDO1));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_BLDO2)) {
|
||||
Serial.printf("BLDO2: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_BLDO2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_BLDO2));
|
||||
}
|
||||
Serial.printf("=========================================\n");
|
||||
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
@ -0,0 +1,155 @@
|
|||
/**
|
||||
*
|
||||
* @license MIT License
|
||||
*
|
||||
* Copyright (c) 2022 lewis he
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
* @file QMI8658_WakeOnMotion.ino
|
||||
* @author Lewis He (lewishe@outlook.com)
|
||||
* @date 2022-11-05
|
||||
*
|
||||
*/
|
||||
#include <Arduino.h>
|
||||
#include <Wire.h>
|
||||
#include <SPI.h>
|
||||
#include "SensorQMI8658.hpp"
|
||||
|
||||
// #define USE_WIRE
|
||||
|
||||
#define I2C1_SDA 17
|
||||
#define I2C1_SCL 18
|
||||
|
||||
|
||||
SensorQMI8658 qmi;
|
||||
|
||||
IMUdata acc;
|
||||
IMUdata gyr;
|
||||
|
||||
|
||||
bool interruptFlag = false;
|
||||
|
||||
void setFlag(void)
|
||||
{
|
||||
interruptFlag = true;
|
||||
|
||||
}
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(115200);
|
||||
while (!Serial);
|
||||
|
||||
#ifdef LILYGO_TBEAM_SUPREME_V3_0
|
||||
extern bool setupPower();
|
||||
setupPower();
|
||||
#endif
|
||||
|
||||
#ifdef USE_WIRE
|
||||
//Using WIRE !!
|
||||
if (!qmi.begin(Wire, QMI8658_L_SLAVE_ADDRESS, I2C1_SDA, I2C1_SCL)) {
|
||||
Serial.println("Failed to find QMI8658 - check your wiring!");
|
||||
while (1) {
|
||||
delay(1000);
|
||||
}
|
||||
}
|
||||
#else
|
||||
|
||||
#ifndef CONFIG_IDF_TARGET_ESP32
|
||||
//Use tbeams3 defalut spi pinz
|
||||
#define SPI_MOSI (35)
|
||||
#define SPI_SCK (36)
|
||||
#define SPI_MISO (37)
|
||||
#define SPI_CS (47)
|
||||
#define IMU_CS (34)
|
||||
#define IMU_INT1 (33) //INTERRUPT PIN1 & PIN2 ,Use or logic to form a pin
|
||||
|
||||
SPI.begin(SPI_SCK, SPI_MISO, SPI_MOSI);
|
||||
pinMode(SPI_CS, OUTPUT); //sdcard pin set high
|
||||
digitalWrite(SPI_CS, HIGH);
|
||||
if (!qmi.begin(IMU_CS, SPI_MOSI, SPI_MISO, SPI_SCK)) {
|
||||
|
||||
#else
|
||||
//Use esp32dev module defalut spi pin
|
||||
#define IMU_CS (5)
|
||||
#define IMU_INT1 (15)
|
||||
#define IMU_INT2 (22)
|
||||
if (!qmi.begin(IMU_CS)) {
|
||||
#endif
|
||||
Serial.println("Failed to find QMI8658 - check your wiring!");
|
||||
while (1) {
|
||||
delay(1000);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
/* Get chip id*/
|
||||
Serial.print("Device ID:");
|
||||
Serial.println(qmi.getChipID(), HEX);
|
||||
|
||||
// enabling wake on motion low power mode with a threshold of 120 mg and
|
||||
// an accelerometer data rate of 128 Hz.
|
||||
qmi.configWakeOnMotion();
|
||||
|
||||
/*
|
||||
* When the QMI8658 is configured as Wom, the interrupt level is arbitrary,
|
||||
* not absolute high or low, and it is in the jump transition state
|
||||
*/
|
||||
pinMode(IMU_INT1, INPUT_PULLUP);
|
||||
#ifdef IMU_INT2
|
||||
pinMode(IMU_INT2, INPUT_PULLUP);
|
||||
attachInterrupt(IMU_INT2, setFlag, CHANGE);
|
||||
#else
|
||||
attachInterrupt(IMU_INT1, setFlag, CHANGE);
|
||||
#endif
|
||||
|
||||
|
||||
// Print register configuration information
|
||||
qmi.dumpCtrlRegister();
|
||||
}
|
||||
|
||||
|
||||
void loop()
|
||||
{
|
||||
|
||||
if (interruptFlag) {
|
||||
interruptFlag = false;
|
||||
uint8_t status = qmi.getStatusRegister();
|
||||
Serial.printf("status:0x%X BIN:", status);
|
||||
Serial.println(status, BIN);
|
||||
|
||||
if (status & SensorQMI8658::EVENT_SIGNIFICANT_MOTION) {
|
||||
Serial.println("EVENT_SIGNIFICANT_MOTION");
|
||||
} else if (status & SensorQMI8658::EVENT_NO_MOTION) {
|
||||
Serial.println("EVENT_NO_MOITON");
|
||||
} else if (status & SensorQMI8658::EVENT_ANY_MOTION) {
|
||||
Serial.println("EVENT_ANY_MOTION");
|
||||
} else if (status & SensorQMI8658::EVENT_PEDOMETER_MOTION) {
|
||||
Serial.println("EVENT_PEDOMETER_MOTION");
|
||||
} else if (status & SensorQMI8658::EVENT_WOM_MOTION) {
|
||||
Serial.println("EVENT_WOM_MOTION");
|
||||
} else if (status & SensorQMI8658::EVENT_TAP_MOTION) {
|
||||
Serial.println("EVENT_TAP_MOTION");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
167
lib/SensorsLib/examples/QMI8658_WakeOnMotion/power.cpp
Normal file
167
lib/SensorsLib/examples/QMI8658_WakeOnMotion/power.cpp
Normal file
|
|
@ -0,0 +1,167 @@
|
|||
/**
|
||||
* @file power.cpp
|
||||
* @author Lewis He (lewishe@outlook.com)
|
||||
* @license MIT
|
||||
* @copyright Copyright (c) 2022
|
||||
* @date 2022-10-25
|
||||
*
|
||||
*/
|
||||
|
||||
|
||||
#ifdef LILYGO_TBEAM_SUPREME_V3_0
|
||||
#include <Wire.h>
|
||||
#include "XPowersAXP2101.tpp"
|
||||
#include "XPowersAXP192.tpp"
|
||||
|
||||
|
||||
|
||||
#define I2C_SDA 42
|
||||
#define I2C_SCL 41
|
||||
#define PMU_IRQ 40
|
||||
|
||||
XPowersLibInterface *PMU = NULL;
|
||||
|
||||
bool setupPower()
|
||||
{
|
||||
Serial.println("setupPower");
|
||||
|
||||
if (!PMU) {
|
||||
PMU = new XPowersAXP2101(Wire1, I2C_SDA, I2C_SCL);
|
||||
if (!PMU->init()) {
|
||||
Serial.println("Warning: Failed to find AXP2101 power management");
|
||||
delete PMU;
|
||||
PMU = NULL;
|
||||
} else {
|
||||
Serial.println("AXP2101 PMU init succeeded, using AXP2101 PMU");
|
||||
}
|
||||
}
|
||||
|
||||
if (!PMU) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (PMU->getChipModel() == XPOWERS_AXP2101) {
|
||||
|
||||
#if defined(LILYGO_TBEAM_V1_2)
|
||||
|
||||
PMU->setProtectedChannel(XPOWERS_DCDC1);
|
||||
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC2);
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC3);
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC4);
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC5);
|
||||
|
||||
// PMU->disablePowerOutput(XPOWERS_ALDO1);
|
||||
// PMU->disablePowerOutput(XPOWERS_ALDO2);
|
||||
// PMU->disablePowerOutput(XPOWERS_ALDO3);
|
||||
PMU->disablePowerOutput(XPOWERS_ALDO4);
|
||||
|
||||
PMU->disablePowerOutput(XPOWERS_BLDO1);
|
||||
PMU->disablePowerOutput(XPOWERS_BLDO2);
|
||||
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO1);
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO2);
|
||||
|
||||
PMU->enablePowerOutput(XPOWERS_VBACKUP);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO1);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO2);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO3);
|
||||
|
||||
PMU->setChargeTargetVoltage(XPOWERS_AXP2101_CHG_VOL_4V4);
|
||||
|
||||
#elif defined(LILYGO_TBEAM_SUPREME_V3_0)
|
||||
|
||||
//t-beam m.2 inface
|
||||
//gps
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO4, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO4);
|
||||
|
||||
// lora
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO3, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO3);
|
||||
|
||||
// Sensor
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO1, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO1);
|
||||
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO2, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO2);
|
||||
|
||||
//Sdcard
|
||||
PMU->setPowerChannelVoltage(XPOWERS_BLDO1, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_BLDO1);
|
||||
|
||||
//face m.2
|
||||
PMU->setPowerChannelVoltage(XPOWERS_DCDC3, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_DCDC3);
|
||||
|
||||
PMU->setPowerChannelVoltage(XPOWERS_DCDC4, XPOWERS_AXP2101_DCDC4_VOL2_MAX);
|
||||
PMU->enablePowerOutput(XPOWERS_DCDC4);
|
||||
|
||||
PMU->setPowerChannelVoltage(XPOWERS_DCDC5, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_DCDC5);
|
||||
|
||||
|
||||
//not use channel
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC2);
|
||||
// PMU->disablePowerOutput(XPOWERS_DCDC4);
|
||||
// PMU->disablePowerOutput(XPOWERS_DCDC5);
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO1);
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO2);
|
||||
PMU->disablePowerOutput(XPOWERS_VBACKUP);
|
||||
|
||||
#endif
|
||||
}
|
||||
|
||||
PMU->enableSystemVoltageMeasure();
|
||||
PMU->enableVbusVoltageMeasure();
|
||||
PMU->enableBattVoltageMeasure();
|
||||
PMU->disableTSPinMeasure();
|
||||
|
||||
Serial.printf("=========================================\n");
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC1)) {
|
||||
Serial.printf("DC1 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC1) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC1));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC2)) {
|
||||
Serial.printf("DC2 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC2));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC3)) {
|
||||
Serial.printf("DC3 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC3) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC3));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC4)) {
|
||||
Serial.printf("DC4 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC4) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC4));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC5)) {
|
||||
Serial.printf("DC5 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC5) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC5));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_LDO2)) {
|
||||
Serial.printf("LDO2 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_LDO2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_LDO2));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_LDO3)) {
|
||||
Serial.printf("LDO3 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_LDO3) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_LDO3));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO1)) {
|
||||
Serial.printf("ALDO1: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO1) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO1));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO2)) {
|
||||
Serial.printf("ALDO2: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO2));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO3)) {
|
||||
Serial.printf("ALDO3: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO3) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO3));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO4)) {
|
||||
Serial.printf("ALDO4: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO4) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO4));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_BLDO1)) {
|
||||
Serial.printf("BLDO1: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_BLDO1) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_BLDO1));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_BLDO2)) {
|
||||
Serial.printf("BLDO2: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_BLDO2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_BLDO2));
|
||||
}
|
||||
Serial.printf("=========================================\n");
|
||||
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
@ -0,0 +1,147 @@
|
|||
/**
|
||||
*
|
||||
* @license MIT License
|
||||
*
|
||||
* Copyright (c) 2022 lewis he
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
* @file QMI8658_WakeOnMotionCallBack.ino
|
||||
* @author Lewis He (lewishe@outlook.com)
|
||||
* @date 2022-11-07
|
||||
*
|
||||
*/
|
||||
#include <Arduino.h>
|
||||
#include <Wire.h>
|
||||
#include <SPI.h>
|
||||
#include "SensorQMI8658.hpp"
|
||||
|
||||
// #define USE_WIRE
|
||||
|
||||
#define I2C1_SDA 17
|
||||
#define I2C1_SCL 18
|
||||
|
||||
|
||||
SensorQMI8658 qmi;
|
||||
|
||||
IMUdata acc;
|
||||
IMUdata gyr;
|
||||
|
||||
|
||||
bool interruptFlag = false;
|
||||
|
||||
void setFlag(void)
|
||||
{
|
||||
interruptFlag = true;
|
||||
}
|
||||
|
||||
void wakeUp()
|
||||
{
|
||||
Serial.println("Awake!");
|
||||
}
|
||||
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(115200);
|
||||
while (!Serial);
|
||||
|
||||
#ifdef LILYGO_TBEAM_SUPREME_V3_0
|
||||
extern bool setupPower();
|
||||
setupPower();
|
||||
#endif
|
||||
|
||||
#ifdef USE_WIRE
|
||||
//Using WIRE !!
|
||||
if (!qmi.begin(Wire, QMI8658_L_SLAVE_ADDRESS, I2C1_SDA, I2C1_SCL)) {
|
||||
Serial.println("Failed to find QMI8658 - check your wiring!");
|
||||
while (1) {
|
||||
delay(1000);
|
||||
}
|
||||
}
|
||||
#else
|
||||
|
||||
#ifndef CONFIG_IDF_TARGET_ESP32
|
||||
//Use tbeams3 defalut spi pinz
|
||||
#define SPI_MOSI (35)
|
||||
#define SPI_SCK (36)
|
||||
#define SPI_MISO (37)
|
||||
#define SPI_CS (47)
|
||||
#define IMU_CS (34)
|
||||
#define IMU_INT1 (33) //INTERRUPT PIN1 & PIN2 ,Use or logic to form a pin
|
||||
|
||||
SPI.begin(SPI_SCK, SPI_MISO, SPI_MOSI);
|
||||
pinMode(SPI_CS, OUTPUT); //sdcard pin set high
|
||||
digitalWrite(SPI_CS, HIGH);
|
||||
if (!qmi.begin(IMU_CS, SPI_MOSI, SPI_MISO, SPI_SCK)) {
|
||||
|
||||
#else
|
||||
//Use esp32dev module defalut spi pin
|
||||
#define IMU_CS (5)
|
||||
#define IMU_INT1 (15)
|
||||
#define IMU_INT2 (22)
|
||||
if (!qmi.begin(IMU_CS)) {
|
||||
#endif
|
||||
Serial.println("Failed to find QMI8658 - check your wiring!");
|
||||
while (1) {
|
||||
delay(1000);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
/* Get chip id*/
|
||||
Serial.print("Device ID:");
|
||||
Serial.println(qmi.getChipID(), HEX);
|
||||
|
||||
// enabling wake on motion low power mode with a threshold of 200 mg and
|
||||
// an accelerometer data rate of 128 Hz.
|
||||
qmi.configWakeOnMotion();
|
||||
|
||||
|
||||
qmi.setWakeupMotionEventCallBack(wakeUp);
|
||||
|
||||
/*
|
||||
* When the QMI8658 is configured as Wom, the interrupt level is arbitrary,
|
||||
* not absolute high or low, and it is in the jump transition state
|
||||
*/
|
||||
pinMode(IMU_INT1, INPUT_PULLUP);
|
||||
#ifdef IMU_INT2
|
||||
pinMode(IMU_INT2, INPUT_PULLUP);
|
||||
attachInterrupt(IMU_INT2, setFlag, CHANGE);
|
||||
#else
|
||||
attachInterrupt(IMU_INT1, setFlag, CHANGE);
|
||||
#endif
|
||||
|
||||
|
||||
// Print register configuration information
|
||||
qmi.dumpCtrlRegister();
|
||||
}
|
||||
|
||||
|
||||
void loop()
|
||||
{
|
||||
|
||||
if (interruptFlag) {
|
||||
interruptFlag = false;
|
||||
qmi.readSensorStatus();
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
|
@ -0,0 +1,167 @@
|
|||
/**
|
||||
* @file power.cpp
|
||||
* @author Lewis He (lewishe@outlook.com)
|
||||
* @license MIT
|
||||
* @copyright Copyright (c) 2022
|
||||
* @date 2022-10-25
|
||||
*
|
||||
*/
|
||||
|
||||
|
||||
#ifdef LILYGO_TBEAM_SUPREME_V3_0
|
||||
#include <Wire.h>
|
||||
#include "XPowersAXP2101.tpp"
|
||||
#include "XPowersAXP192.tpp"
|
||||
|
||||
|
||||
|
||||
#define I2C_SDA 42
|
||||
#define I2C_SCL 41
|
||||
#define PMU_IRQ 40
|
||||
|
||||
XPowersLibInterface *PMU = NULL;
|
||||
|
||||
bool setupPower()
|
||||
{
|
||||
Serial.println("setupPower");
|
||||
|
||||
if (!PMU) {
|
||||
PMU = new XPowersAXP2101(Wire1, I2C_SDA, I2C_SCL);
|
||||
if (!PMU->init()) {
|
||||
Serial.println("Warning: Failed to find AXP2101 power management");
|
||||
delete PMU;
|
||||
PMU = NULL;
|
||||
} else {
|
||||
Serial.println("AXP2101 PMU init succeeded, using AXP2101 PMU");
|
||||
}
|
||||
}
|
||||
|
||||
if (!PMU) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (PMU->getChipModel() == XPOWERS_AXP2101) {
|
||||
|
||||
#if defined(LILYGO_TBEAM_V1_2)
|
||||
|
||||
PMU->setProtectedChannel(XPOWERS_DCDC1);
|
||||
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC2);
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC3);
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC4);
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC5);
|
||||
|
||||
// PMU->disablePowerOutput(XPOWERS_ALDO1);
|
||||
// PMU->disablePowerOutput(XPOWERS_ALDO2);
|
||||
// PMU->disablePowerOutput(XPOWERS_ALDO3);
|
||||
PMU->disablePowerOutput(XPOWERS_ALDO4);
|
||||
|
||||
PMU->disablePowerOutput(XPOWERS_BLDO1);
|
||||
PMU->disablePowerOutput(XPOWERS_BLDO2);
|
||||
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO1);
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO2);
|
||||
|
||||
PMU->enablePowerOutput(XPOWERS_VBACKUP);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO1);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO2);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO3);
|
||||
|
||||
PMU->setChargeTargetVoltage(XPOWERS_AXP2101_CHG_VOL_4V4);
|
||||
|
||||
#elif defined(LILYGO_TBEAM_SUPREME_V3_0)
|
||||
|
||||
//t-beam m.2 inface
|
||||
//gps
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO4, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO4);
|
||||
|
||||
// lora
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO3, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO3);
|
||||
|
||||
// Sensor
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO1, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO1);
|
||||
|
||||
PMU->setPowerChannelVoltage(XPOWERS_ALDO2, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_ALDO2);
|
||||
|
||||
//Sdcard
|
||||
PMU->setPowerChannelVoltage(XPOWERS_BLDO1, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_BLDO1);
|
||||
|
||||
//face m.2
|
||||
PMU->setPowerChannelVoltage(XPOWERS_DCDC3, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_DCDC3);
|
||||
|
||||
PMU->setPowerChannelVoltage(XPOWERS_DCDC4, XPOWERS_AXP2101_DCDC4_VOL2_MAX);
|
||||
PMU->enablePowerOutput(XPOWERS_DCDC4);
|
||||
|
||||
PMU->setPowerChannelVoltage(XPOWERS_DCDC5, 3300);
|
||||
PMU->enablePowerOutput(XPOWERS_DCDC5);
|
||||
|
||||
|
||||
//not use channel
|
||||
PMU->disablePowerOutput(XPOWERS_DCDC2);
|
||||
// PMU->disablePowerOutput(XPOWERS_DCDC4);
|
||||
// PMU->disablePowerOutput(XPOWERS_DCDC5);
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO1);
|
||||
PMU->disablePowerOutput(XPOWERS_DLDO2);
|
||||
PMU->disablePowerOutput(XPOWERS_VBACKUP);
|
||||
|
||||
#endif
|
||||
}
|
||||
|
||||
PMU->enableSystemVoltageMeasure();
|
||||
PMU->enableVbusVoltageMeasure();
|
||||
PMU->enableBattVoltageMeasure();
|
||||
PMU->disableTSPinMeasure();
|
||||
|
||||
Serial.printf("=========================================\n");
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC1)) {
|
||||
Serial.printf("DC1 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC1) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC1));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC2)) {
|
||||
Serial.printf("DC2 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC2));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC3)) {
|
||||
Serial.printf("DC3 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC3) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC3));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC4)) {
|
||||
Serial.printf("DC4 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC4) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC4));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_DCDC5)) {
|
||||
Serial.printf("DC5 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_DCDC5) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_DCDC5));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_LDO2)) {
|
||||
Serial.printf("LDO2 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_LDO2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_LDO2));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_LDO3)) {
|
||||
Serial.printf("LDO3 : %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_LDO3) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_LDO3));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO1)) {
|
||||
Serial.printf("ALDO1: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO1) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO1));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO2)) {
|
||||
Serial.printf("ALDO2: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO2));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO3)) {
|
||||
Serial.printf("ALDO3: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO3) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO3));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_ALDO4)) {
|
||||
Serial.printf("ALDO4: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_ALDO4) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_ALDO4));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_BLDO1)) {
|
||||
Serial.printf("BLDO1: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_BLDO1) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_BLDO1));
|
||||
}
|
||||
if (PMU->isChannelAvailable(XPOWERS_BLDO2)) {
|
||||
Serial.printf("BLDO2: %s Voltage: %04u mV \n", PMU->isPowerChannelEnable(XPOWERS_BLDO2) ? "+" : "-", PMU->getPowerChannelVoltage(XPOWERS_BLDO2));
|
||||
}
|
||||
Serial.printf("=========================================\n");
|
||||
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
#endif
|
||||
18
lib/SensorsLib/keywords.txt
Normal file
18
lib/SensorsLib/keywords.txt
Normal file
|
|
@ -0,0 +1,18 @@
|
|||
#######################################
|
||||
# Syntax Coloring Map For SensorLib By lewis He
|
||||
# github:https://github.com/lewisxhe
|
||||
#######################################
|
||||
|
||||
#######################################
|
||||
# Datatypes (KEYWORD1)
|
||||
#######################################
|
||||
|
||||
#######################################
|
||||
# Methods and Functions (KEYWORD2)
|
||||
#######################################
|
||||
|
||||
#######################################
|
||||
# Constants (LITERAL1)
|
||||
#######################################
|
||||
|
||||
|
||||
29
lib/SensorsLib/library.json
Normal file
29
lib/SensorsLib/library.json
Normal file
|
|
@ -0,0 +1,29 @@
|
|||
{
|
||||
"name": "SensorLib",
|
||||
"version": "0.1.0",
|
||||
"description": "Arduino library for QMI8658 Inertial measurement,QMC6310 Magnetometer",
|
||||
"keywords": "QMC6310 QMI8658 IMU Sensor",
|
||||
"authors": [{
|
||||
"name": "LewisHe",
|
||||
"url": "https://github.com/lewisxhe",
|
||||
"maintainer": true
|
||||
}],
|
||||
"repository": {
|
||||
"type": "git",
|
||||
"url": "https://github.com/lewisxhe/SensorsLib.git"
|
||||
},
|
||||
"homepage": "https://github.com/lewisxhe/SensorsLib",
|
||||
"export": {
|
||||
"include": [
|
||||
"LICENSE",
|
||||
"library.json",
|
||||
"library.properties",
|
||||
"README.md",
|
||||
"keywords.txt",
|
||||
"src/*",
|
||||
"examples/*"
|
||||
]
|
||||
},
|
||||
"frameworks": ["arduino"],
|
||||
"platforms": "esp32"
|
||||
}
|
||||
9
lib/SensorsLib/library.properties
Normal file
9
lib/SensorsLib/library.properties
Normal file
|
|
@ -0,0 +1,9 @@
|
|||
name=SensorLib
|
||||
version=0.1.0
|
||||
author=Lewis He
|
||||
maintainer=Lewis He <lewishe@outlook.com>
|
||||
sentence=Arduino library for QMI8658 Inertial measurement,QMC6310 Magnetometer
|
||||
paragraph=Arduino library for QMI8658 Inertial measurement,QMC6310 Magnetometer
|
||||
category=Communication
|
||||
url=https://github.com/lewisxhe/SensorsLib
|
||||
architectures=esp32
|
||||
115
lib/SensorsLib/src/REG/MPU6886Constants.h
Normal file
115
lib/SensorsLib/src/REG/MPU6886Constants.h
Normal file
|
|
@ -0,0 +1,115 @@
|
|||
/**
|
||||
*
|
||||
* @license MIT License
|
||||
*
|
||||
* Copyright (c) 2022 lewis he
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
* @file MPU6886Constants.h
|
||||
* @author Lewis He (lewishe@outlook.com)
|
||||
* @date 2022-10-16
|
||||
*
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
|
||||
#define MPU6886_SLAVE_ADDRESS (0x68)
|
||||
|
||||
#define MPU6886_REG_XG_OFFS_TC_H (0x04)
|
||||
#define MPU6886_REG_XG_OFFS_TC_L (0x05)
|
||||
#define MPU6886_REG_YG_OFFS_TC_H (0x07)
|
||||
#define MPU6886_REG_YG_OFFS_TC_L (0x08)
|
||||
#define MPU6886_REG_ZG_OFFS_TC_H (0x0A)
|
||||
#define MPU6886_REG_ZG_OFFS_TC_L (0x0B)
|
||||
#define MPU6886_REG_SELF_TEST_X_ACCEL (0x0D)
|
||||
#define MPU6886_REG_SELF_TEST_Y_ACCEL (0x0E)
|
||||
#define MPU6886_REG_SELF_TEST_Z_ACCEL (0x0F)
|
||||
#define MPU6886_REG_XG_OFFS_USRH (0x13)
|
||||
#define MPU6886_REG_XG_OFFS_USRL (0x14)
|
||||
#define MPU6886_REG_YG_OFFS_USRH (0x15)
|
||||
#define MPU6886_REG_YG_OFFS_USRL (0x16)
|
||||
#define MPU6886_REG_ZG_OFFS_USRH (0x17)
|
||||
#define MPU6886_REG_ZG_OFFS_USRL (0x18)
|
||||
#define MPU6886_REG_SMPLRT_DIV (0x19)
|
||||
#define MPU6886_REG_CONFIG (0x1A)
|
||||
#define MPU6886_REG_GYRO_CONFIG (0x1B)
|
||||
#define MPU6886_REG_ACCEL_CONFIG (0x1C)
|
||||
#define MPU6886_REG_ACCEL_CONFIG_2 (0x1D)
|
||||
#define MPU6886_REG_LP_MODE_CFG (0x1E)
|
||||
#define MPU6886_REG_ACCEL_WOM_X_THR (0x20)
|
||||
#define MPU6886_REG_ACCEL_WOM_Y_THR (0x21)
|
||||
#define MPU6886_REG_ACCEL_WOM_Z_THR (0x22)
|
||||
#define MPU6886_REG_FIFO_EN (0x23)
|
||||
#define MPU6886_REG_FSYNC_INT (0x36)
|
||||
#define MPU6886_REG_INT_PIN_CFG (0x37)
|
||||
#define MPU6886_REG_INT_ENABLE (0x38)
|
||||
#define MPU6886_REG_FIFO_WM_INT_STATUS (0x39)
|
||||
#define MPU6886_REG_INT_STATUS (0x3A)
|
||||
#define MPU6886_REG_ACCEL_XOUT_H (0x3B)
|
||||
#define MPU6886_REG_ACCEL_XOUT_L (0x3C)
|
||||
#define MPU6886_REG_ACCEL_YOUT_H (0x3D)
|
||||
#define MPU6886_REG_ACCEL_YOUT_L (0x3E)
|
||||
#define MPU6886_REG_ACCEL_ZOUT_H (0x3F)
|
||||
#define MPU6886_REG_ACCEL_ZOUT_L (0x40)
|
||||
#define MPU6886_REG_TEMP_OUT_H (0x41)
|
||||
#define MPU6886_REG_TEMP_OUT_L (0x42)
|
||||
#define MPU6886_REG_GYRO_XOUT_H (0x43)
|
||||
#define MPU6886_REG_GYRO_XOUT_L (0x44)
|
||||
#define MPU6886_REG_GYRO_YOUT_H (0x45)
|
||||
#define MPU6886_REG_GYRO_YOUT_L (0x46)
|
||||
#define MPU6886_REG_GYRO_ZOUT_H (0x47)
|
||||
#define MPU6886_REG_GYRO_ZOUT_L (0x48)
|
||||
#define MPU6886_REG_SELF_TEST_X_GYRO (0x50)
|
||||
#define MPU6886_REG_SELF_TEST_Y_GYRO (0x51)
|
||||
#define MPU6886_REG_SELF_TEST_Z_GYRO (0x52)
|
||||
#define MPU6886_REG_E_ID0 (0x53)
|
||||
#define MPU6886_REG_E_ID1 (0x54)
|
||||
#define MPU6886_REG_E_ID2 (0x55)
|
||||
#define MPU6886_REG_E_ID3 (0x56)
|
||||
#define MPU6886_REG_E_ID4 (0x57)
|
||||
#define MPU6886_REG_E_ID5 (0x58)
|
||||
#define MPU6886_REG_E_ID6 (0x59)
|
||||
#define MPU6886_REG_FIFO_WM_TH1 (0x60)
|
||||
#define MPU6886_REG_FIFO_WM_TH2 (0x61)
|
||||
#define MPU6886_REG_SIGNAL_PATH_RESET (0x68)
|
||||
#define MPU6886_REG_ACCEL_INTEL_CTRL (0x69)
|
||||
#define MPU6886_REG_USER_CTRL (0x6A)
|
||||
#define MPU6886_REG_PWR_MGMT_1 (0x6B)
|
||||
#define MPU6886_REG_PWR_MGMT_2 (0x6C)
|
||||
#define MPU6886_REG_I2C_IF (0x70)
|
||||
#define MPU6886_REG_FIFO_COUNTH (0x72)
|
||||
#define MPU6886_REG_FIFO_COUNTL (0x73)
|
||||
#define MPU6886_REG_FIFO_R_W (0x74)
|
||||
#define MPU6886_REG_WHO_AM_I (0x75)
|
||||
#define MPU6886_REG_XA_OFFSET_H (0x77)
|
||||
#define MPU6886_REG_XA_OFFSET_L (0x78)
|
||||
#define MPU6886_REG_YA_OFFSET_H (0x7A)
|
||||
#define MPU6886_REG_YA_OFFSET_L (0x7B)
|
||||
#define MPU6886_REG_ZA_OFFSET_H (0x7D)
|
||||
#define MPU6886_REG_ZA_OFFSET_L (0x7E)
|
||||
|
||||
|
||||
#define MPU6886_WHO_AM_I_RES (0x19)
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
53
lib/SensorsLib/src/REG/QMC6310Constants.h
Normal file
53
lib/SensorsLib/src/REG/QMC6310Constants.h
Normal file
|
|
@ -0,0 +1,53 @@
|
|||
/**
|
||||
*
|
||||
* @license MIT License
|
||||
*
|
||||
* Copyright (c) 2022 lewis he
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
* @file QMC6310Constants.h
|
||||
* @author Lewis He (lewishe@outlook.com)
|
||||
* @date 2022-10-16
|
||||
*
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
// @brief device address
|
||||
#define QMC6310_SLAVE_ADDRESS (0x1C)
|
||||
#define QMC6310_DEFAULT_ID (0x80)
|
||||
|
||||
|
||||
#define QMC6310_REG_CHIP_ID (0x00)
|
||||
#define QMC6310_REG_LSB_DX (0X01)
|
||||
#define QMC6310_REG_MSB_DX (0X02)
|
||||
#define QMC6310_REG_LSB_DY (0X03)
|
||||
#define QMC6310_REG_MSB_DY (0X04)
|
||||
#define QMC6310_REG_LSB_DZ (0X05)
|
||||
#define QMC6310_REG_MSB_DZ (0X06)
|
||||
#define QMC6310_REG_STAT (0X09)
|
||||
#define QMC6310_REG_CMD1 (0x0A)
|
||||
#define QMC6310_REG_CMD2 (0x0B)
|
||||
|
||||
|
||||
#define QMC6310_REG_SIGN (0x29)
|
||||
|
||||
|
||||
|
||||
133
lib/SensorsLib/src/REG/QMI8658Constants.h
Normal file
133
lib/SensorsLib/src/REG/QMI8658Constants.h
Normal file
|
|
@ -0,0 +1,133 @@
|
|||
/**
|
||||
*
|
||||
* @license MIT License
|
||||
*
|
||||
* Copyright (c) 2022 lewis he
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
* @file QMI8658Constants.h
|
||||
* @author Lewis He (lewishe@outlook.com)
|
||||
* @date 2022-10-16
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
// @brief device address
|
||||
#define QMI8658_L_SLAVE_ADDRESS (0x6B)
|
||||
#define QMI8658_H_SLAVE_ADDRESS (0x6A)
|
||||
|
||||
|
||||
// @brief registers default value
|
||||
#define QMI8658_REG_WHOAMI_DEFAULT (0x05)
|
||||
#define QMI8658_REG_STATUS_DEFAULT (0x03)
|
||||
#define QMI8658_REG_RESET_DEFAULT (0xB0)
|
||||
|
||||
|
||||
// @brief registers list
|
||||
#define QMI8658_REG_WHOAMI (0x00)
|
||||
#define QMI8658_REG_REVISION (0x01)
|
||||
#define QMI8658_REG_CTRL1 (0x02)
|
||||
#define QMI8658_REG_CTRL2 (0x03)
|
||||
#define QMI8658_REG_CTRL3 (0x04)
|
||||
// #define QMI8658_REG_CTRL4 (0x05)
|
||||
#define QMI8658_REG_CTRL5 (0x06)
|
||||
// #define QMI8658_REG_CTRL6 (0x07)
|
||||
#define QMI8658_REG_CTRL7 (0x08)
|
||||
#define QMI8658_REG_CTRL8 (0x09)
|
||||
#define QMI8658_REG_CTRL9 (0x0A)
|
||||
|
||||
#define QMI8658_REG_CAL1_L (0x0B)
|
||||
#define QMI8658_REG_CAL1_H (0x0C)
|
||||
#define QMI8658_REG_CAL2_L (0x0D)
|
||||
#define QMI8658_REG_CAL2_H (0x0E)
|
||||
#define QMI8658_REG_CAL3_L (0x0F)
|
||||
#define QMI8658_REG_CAL3_H (0x10)
|
||||
#define QMI8658_REG_CAL4_L (0x11)
|
||||
#define QMI8658_REG_CAL4_H (0x12)
|
||||
|
||||
#define QMI8658_REG_FIFOWMKTH (0x13)
|
||||
#define QMI8658_REG_FIFOCTRL (0x14)
|
||||
#define QMI8658_REG_FIFOCOUNT (0x15)
|
||||
#define QMI8658_REG_FIFOSTATUS (0x16)
|
||||
#define QMI8658_REG_FIFODATA (0x17)
|
||||
// #define QMI8658_REG_STATUSI2CM (0x2C)
|
||||
#define QMI8658_REG_STATUSINT (0x2D)
|
||||
#define QMI8658_REG_STATUS0 (0x2E)
|
||||
#define QMI8658_REG_STATUS1 (0x2F)
|
||||
#define QMI8658_REG_TIMESTAMP_L (0x30)
|
||||
#define QMI8658_REG_TIMESTAMP_M (0x31)
|
||||
#define QMI8658_REG_TIMESTAMP_H (0x32)
|
||||
#define QMI8658_REG_TEMPEARTURE_L (0x33)
|
||||
#define QMI8658_REG_TEMPEARTURE_H (0x34)
|
||||
#define QMI8658_REG_AX_L (0x35)
|
||||
#define QMI8658_REG_AX_H (0x36)
|
||||
#define QMI8658_REG_AY_L (0x37)
|
||||
#define QMI8658_REG_AY_H (0x38)
|
||||
#define QMI8658_REG_AZ_L (0x39)
|
||||
#define QMI8658_REG_AZ_H (0x3A)
|
||||
#define QMI8658_REG_GX_L (0x3B)
|
||||
#define QMI8658_REG_GX_H (0x3C)
|
||||
#define QMI8658_REG_GY_L (0x3D)
|
||||
#define QMI8658_REG_GY_H (0x3E)
|
||||
#define QMI8658_REG_GZ_L (0x3F)
|
||||
#define QMI8658_REG_GZ_H (0x40)
|
||||
|
||||
#define QMI8658_REG_COD_STATUS (0x46)
|
||||
|
||||
#define QMI8658_REG_DQW_L (0x49)
|
||||
#define QMI8658_REG_DQW_H (0x4A)
|
||||
#define QMI8658_REG_DQX_L (0x4B)
|
||||
#define QMI8658_REG_DQX_H (0x4C)
|
||||
#define QMI8658_REG_DQY_L (0x4D)
|
||||
#define QMI8658_REG_DQY_H (0x4E)
|
||||
#define QMI8658_REG_DQZ_L (0x4F)
|
||||
#define QMI8658_REG_DQZ_H (0x50)
|
||||
|
||||
#define QMI8658_REG_DVX_L (0x51)
|
||||
#define QMI8658_REG_DVX_H (0x52)
|
||||
#define QMI8658_REG_DVY_L (0x53)
|
||||
#define QMI8658_REG_DVY_H (0x54)
|
||||
#define QMI8658_REG_DVZ_L (0x55)
|
||||
#define QMI8658_REG_DVZ_H (0x56)
|
||||
|
||||
#define QMI8658_REG_TAP_STATUS (0x59)
|
||||
#define QMI8658_REG_PEDO_L (0x5A)
|
||||
#define QMI8658_REG_PEDO_M (0x5B)
|
||||
#define QMI8658_REG_PEDO_H (0x5C)
|
||||
#define QMI8658_REG_RESET (0x60)
|
||||
|
||||
#define QMI8658_REG_RST_RESULT (0x4D)
|
||||
#define QMI8658_REG_RST_RESULT_VAL (0x80)
|
||||
|
||||
#define STATUS0_ACCE_AVAIL (0x01)
|
||||
#define STATUS0_GYRO_AVAIL (0x02)
|
||||
#define QMI8658_ACCEL_LPF_MASK (0xF9)
|
||||
#define QMI8658_GYRO_LPF_MASK (0x9F)
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
#define QMI8658_ACCEL_EN_MASK (0x01)
|
||||
#define QMI8658_GYRO_EN_MASK (0x02)
|
||||
#define QMI8658_ACCEL_GYRO_EN_MASK (0x03)
|
||||
|
||||
|
||||
#define QMI8658_FIFO_MAP_INT1 0x04 // ctrl1
|
||||
390
lib/SensorsLib/src/SensorCommon.tpp
Normal file
390
lib/SensorsLib/src/SensorCommon.tpp
Normal file
|
|
@ -0,0 +1,390 @@
|
|||
/**
|
||||
*
|
||||
* @license MIT License
|
||||
*
|
||||
* Copyright (c) 2022 lewis he
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
* @file SensorCommon.tpp
|
||||
* @author Lewis He (lewishe@outlook.com)
|
||||
* @date 2022-10-16
|
||||
*
|
||||
*/
|
||||
|
||||
|
||||
#pragma once
|
||||
|
||||
#if defined(ARDUINO)
|
||||
#include <Arduino.h>
|
||||
#include <Wire.h>
|
||||
#include <SPI.h>
|
||||
#endif
|
||||
|
||||
|
||||
#define DEV_WIRE_NONE (0)
|
||||
#define DEV_WIRE_ERR (-1)
|
||||
#define DEV_WIRE_TIMEOUT (-2)
|
||||
|
||||
#ifdef _BV
|
||||
#undef _BV
|
||||
#endif
|
||||
#define _BV(b) (1UL << (uint32_t)(b))
|
||||
|
||||
// #define LOG_PORT Serial
|
||||
#ifdef LOG_PORT
|
||||
#define LOG(fmt, ...) LOG_PORT.printf("[%s] " fmt , __func__, ##__VA_ARGS__)
|
||||
#define LOG_BIN(x) LOG_PORT.println(x,BIN);
|
||||
#else
|
||||
#define LOG(fmt, ...)
|
||||
#define LOG_BIN(x)
|
||||
#endif
|
||||
|
||||
|
||||
#define SENSORLIB_ATTR_NOT_IMPLEMENTED __attribute__((error("Not implemented")))
|
||||
|
||||
|
||||
template <class chipType>
|
||||
class SensorCommon
|
||||
{
|
||||
typedef int (*iic_fptr_t)(uint8_t devAddr, uint8_t regAddr, uint8_t *data, uint8_t len);
|
||||
|
||||
public:
|
||||
~SensorCommon()
|
||||
{
|
||||
if (__spiSetting) {
|
||||
delete __spiSetting;
|
||||
}
|
||||
}
|
||||
|
||||
void setSpiSetting(uint32_t freq, uint8_t dataOrder = SPI_MSBFIRST, uint8_t dataMode = SPI_MODE0)
|
||||
{
|
||||
__freq = freq;
|
||||
__dataOrder = dataOrder;
|
||||
__dataMode = dataMode;
|
||||
}
|
||||
|
||||
#if defined(ARDUINO)
|
||||
bool begin(TwoWire &w, uint8_t addr, int sda, int scl)
|
||||
{
|
||||
LOG("Using Wire interface.\n");
|
||||
if (__has_init)return thisChip().initImpl();
|
||||
__wire = &w;
|
||||
__wire->begin(sda, scl);
|
||||
__addr = addr;
|
||||
__spi = NULL;
|
||||
thisReadRegCallback = NULL;
|
||||
thisWriteRegCallback = NULL;
|
||||
__has_init = thisChip().initImpl();
|
||||
return __has_init;
|
||||
}
|
||||
|
||||
bool begin(int cs, int mosi = -1, int miso = -1, int sck = -1, SPIClass &spi = SPI)
|
||||
{
|
||||
LOG("Using SPI interface.\n");
|
||||
if (__has_init)return thisChip().initImpl();
|
||||
__spi = &spi;
|
||||
__cs = cs;
|
||||
pinMode(__cs, OUTPUT);
|
||||
digitalWrite(__cs, HIGH);
|
||||
__spiSetting = new SPISettings(__freq, __dataOrder, __dataMode);
|
||||
if (!__spiSetting) {
|
||||
return false;
|
||||
}
|
||||
if (mosi != -1 && miso != -1 && sck == -1) {
|
||||
__spi->begin(sck, miso, mosi);
|
||||
} else {
|
||||
__spi->begin();
|
||||
}
|
||||
__wire = NULL;
|
||||
__readMask = thisChip().getReadMaskImpl();
|
||||
__has_init = thisChip().initImpl();
|
||||
return __has_init;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
|
||||
bool begin(uint8_t addr, iic_fptr_t readRegCallback, iic_fptr_t writeRegCallback)
|
||||
{
|
||||
LOG("Using Custom interface.\n");
|
||||
if (__has_init)return thisChip().initImpl();
|
||||
thisReadRegCallback = readRegCallback;
|
||||
thisWriteRegCallback = writeRegCallback;
|
||||
__addr = addr;
|
||||
__spi = NULL;
|
||||
__has_init = thisChip().initImpl();
|
||||
return __has_init;
|
||||
}
|
||||
|
||||
protected:
|
||||
int readRegister(uint8_t reg)
|
||||
{
|
||||
uint8_t val = 0;
|
||||
if (thisReadRegCallback) {
|
||||
if (thisReadRegCallback(__addr, reg, &val, 1) != 0) {
|
||||
return DEV_WIRE_NONE;
|
||||
}
|
||||
return val;
|
||||
}
|
||||
#if defined(ARDUINO)
|
||||
if (__wire) {
|
||||
__wire->beginTransmission(__addr);
|
||||
__wire->write(reg);
|
||||
if (__wire->endTransmission() != 0) {
|
||||
LOG("I2C Transfer Error!\n");
|
||||
return DEV_WIRE_ERR;
|
||||
}
|
||||
__wire->requestFrom(__addr, 1U);
|
||||
return __wire->read();
|
||||
}
|
||||
if (__spi) {
|
||||
uint8_t data = 0x00;
|
||||
__spi->beginTransaction(*__spiSetting);
|
||||
digitalWrite(__cs, LOW);
|
||||
__spi->transfer(__readMask != -1 ? (reg | __readMask) : reg);
|
||||
data = __spi->transfer(0x00);
|
||||
digitalWrite(__cs, HIGH);
|
||||
__spi->endTransaction();
|
||||
return data;
|
||||
}
|
||||
#endif
|
||||
return DEV_WIRE_ERR;
|
||||
}
|
||||
|
||||
int writeRegister(uint8_t reg, uint8_t norVal, uint8_t orVal)
|
||||
{
|
||||
int val = readRegister(reg);
|
||||
if (val == DEV_WIRE_ERR) {
|
||||
return DEV_WIRE_ERR;
|
||||
}
|
||||
val &= norVal;
|
||||
val |= orVal;
|
||||
return writeRegister(reg, val);
|
||||
}
|
||||
|
||||
int writeRegister(uint8_t reg, uint8_t val)
|
||||
{
|
||||
if (thisWriteRegCallback) {
|
||||
return thisWriteRegCallback(__addr, reg, &val, 1);
|
||||
}
|
||||
#if defined(ARDUINO)
|
||||
if (__wire) {
|
||||
__wire->beginTransmission(__addr);
|
||||
__wire->write(reg);
|
||||
__wire->write(val);
|
||||
return (__wire->endTransmission() == 0) ? DEV_WIRE_NONE : DEV_WIRE_ERR;
|
||||
}
|
||||
if (__spi) {
|
||||
__spi->beginTransaction(*__spiSetting);
|
||||
digitalWrite(__cs, LOW);
|
||||
__spi->transfer(reg);
|
||||
__spi->transfer(val);
|
||||
digitalWrite(__cs, HIGH);
|
||||
__spi->endTransaction();
|
||||
return DEV_WIRE_NONE;
|
||||
}
|
||||
#endif
|
||||
return DEV_WIRE_ERR;
|
||||
}
|
||||
|
||||
int readRegister(uint8_t reg, uint8_t *buf, uint8_t lenght)
|
||||
{
|
||||
if (thisReadRegCallback) {
|
||||
return thisReadRegCallback(__addr, reg, buf, lenght);
|
||||
}
|
||||
#if defined(ARDUINO)
|
||||
if (__wire) {
|
||||
__wire->beginTransmission(__addr);
|
||||
__wire->write(reg);
|
||||
if (__wire->endTransmission() != 0) {
|
||||
return DEV_WIRE_ERR;
|
||||
}
|
||||
__wire->requestFrom(__addr, lenght);
|
||||
return __wire->readBytes(buf, lenght) == lenght ? DEV_WIRE_NONE : DEV_WIRE_ERR;
|
||||
}
|
||||
if (__spi) {
|
||||
__spi->beginTransaction(*__spiSetting);
|
||||
digitalWrite(__cs, LOW);
|
||||
__spi->transfer(__readMask != -1 ? (reg | __readMask) : reg);
|
||||
for (size_t i = 0; i < lenght; i++) {
|
||||
buf[i] = __spi->transfer(0x00);
|
||||
}
|
||||
digitalWrite(__cs, HIGH);
|
||||
__spi->endTransaction();
|
||||
return DEV_WIRE_NONE;
|
||||
}
|
||||
#endif
|
||||
return DEV_WIRE_ERR;
|
||||
}
|
||||
|
||||
int writeRegister(uint8_t reg, uint8_t *buf, uint8_t lenght)
|
||||
{
|
||||
if (thisWriteRegCallback) {
|
||||
return thisWriteRegCallback(__addr, reg, buf, lenght);
|
||||
}
|
||||
#if defined(ARDUINO)
|
||||
if (__wire) {
|
||||
__wire->beginTransmission(__addr);
|
||||
__wire->write(reg);
|
||||
__wire->write(buf, lenght);
|
||||
return (__wire->endTransmission() == 0) ? 0 : DEV_WIRE_ERR;
|
||||
}
|
||||
if (__spi) {
|
||||
__spi->beginTransaction(*__spiSetting);
|
||||
digitalWrite(__cs, LOW);
|
||||
__spi->transfer(reg);
|
||||
__spi->transfer(buf, lenght);
|
||||
digitalWrite(__cs, HIGH);
|
||||
__spi->endTransaction();
|
||||
return DEV_WIRE_NONE;
|
||||
}
|
||||
#endif
|
||||
return DEV_WIRE_ERR;
|
||||
}
|
||||
|
||||
|
||||
bool inline clrRegisterBit(uint8_t registers, uint8_t bit)
|
||||
{
|
||||
int val = readRegister(registers);
|
||||
if (val == DEV_WIRE_ERR) {
|
||||
return false;
|
||||
}
|
||||
return writeRegister(registers, (val & (~_BV(bit)))) == 0;
|
||||
}
|
||||
|
||||
bool inline setRegisterBit(uint8_t registers, uint8_t bit)
|
||||
{
|
||||
int val = readRegister(registers);
|
||||
if (val == DEV_WIRE_ERR) {
|
||||
return false;
|
||||
}
|
||||
return writeRegister(registers, (val | (_BV(bit)))) == 0;
|
||||
}
|
||||
|
||||
bool inline getRegisterBit(uint8_t registers, uint8_t bit)
|
||||
{
|
||||
int val = readRegister(registers);
|
||||
if (val == DEV_WIRE_ERR) {
|
||||
return false;
|
||||
}
|
||||
return val & _BV(bit);
|
||||
}
|
||||
|
||||
uint16_t inline readRegisterH8L4(uint8_t highReg, uint8_t lowReg)
|
||||
{
|
||||
int h8 = readRegister(highReg);
|
||||
int l4 = readRegister(lowReg);
|
||||
if (h8 == DEV_WIRE_ERR || l4 == DEV_WIRE_ERR)return 0;
|
||||
return (h8 << 4) | (l4 & 0x0F);
|
||||
}
|
||||
|
||||
uint16_t inline readRegisterH8L5(uint8_t highReg, uint8_t lowReg)
|
||||
{
|
||||
int h8 = readRegister(highReg);
|
||||
int l5 = readRegister(lowReg);
|
||||
if (h8 == DEV_WIRE_ERR || l5 == DEV_WIRE_ERR)return 0;
|
||||
return (h8 << 5) | (l5 & 0x1F);
|
||||
}
|
||||
|
||||
uint16_t inline readRegisterH6L8(uint8_t highReg, uint8_t lowReg)
|
||||
{
|
||||
int h6 = readRegister(highReg);
|
||||
int l8 = readRegister(lowReg);
|
||||
if (h6 == DEV_WIRE_ERR || l8 == DEV_WIRE_ERR)return 0;
|
||||
return ((h6 & 0x3F) << 8) | l8;
|
||||
}
|
||||
|
||||
uint16_t inline readRegisterH5L8(uint8_t highReg, uint8_t lowReg)
|
||||
{
|
||||
int h5 = readRegister(highReg);
|
||||
int l8 = readRegister(lowReg);
|
||||
if (h5 == DEV_WIRE_ERR || l8 == DEV_WIRE_ERR)return 0;
|
||||
return ((h5 & 0x1F) << 8) | l8;
|
||||
}
|
||||
|
||||
/*
|
||||
* CRTP Helper
|
||||
*/
|
||||
protected:
|
||||
|
||||
bool begin()
|
||||
{
|
||||
#if defined(ARDUINO)
|
||||
if (__has_init) return thisChip().initImpl();
|
||||
__has_init = true;
|
||||
|
||||
if (__wire) {
|
||||
log_i("SDA:%d SCL:%d", __sda, __scl);
|
||||
__wire->begin(__sda, __scl);
|
||||
}
|
||||
if (__spi) {
|
||||
// int cs, int mosi = -1, int miso = -1, int sck = -1, SPIClass &spi = SPI
|
||||
begin(__cs, __mosi, __miso, __sck, *__spi);
|
||||
}
|
||||
|
||||
#endif /*ARDUINO*/
|
||||
return thisChip().initImpl();
|
||||
}
|
||||
|
||||
void end()
|
||||
{
|
||||
#if defined(ARDUINO)
|
||||
if (__wire) {
|
||||
#if defined(ESP_IDF_VERSION)
|
||||
#if ESP_IDF_VERSION > ESP_IDF_VERSION_VAL(4,4,0)
|
||||
__wire->end();
|
||||
#endif /*ESP_IDF_VERSION*/
|
||||
#endif /*ESP_IDF_VERSION*/
|
||||
}
|
||||
#endif /*ARDUINO*/
|
||||
}
|
||||
|
||||
|
||||
inline const chipType &thisChip() const
|
||||
{
|
||||
return static_cast<const chipType &>(*this);
|
||||
}
|
||||
|
||||
inline chipType &thisChip()
|
||||
{
|
||||
return static_cast<chipType &>(*this);
|
||||
}
|
||||
|
||||
protected:
|
||||
bool __has_init = false;
|
||||
#if defined(ARDUINO)
|
||||
TwoWire *__wire = NULL;
|
||||
SPIClass *__spi = NULL;
|
||||
SPISettings *__spiSetting = NULL;
|
||||
#endif
|
||||
uint32_t __freq = 1000000;
|
||||
uint8_t __dataOrder = SPI_MSBFIRST;
|
||||
uint8_t __dataMode = SPI_MODE0;
|
||||
int __readMask = -1;
|
||||
int __sda = -1;
|
||||
int __scl = -1;
|
||||
int __cs = -1;
|
||||
int __miso = -1;
|
||||
int __mosi = -1;
|
||||
int __sck = -1;
|
||||
uint8_t __addr = 0xFF;
|
||||
iic_fptr_t thisReadRegCallback = NULL;
|
||||
iic_fptr_t thisWriteRegCallback = NULL;
|
||||
};
|
||||
399
lib/SensorsLib/src/SensorQMC6310.hpp
Normal file
399
lib/SensorsLib/src/SensorQMC6310.hpp
Normal file
|
|
@ -0,0 +1,399 @@
|
|||
/**
|
||||
*
|
||||
* @license MIT License
|
||||
*
|
||||
* Copyright (c) 2022 lewis he
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
* @file SensorQMC6310.hpp
|
||||
* @author Lewis He (lewishe@outlook.com)
|
||||
* @date 2022-10-16
|
||||
*
|
||||
*/
|
||||
|
||||
|
||||
#include "REG/QMC6310Constants.h"
|
||||
#include "SensorCommon.tpp"
|
||||
|
||||
class Polar
|
||||
{
|
||||
public:
|
||||
Polar(): polar(0), Gauss(0), uT(0) {}
|
||||
Polar(float polar, float Gauss, float uT): polar(polar), Gauss(Gauss), uT(uT) {}
|
||||
float polar;
|
||||
float Gauss;
|
||||
float uT;
|
||||
};
|
||||
|
||||
|
||||
class SensorQMC6310 :
|
||||
public SensorCommon<SensorQMC6310>
|
||||
{
|
||||
friend class SensorCommon<SensorQMC6310>;
|
||||
public:
|
||||
|
||||
|
||||
enum SensorMode {
|
||||
MODE_SUSPEND,
|
||||
MODE_NORMAL,
|
||||
MODE_SINGLE,
|
||||
MODE_CONTINUOUS,
|
||||
};
|
||||
|
||||
// Unit:Guass
|
||||
enum MagRange {
|
||||
RANGE_30G,
|
||||
RANGE_12G,
|
||||
RANGE_8G,
|
||||
RANGE_2G,
|
||||
};
|
||||
|
||||
enum OutputRate {
|
||||
DATARATE_10HZ,
|
||||
DATARATE_50HZ,
|
||||
DATARATE_100HZ,
|
||||
DATARATE_200HZ,
|
||||
};
|
||||
|
||||
enum CtrlReg {
|
||||
SET_RESET_ON,
|
||||
SET_ONLY_ON,
|
||||
SET_RESET_OFF,
|
||||
};
|
||||
|
||||
enum OverSampleRatio {
|
||||
OSR_8,
|
||||
OSR_4,
|
||||
OSR_2,
|
||||
OSR_1,
|
||||
};
|
||||
|
||||
enum DownSampleRatio {
|
||||
DSR_1,
|
||||
DSR_2,
|
||||
DSR_4,
|
||||
DSR_8,
|
||||
};
|
||||
|
||||
#if defined(ARDUINO)
|
||||
SensorQMC6310(TwoWire &w, int sda = SDA, int scl = SCL, uint8_t addr = QMC6310_SLAVE_ADDRESS)
|
||||
{
|
||||
__wire = &w;
|
||||
__sda = sda;
|
||||
__scl = scl;
|
||||
__addr = addr;
|
||||
}
|
||||
#endif
|
||||
|
||||
SensorQMC6310()
|
||||
{
|
||||
#if defined(ARDUINO)
|
||||
__wire = &Wire;
|
||||
__sda = SDA;
|
||||
__scl = SCL;
|
||||
#endif
|
||||
__addr = QMC6310_SLAVE_ADDRESS;
|
||||
}
|
||||
|
||||
~SensorQMC6310()
|
||||
{
|
||||
deinit();
|
||||
}
|
||||
|
||||
bool init()
|
||||
{
|
||||
return begin();
|
||||
}
|
||||
|
||||
void deinit()
|
||||
{
|
||||
// end();
|
||||
}
|
||||
|
||||
void reset()
|
||||
{
|
||||
writeRegister(QMC6310_REG_CMD2, 0x80);
|
||||
delay(10);
|
||||
writeRegister(QMC6310_REG_CMD2, 0x00);
|
||||
}
|
||||
|
||||
uint8_t getChipID()
|
||||
{
|
||||
return readRegister(QMC6310_REG_CHIP_ID);
|
||||
}
|
||||
|
||||
|
||||
int getStatus()
|
||||
{
|
||||
return readRegister(QMC6310_REG_STAT);
|
||||
}
|
||||
|
||||
bool isDataReady()
|
||||
{
|
||||
if (readRegister(QMC6310_REG_STAT) & 0x01) {
|
||||
return true;
|
||||
}
|
||||
LOG("No ready!\n");
|
||||
return false;
|
||||
}
|
||||
|
||||
bool isDataOverflow()
|
||||
{
|
||||
if (readRegister(QMC6310_REG_STAT) & 0x02) {
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
int setSelfTest(bool en)
|
||||
{
|
||||
return en ? setRegisterBit(QMC6310_REG_CMD2, 1)
|
||||
: clrRegisterBit(QMC6310_REG_CMD2, 1);
|
||||
}
|
||||
|
||||
int setMode(SensorMode m)
|
||||
{
|
||||
return writeRegister(QMC6310_REG_CMD1, 0xFC, m);
|
||||
}
|
||||
|
||||
int setCtrlRegister(CtrlReg c)
|
||||
{
|
||||
return writeRegister(QMC6310_REG_CMD2, 0xFC, c);
|
||||
}
|
||||
|
||||
int setDataOutputRate(OutputRate odr)
|
||||
{
|
||||
return writeRegister(QMC6310_REG_CMD1, 0xF3, (odr << 2));
|
||||
}
|
||||
|
||||
int setOverSampleRate(OverSampleRatio osr)
|
||||
{
|
||||
return writeRegister(QMC6310_REG_CMD1, 0xCF, (osr << 4));
|
||||
}
|
||||
|
||||
int setDownSampleRate(DownSampleRatio dsr)
|
||||
{
|
||||
return writeRegister(QMC6310_REG_CMD1, 0x3F, (dsr << 6));
|
||||
}
|
||||
|
||||
// Define the sign for X Y and Z axis
|
||||
int setSign(uint8_t x, uint8_t y, uint8_t z)
|
||||
{
|
||||
int sign = x + y * 2 + z * 4;
|
||||
return writeRegister(QMC6310_REG_SIGN, sign);
|
||||
}
|
||||
|
||||
int configMagnetometer(SensorMode mode, MagRange range, OutputRate odr,
|
||||
OverSampleRatio osr, DownSampleRatio dsr)
|
||||
{
|
||||
if (setMagRange(range) != DEV_WIRE_NONE) {
|
||||
return DEV_WIRE_ERR;
|
||||
}
|
||||
if (writeRegister(QMC6310_REG_CMD1, 0xFC, mode) != DEV_WIRE_NONE) {
|
||||
return DEV_WIRE_ERR;
|
||||
}
|
||||
if (writeRegister(QMC6310_REG_CMD1, 0xF3, (odr << 2)) != DEV_WIRE_NONE) {
|
||||
return DEV_WIRE_ERR;
|
||||
}
|
||||
if (writeRegister(QMC6310_REG_CMD1, 0xCF, (osr << 4)) != DEV_WIRE_NONE) {
|
||||
return DEV_WIRE_ERR;
|
||||
}
|
||||
if (writeRegister(QMC6310_REG_CMD1, 0x3F, (dsr << 6)) != DEV_WIRE_NONE) {
|
||||
return DEV_WIRE_ERR;
|
||||
}
|
||||
return DEV_WIRE_NONE;
|
||||
}
|
||||
|
||||
int setMagRange(MagRange range)
|
||||
{
|
||||
switch (range) {
|
||||
case RANGE_30G:
|
||||
sensitivity = 0.1;
|
||||
break;
|
||||
case RANGE_12G:
|
||||
sensitivity = 0.04;
|
||||
break;
|
||||
case RANGE_8G:
|
||||
sensitivity = 0.026;
|
||||
break;
|
||||
case RANGE_2G:
|
||||
sensitivity = 0.0066;
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
return writeRegister(QMC6310_REG_CMD2, 0xF3, (range << 2));
|
||||
}
|
||||
|
||||
void setOffset(int x, int y, int z)
|
||||
{
|
||||
x_offset = x; y_offset = y; z_offset = z;
|
||||
}
|
||||
|
||||
int readData()
|
||||
{
|
||||
uint8_t buffer[6];
|
||||
int16_t x, y, z;
|
||||
if (readRegister(QMC6310_REG_LSB_DX, buffer,
|
||||
6) != DEV_WIRE_ERR) {
|
||||
x = (int16_t)(buffer[1] << 8) | (buffer[0]);
|
||||
y = (int16_t)(buffer[3] << 8) | (buffer[2]);
|
||||
z = (int16_t)(buffer[5] << 8) | (buffer[4]);
|
||||
|
||||
if (x >= 0x8000) {
|
||||
x = -((65535 - x) + 1);
|
||||
}
|
||||
x = (x - x_offset);
|
||||
if (y >= 0x8000) {
|
||||
y = -((65535 - y) + 1);
|
||||
}
|
||||
y = (y - y_offset);
|
||||
if (z >= 0x8000) {
|
||||
z = -((65535 - z) + 1);
|
||||
}
|
||||
z = (z - z_offset);
|
||||
|
||||
raw[0] = x;
|
||||
raw[1] = y;
|
||||
raw[2] = z;
|
||||
|
||||
mag[0] = (float)x * sensitivity;
|
||||
mag[1] = (float)y * sensitivity;
|
||||
mag[2] = (float)z * sensitivity;
|
||||
return DEV_WIRE_NONE;
|
||||
}
|
||||
return DEV_WIRE_ERR;
|
||||
}
|
||||
|
||||
void setDeclination(float dec)
|
||||
{
|
||||
_declination = dec;
|
||||
}
|
||||
|
||||
bool readPolar(Polar &p)
|
||||
{
|
||||
if (isDataReady()) {
|
||||
readData();
|
||||
float x = getX();
|
||||
float y = getY();
|
||||
float z = getZ();
|
||||
float angle = (atan2(x, -y) / PI) * 180.0 + _declination;
|
||||
angle = _convertAngleToPositive(angle);
|
||||
float magnitude = sqrt(x * x + y * y + z * z);
|
||||
p = Polar(angle, magnitude * 100, magnitude);
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
int16_t getRawX()
|
||||
{
|
||||
return raw[0];
|
||||
}
|
||||
|
||||
int16_t getRawY()
|
||||
{
|
||||
return raw[1];
|
||||
}
|
||||
|
||||
int16_t getRawZ()
|
||||
{
|
||||
return raw[2];
|
||||
}
|
||||
|
||||
float getX()
|
||||
{
|
||||
return mag[0];
|
||||
}
|
||||
|
||||
float getY()
|
||||
{
|
||||
return mag[1];
|
||||
}
|
||||
|
||||
float getZ()
|
||||
{
|
||||
return mag[2];
|
||||
}
|
||||
|
||||
void getMag(float &x, float &y, float &z)
|
||||
{
|
||||
x = mag[0];
|
||||
y = mag[1];
|
||||
z = mag[2];
|
||||
}
|
||||
|
||||
void dumpCtrlRegister()
|
||||
{
|
||||
uint8_t buffer[2];
|
||||
readRegister(QMC6310_REG_CMD1, buffer, 2);
|
||||
for (int i = 0; i < 2; ++i) {
|
||||
#if defined(ARDUINO)
|
||||
Serial.printf("CMD%d: 0x%02x", i + 1, buffer[i]);
|
||||
#else
|
||||
printf("CTRL%d: 0x%02x", i + 1, buffer[i]);
|
||||
#endif
|
||||
#if defined(ARDUINO)
|
||||
Serial.print("\t\t BIN:");
|
||||
Serial.println(buffer[i], BIN);
|
||||
#else
|
||||
LOG("\n");
|
||||
#endif
|
||||
}
|
||||
#if defined(ARDUINO)
|
||||
Serial.println();
|
||||
#else
|
||||
printf("\n");
|
||||
#endif
|
||||
}
|
||||
|
||||
private:
|
||||
|
||||
float _convertAngleToPositive(float angle)
|
||||
{
|
||||
if (angle >= 360.0) {
|
||||
angle = angle - 360.0;
|
||||
}
|
||||
if (angle < 0) {
|
||||
angle = angle + 360.0;
|
||||
}
|
||||
return angle;
|
||||
}
|
||||
|
||||
|
||||
bool initImpl()
|
||||
{
|
||||
reset();
|
||||
return getChipID() == QMC6310_DEFAULT_ID;
|
||||
}
|
||||
|
||||
int getReadMaskImpl()
|
||||
{
|
||||
return -1;
|
||||
}
|
||||
|
||||
protected:
|
||||
int16_t raw[3];
|
||||
float mag[3];
|
||||
float _declination;
|
||||
float sensitivity;
|
||||
int16_t x_offset = 0, y_offset = 0, z_offset = 0;
|
||||
};
|
||||
|
||||
1500
lib/SensorsLib/src/SensorQMI8658.hpp
Normal file
1500
lib/SensorsLib/src/SensorQMI8658.hpp
Normal file
File diff suppressed because it is too large
Load diff
Loading…
Add table
Add a link
Reference in a new issue