mirror of
https://github.com/meshtastic/firmware.git
synced 2025-06-08 14:12:05 +00:00
T1000-E Peripherals (#5141)
* T1000-E Peripherals - enable intelligent charge controller signals - enable Accelerometer - enable internal I2C bus - provide Power to Accelerometer * POC Accelerometer Code (wakeScreen is moot for that device, just test if the driver works) * fix building without the sensor
This commit is contained in:
parent
0c0da3909f
commit
93318b4f56
@ -360,7 +360,12 @@ class AnalogBatteryLevel : public HasBatteryLevel
|
||||
/**
|
||||
* return true if there is a battery installed in this unit
|
||||
*/
|
||||
// if we have a integrated device with a battery, we can assume that the battery is always connected
|
||||
#ifdef BATTERY_IMMUTABLE
|
||||
virtual bool isBatteryConnect() override { return true; }
|
||||
#else
|
||||
virtual bool isBatteryConnect() override { return getBatteryPercent() != -1; }
|
||||
#endif
|
||||
|
||||
/// If we see a battery voltage higher than physics allows - assume charger is pumping
|
||||
/// in power
|
||||
|
@ -136,6 +136,7 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
#define LPS22HB_ADDR_ALT 0x5D
|
||||
#define SHT31_4x_ADDR 0x44
|
||||
#define PMSA0031_ADDR 0x12
|
||||
#define QMA6100P_ADDR 0x12
|
||||
#define AHT10_ADDR 0x38
|
||||
#define RCWL9620_ADDR 0x57
|
||||
#define VEML7700_ADDR 0x10
|
||||
|
@ -37,8 +37,8 @@ ScanI2C::FoundDevice ScanI2C::firstKeyboard() const
|
||||
|
||||
ScanI2C::FoundDevice ScanI2C::firstAccelerometer() const
|
||||
{
|
||||
ScanI2C::DeviceType types[] = {MPU6050, LIS3DH, BMA423, LSM6DS3, BMX160, STK8BAXX, ICM20948};
|
||||
return firstOfOrNONE(7, types);
|
||||
ScanI2C::DeviceType types[] = {MPU6050, LIS3DH, BMA423, LSM6DS3, BMX160, STK8BAXX, ICM20948, QMA6100P};
|
||||
return firstOfOrNONE(8, types);
|
||||
}
|
||||
|
||||
ScanI2C::FoundDevice ScanI2C::find(ScanI2C::DeviceType) const
|
||||
|
@ -39,6 +39,7 @@ class ScanI2C
|
||||
QMC5883L,
|
||||
HMC5883L,
|
||||
PMSA0031,
|
||||
QMA6100P,
|
||||
MPU6050,
|
||||
LIS3DH,
|
||||
BMA423,
|
||||
|
@ -173,7 +173,16 @@ void ScanI2CTwoWire::scanPort(I2CPort port, uint8_t *address, uint8_t asize)
|
||||
}
|
||||
#endif
|
||||
|
||||
for (addr.address = 1; addr.address < 127; addr.address++) {
|
||||
// We only need to scan 112 addresses, the rest is reserved for special purposes
|
||||
// 0x00 General Call
|
||||
// 0x01 CBUS addresses
|
||||
// 0x02 Reserved for different bus formats
|
||||
// 0x03 Reserved for future purposes
|
||||
// 0x04-0x07 High Speed Master Code
|
||||
// 0x78-0x7B 10-bit slave addressing
|
||||
// 0x7C-0x7F Reserved for future purposes
|
||||
|
||||
for (addr.address = 8; addr.address < 120; addr.address++) {
|
||||
if (asize != 0) {
|
||||
if (!in_array(address, asize, addr.address))
|
||||
continue;
|
||||
@ -395,7 +404,11 @@ void ScanI2CTwoWire::scanPort(I2CPort port, uint8_t *address, uint8_t asize)
|
||||
|
||||
SCAN_SIMPLE_CASE(QMC5883L_ADDR, QMC5883L, "QMC5883L Highrate 3-Axis magnetic sensor found")
|
||||
SCAN_SIMPLE_CASE(HMC5883L_ADDR, HMC5883L, "HMC5883L 3-Axis digital compass found")
|
||||
#ifdef HAS_QMA6100P
|
||||
SCAN_SIMPLE_CASE(QMA6100P_ADDR, QMA6100P, "QMA6100P accelerometer found")
|
||||
#else
|
||||
SCAN_SIMPLE_CASE(PMSA0031_ADDR, PMSA0031, "PMSA0031 air quality sensor found")
|
||||
#endif
|
||||
SCAN_SIMPLE_CASE(BMA423_ADDR, BMA423, "BMA423 accelerometer found");
|
||||
SCAN_SIMPLE_CASE(LSM6DS3_ADDR, LSM6DS3, "LSM6DS3 accelerometer found at address 0x%x", (uint8_t)addr.address);
|
||||
SCAN_SIMPLE_CASE(TCA9535_ADDR, TCA9535, "TCA9535 I2C expander found");
|
||||
|
@ -9,7 +9,7 @@ CardKbI2cImpl::CardKbI2cImpl() : KbI2cBase("cardKB") {}
|
||||
|
||||
void CardKbI2cImpl::init()
|
||||
{
|
||||
#if !MESHTASTIC_EXCLUDE_I2C && !defined(ARCH_PORTDUINO)
|
||||
#if !MESHTASTIC_EXCLUDE_I2C && !defined(ARCH_PORTDUINO) && !defined(I2C_NO_RESCAN)
|
||||
if (cardkb_found.address == 0x00) {
|
||||
LOG_DEBUG("Rescanning for I2C keyboard");
|
||||
uint8_t i2caddr_scan[] = {CARDKB_ADDR, TDECK_KB_ADDR, BBQ10_KB_ADDR, MPR121_KB_ADDR};
|
||||
@ -49,7 +49,7 @@ void CardKbI2cImpl::init()
|
||||
kb_model = 0x00;
|
||||
}
|
||||
}
|
||||
LOG_DEBUG("Keyboard Type: 0x%02x Model: 0x%02x Address: 0x%02x\n", kb_info.type, kb_model, cardkb_found.address);
|
||||
LOG_DEBUG("Keyboard Type: 0x%02x Model: 0x%02x Address: 0x%02x", kb_info.type, kb_model, cardkb_found.address);
|
||||
if (cardkb_found.address == 0x00) {
|
||||
disable();
|
||||
return;
|
||||
|
@ -35,6 +35,7 @@ int32_t AirQualityTelemetryModule::runOnce()
|
||||
if (moduleConfig.telemetry.air_quality_enabled) {
|
||||
LOG_INFO("Air quality Telemetry: Initializing");
|
||||
if (!aqi.begin_I2C()) {
|
||||
#ifndef I2C_NO_RESCAN
|
||||
LOG_WARN("Could not establish i2c connection to AQI sensor. Rescanning...");
|
||||
// rescan for late arriving sensors. AQI Module starts about 10 seconds into the boot so this is plenty.
|
||||
uint8_t i2caddr_scan[] = {PMSA0031_ADDR};
|
||||
@ -51,6 +52,7 @@ int32_t AirQualityTelemetryModule::runOnce()
|
||||
i2cScanner->fetchI2CBus(found.address);
|
||||
return 1000;
|
||||
}
|
||||
#endif
|
||||
return disable();
|
||||
}
|
||||
return 1000;
|
||||
|
@ -14,6 +14,9 @@
|
||||
#include "LSM6DS3Sensor.h"
|
||||
#include "MPU6050Sensor.h"
|
||||
#include "MotionSensor.h"
|
||||
#ifdef HAS_QMA6100P
|
||||
#include "QMA6100PSensor.h"
|
||||
#endif
|
||||
#include "STK8XXXSensor.h"
|
||||
|
||||
extern ScanI2C::DeviceAddress accelerometer_found;
|
||||
@ -97,6 +100,11 @@ class AccelerometerThread : public concurrency::OSThread
|
||||
case ScanI2C::DeviceType::ICM20948:
|
||||
sensor = new ICM20948Sensor(device);
|
||||
break;
|
||||
#ifdef HAS_QMA6100P
|
||||
case ScanI2C::DeviceType::QMA6100P:
|
||||
sensor = new QMA6100PSensor(device);
|
||||
break;
|
||||
#endif
|
||||
default:
|
||||
disable();
|
||||
return;
|
||||
|
183
src/motion/QMA6100PSensor.cpp
Normal file
183
src/motion/QMA6100PSensor.cpp
Normal file
@ -0,0 +1,183 @@
|
||||
#include "QMA6100PSensor.h"
|
||||
|
||||
#if !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL) && !MESHTASTIC_EXCLUDE_I2C && HAS_QMA6100P
|
||||
|
||||
// Flag when an interrupt has been detected
|
||||
volatile static bool QMA6100P_IRQ = false;
|
||||
|
||||
// Interrupt service routine
|
||||
void QMA6100PSetInterrupt()
|
||||
{
|
||||
QMA6100P_IRQ = true;
|
||||
}
|
||||
|
||||
QMA6100PSensor::QMA6100PSensor(ScanI2C::FoundDevice foundDevice) : MotionSensor::MotionSensor(foundDevice) {}
|
||||
|
||||
bool QMA6100PSensor::init()
|
||||
{
|
||||
// Initialise the sensor
|
||||
sensor = QMA6100PSingleton::GetInstance();
|
||||
if (!sensor->init(device))
|
||||
return false;
|
||||
|
||||
// Enable simple Wake on Motion
|
||||
return sensor->setWakeOnMotion();
|
||||
}
|
||||
|
||||
#ifdef QMA_6100P_INT_PIN
|
||||
|
||||
int32_t QMA6100PSensor::runOnce()
|
||||
{
|
||||
// Wake on motion using hardware interrupts - this is the most efficient way to check for motion
|
||||
if (QMA6100P_IRQ) {
|
||||
QMA6100P_IRQ = false;
|
||||
wakeScreen();
|
||||
}
|
||||
return MOTION_SENSOR_CHECK_INTERVAL_MS;
|
||||
}
|
||||
|
||||
#else
|
||||
|
||||
int32_t QMA6100PSensor::runOnce()
|
||||
{
|
||||
// Wake on motion using polling - this is not as efficient as using hardware interrupt pin (see above)
|
||||
|
||||
uint8_t tempVal;
|
||||
if (!sensor->readRegisterRegion(SFE_QMA6100P_INT_ST0, &tempVal, 1)) {
|
||||
LOG_DEBUG("QMA6100PSensor::isWakeOnMotion failed to read interrupts");
|
||||
return MOTION_SENSOR_CHECK_INTERVAL_MS;
|
||||
}
|
||||
|
||||
if ((tempVal & 7) != 0) {
|
||||
// Wake up!
|
||||
wakeScreen();
|
||||
}
|
||||
return MOTION_SENSOR_CHECK_INTERVAL_MS;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
// ----------------------------------------------------------------------
|
||||
// QMA6100PSingleton
|
||||
// ----------------------------------------------------------------------
|
||||
|
||||
// Get a singleton wrapper for an Sparkfun QMA_6100P_I2C
|
||||
QMA6100PSingleton *QMA6100PSingleton::GetInstance()
|
||||
{
|
||||
if (pinstance == nullptr) {
|
||||
pinstance = new QMA6100PSingleton();
|
||||
}
|
||||
return pinstance;
|
||||
}
|
||||
|
||||
QMA6100PSingleton::QMA6100PSingleton() {}
|
||||
|
||||
QMA6100PSingleton::~QMA6100PSingleton() {}
|
||||
|
||||
QMA6100PSingleton *QMA6100PSingleton::pinstance{nullptr};
|
||||
|
||||
// Initialise the QMA6100P Sensor
|
||||
bool QMA6100PSingleton::init(ScanI2C::FoundDevice device)
|
||||
{
|
||||
|
||||
// startup
|
||||
#ifdef Wire1
|
||||
bool status = begin(device.address.address, device.address.port == ScanI2C::I2CPort::WIRE1 ? &Wire1 : &Wire);
|
||||
#else
|
||||
// check chip id
|
||||
bool status = begin(device.address.address, &Wire);
|
||||
#endif
|
||||
if (status != true) {
|
||||
LOG_WARN("QMA6100PSensor::init begin failed\n");
|
||||
return false;
|
||||
}
|
||||
delay(20);
|
||||
// SW reset to make sure the device starts in a known state
|
||||
if (softwareReset() != true) {
|
||||
LOG_WARN("QMA6100PSensor::init reset failed\n");
|
||||
return false;
|
||||
}
|
||||
delay(20);
|
||||
// Set range
|
||||
if (!setRange(QMA_6100P_MPU_ACCEL_SCALE)) {
|
||||
LOG_WARN("QMA6100PSensor::init range failed");
|
||||
return false;
|
||||
}
|
||||
// set active mode
|
||||
if (!enableAccel()) {
|
||||
LOG_WARN("ERROR :QMA6100PSensor::active mode set failed");
|
||||
}
|
||||
// set calibrateoffsets
|
||||
if (!calibrateOffsets()) {
|
||||
LOG_WARN("ERROR :QMA6100PSensor:: calibration failed");
|
||||
}
|
||||
#ifdef QMA_6100P_INT_PIN
|
||||
|
||||
// Active low & Open Drain
|
||||
uint8_t tempVal;
|
||||
if (!readRegisterRegion(SFE_QMA6100P_INTPINT_CONF, &tempVal, 1)) {
|
||||
LOG_WARN("QMA6100PSensor::init failed to read interrupt pin config");
|
||||
return false;
|
||||
}
|
||||
|
||||
tempVal |= 0b00000010; // Active low & Open Drain
|
||||
|
||||
if (!writeRegisterByte(SFE_QMA6100P_INTPINT_CONF, tempVal)) {
|
||||
LOG_WARN("QMA6100PSensor::init failed to write interrupt pin config");
|
||||
return false;
|
||||
}
|
||||
|
||||
// Latch until cleared, all reads clear the latch
|
||||
if (!readRegisterRegion(SFE_QMA6100P_INT_CFG, &tempVal, 1)) {
|
||||
LOG_WARN("QMA6100PSensor::init failed to read interrupt config");
|
||||
return false;
|
||||
}
|
||||
|
||||
tempVal |= 0b10000001; // Latch until cleared, INT_RD_CLR1
|
||||
|
||||
if (!writeRegisterByte(SFE_QMA6100P_INT_CFG, tempVal)) {
|
||||
LOG_WARN("QMA6100PSensor::init failed to write interrupt config");
|
||||
return false;
|
||||
}
|
||||
// Set up an interrupt pin with an internal pullup for active low
|
||||
pinMode(QMA_6100P_INT_PIN, INPUT_PULLUP);
|
||||
|
||||
// Set up an interrupt service routine
|
||||
attachInterrupt(QMA_6100P_INT_PIN, QMA6100PSetInterrupt, FALLING);
|
||||
|
||||
#endif
|
||||
return true;
|
||||
}
|
||||
|
||||
bool QMA6100PSingleton::setWakeOnMotion()
|
||||
{
|
||||
// Enable 'Any Motion' interrupt
|
||||
if (!writeRegisterByte(SFE_QMA6100P_INT_EN2, 0b00000111)) {
|
||||
LOG_WARN("QMA6100PSingleton::setWakeOnMotion failed to write interrupt enable");
|
||||
return false;
|
||||
}
|
||||
|
||||
// Set 'Significant Motion' interrupt map to INT1
|
||||
uint8_t tempVal;
|
||||
|
||||
if (!readRegisterRegion(SFE_QMA6100P_INT_MAP1, &tempVal, 1)) {
|
||||
LOG_WARN("QMA6100PSingleton::setWakeOnMotion failed to read interrupt map");
|
||||
return false;
|
||||
}
|
||||
|
||||
sfe_qma6100p_int_map1_bitfield_t int_map1;
|
||||
int_map1.all = tempVal;
|
||||
int_map1.bits.int1_any_mot = 1; // any motion interrupt to INT1
|
||||
tempVal = int_map1.all;
|
||||
|
||||
if (!writeRegisterByte(SFE_QMA6100P_INT_MAP1, tempVal)) {
|
||||
LOG_WARN("QMA6100PSingleton::setWakeOnMotion failed to write interrupt map");
|
||||
return false;
|
||||
}
|
||||
|
||||
// Clear any current interrupts
|
||||
QMA6100P_IRQ = false;
|
||||
return true;
|
||||
}
|
||||
|
||||
#endif
|
63
src/motion/QMA6100PSensor.h
Normal file
63
src/motion/QMA6100PSensor.h
Normal file
@ -0,0 +1,63 @@
|
||||
#pragma once
|
||||
#ifndef _QMA_6100P_SENSOR_H_
|
||||
#define _QMA_6100P_SENSOR_H_
|
||||
|
||||
#include "MotionSensor.h"
|
||||
|
||||
#if !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL) && !MESHTASTIC_EXCLUDE_I2C && HAS_QMA6100P
|
||||
|
||||
#include <QMA6100P.h>
|
||||
|
||||
// Set the default accelerometer scale - gpm2, gpm4, gpm8, gpm16
|
||||
#ifndef QMA_6100P_MPU_ACCEL_SCALE
|
||||
#define QMA_6100P_MPU_ACCEL_SCALE SFE_QMA6100P_RANGE32G
|
||||
#endif
|
||||
|
||||
// The I2C address of the Accelerometer (if found) from main.cpp
|
||||
extern ScanI2C::DeviceAddress accelerometer_found;
|
||||
|
||||
// Singleton wrapper for the Sparkfun QMA_6100P_I2C class
|
||||
class QMA6100PSingleton : public QMA6100P
|
||||
{
|
||||
private:
|
||||
static QMA6100PSingleton *pinstance;
|
||||
|
||||
protected:
|
||||
QMA6100PSingleton();
|
||||
~QMA6100PSingleton();
|
||||
|
||||
public:
|
||||
// Create a singleton instance (not thread safe)
|
||||
static QMA6100PSingleton *GetInstance();
|
||||
|
||||
// Singletons should not be cloneable.
|
||||
QMA6100PSingleton(QMA6100PSingleton &other) = delete;
|
||||
|
||||
// Singletons should not be assignable.
|
||||
void operator=(const QMA6100PSingleton &) = delete;
|
||||
|
||||
// Initialise the motion sensor singleton for normal operation
|
||||
bool init(ScanI2C::FoundDevice device);
|
||||
|
||||
// Enable Wake on Motion interrupts (sensor must be initialised first)
|
||||
bool setWakeOnMotion();
|
||||
};
|
||||
|
||||
class QMA6100PSensor : public MotionSensor
|
||||
{
|
||||
private:
|
||||
QMA6100PSingleton *sensor = nullptr;
|
||||
|
||||
public:
|
||||
explicit QMA6100PSensor(ScanI2C::FoundDevice foundDevice);
|
||||
|
||||
// Initialise the motion sensor
|
||||
virtual bool init() override;
|
||||
|
||||
// Called each time our sensor gets a chance to run
|
||||
virtual int32_t runOnce() override;
|
||||
};
|
||||
|
||||
#endif
|
||||
|
||||
#endif
|
@ -717,7 +717,7 @@ bool MQTT::isPrivateIpAddress(const char address[])
|
||||
// Even if it's not a valid IP address, we will know it's not a domain.
|
||||
bool hasColon = false;
|
||||
int numDots = 0;
|
||||
for (int i = 0; i < length; i++) {
|
||||
for (size_t i = 0; i < length; i++) {
|
||||
if (!isdigit(address[i]) && address[i] != '.' && address[i] != ':') {
|
||||
return false;
|
||||
}
|
||||
|
@ -1,16 +1,14 @@
|
||||
; tracker-t1000-e v0.9.1
|
||||
[env:tracker-t1000-e]
|
||||
extends = nrf52840_base
|
||||
board = tracker-t1000-e
|
||||
; board_level = extra
|
||||
; platform = https://github.com/maxgerhardt/platform-nordicnrf52#cac6fcf943a41accd2aeb4f3659ae297a73f422e
|
||||
build_flags = ${nrf52840_base.build_flags} -Ivariants/tracker-t1000-e -Isrc/platform/nrf52/softdevice -Isrc/platform/nrf52/softdevice/nrf52 -DTRACKER_T1000_E
|
||||
-L "${platformio.libdeps_dir}/${this.__env__}/bsec2/src/cortex-m4/fpv4-sp-d16-hard"
|
||||
-DGPS_POWER_TOGGLE ; comment this line to disable triple press function on the user button to turn off gps entirely.
|
||||
-DGPS_POWER_TOGGLE
|
||||
board_build.ldscript = src/platform/nrf52/nrf52840_s140_v7.ld
|
||||
build_src_filter = ${nrf52_base.build_src_filter} +<../variants/tracker-t1000-e>
|
||||
lib_deps =
|
||||
${nrf52840_base.lib_deps}
|
||||
https://github.com/meshtastic/QMA6100P_Arduino_Library.git#14c900b8b2e4feaac5007a7e41e0c1b7f0841136
|
||||
debug_tool = jlink
|
||||
; If not set we will default to uploading over serial (first it forces bootloader entry by talking 1200bps to cdcacm)
|
||||
upload_protocol = nrfutil
|
||||
|
@ -40,7 +40,7 @@ void initVariant()
|
||||
digitalWrite(PIN_3V3_EN, HIGH);
|
||||
|
||||
pinMode(PIN_3V3_ACC_EN, OUTPUT);
|
||||
digitalWrite(PIN_3V3_ACC_EN, LOW);
|
||||
digitalWrite(PIN_3V3_ACC_EN, HIGH);
|
||||
|
||||
pinMode(BUZZER_EN_PIN, OUTPUT);
|
||||
digitalWrite(BUZZER_EN_PIN, HIGH);
|
||||
|
@ -52,7 +52,7 @@ extern "C" {
|
||||
#define LED_BLUE -1 // Actually green
|
||||
#define LED_STATE_ON 1 // State when LED is lit
|
||||
|
||||
#define BUTTON_PIN (0 + 6) // P0.6
|
||||
#define BUTTON_PIN (0 + 6) // P0.06
|
||||
#define BUTTON_ACTIVE_LOW false
|
||||
#define BUTTON_ACTIVE_PULLUP false
|
||||
#define BUTTON_SENSE_TYPE 0x6
|
||||
@ -61,9 +61,11 @@ extern "C" {
|
||||
|
||||
#define WIRE_INTERFACES_COUNT 1
|
||||
|
||||
// unused pins
|
||||
#define PIN_WIRE_SDA (0 + 9) // P0.26
|
||||
#define PIN_WIRE_SCL (0 + 10) // P0.27
|
||||
#define PIN_WIRE_SDA (0 + 26) // P0.26
|
||||
#define PIN_WIRE_SCL (0 + 27) // P0.27
|
||||
#define I2C_NO_RESCAN // I2C is a bit finicky, don't scan too much
|
||||
#define HAS_QMA6100P // very rare beast, only on this board.
|
||||
#define QMA_6100P_INT_PIN (32 + 2) // P1.02
|
||||
|
||||
/*
|
||||
* Serial interfaces
|
||||
@ -116,14 +118,22 @@ extern "C" {
|
||||
#define PIN_GPS_RESET (32 + 15) // P1.15
|
||||
#define GPS_RESET_MODE HIGH
|
||||
|
||||
#define GPS_VRTC_EN (0 + 8) // P0.8, awlays high
|
||||
#define GPS_SLEEP_INT (32 + 12) // P1.12, awlays high
|
||||
#define GPS_VRTC_EN (0 + 8) // P0.8, always high
|
||||
#define GPS_SLEEP_INT (32 + 12) // P1.12, always high
|
||||
#define GPS_RTC_INT (0 + 15) // P0.15, normal is LOW, wake by HIGH
|
||||
#define GPS_RESETB_OUT (32 + 14) // P1.14, awlays input pull_up
|
||||
#define GPS_RESETB_OUT (32 + 14) // P1.14, always input pull_up
|
||||
|
||||
#define GPS_FIX_HOLD_TIME 15000 // ms
|
||||
#define BATTERY_PIN 2
|
||||
#define BATTERY_PIN 2 // P0.02/AIN0, BAT_ADC
|
||||
#define BATTERY_IMMUTABLE
|
||||
#define ADC_MULTIPLIER (2.0F)
|
||||
// P0.04/AIN2 is VCC_ADC, P0.05/AIN3 is CHARGER_DET, P1.03 is CHARGE_STA, P1.04 is CHARGE_DONE
|
||||
|
||||
#define EXT_CHRG_DETECT (32 + 3) // P1.03
|
||||
#define EXT_CHRG_DETECT_VALUE LOW
|
||||
// #define EXT_IS_CHRGD (32 + 4) // P1.04
|
||||
// #define EXT_IS_CHRGD_VALUE LOW
|
||||
#define EXT_PWR_DETECT (0 + 5) // P0.05
|
||||
|
||||
#define ADC_RESOLUTION 14
|
||||
#define BATTERY_SENSE_RESOLUTION_BITS 12
|
||||
@ -133,13 +143,13 @@ extern "C" {
|
||||
#define VBAT_AR_INTERNAL AR_INTERNAL_3_0
|
||||
|
||||
// Buzzer
|
||||
#define BUZZER_EN_PIN (32 + 5) // P1.05, awlays high
|
||||
#define BUZZER_EN_PIN (32 + 5) // P1.05, always high
|
||||
#define PIN_BUZZER (0 + 25) // P0.25, pwm output
|
||||
|
||||
#define T1000X_SENSOR_EN
|
||||
#define T1000X_VCC_PIN (0 + 4) // P0.4
|
||||
#define T1000X_NTC_PIN (0 + 31) // P0.31
|
||||
#define T1000X_LUX_PIN (0 + 29) // P0.29
|
||||
#define T1000X_NTC_PIN (0 + 31) // P0.31/AIN7
|
||||
#define T1000X_LUX_PIN (0 + 29) // P0.29/AIN5
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user