mirror of
https://github.com/OpenEPaperLink/OpenEPaperLink.git
synced 2026-03-21 10:06:07 +01:00
added support for NFC wake
This commit is contained in:
BIN
tag_fw/fw154.bin
BIN
tag_fw/fw154.bin
Binary file not shown.
Binary file not shown.
BIN
tag_fw/fw29.bin
BIN
tag_fw/fw29.bin
Binary file not shown.
BIN
tag_fw/fw42.bin
BIN
tag_fw/fw42.bin
Binary file not shown.
@@ -23,6 +23,24 @@ extern void dump(uint8_t* __xdata a, uint16_t __xdata l); // remove me when don
|
||||
extern uint8_t __xdata blockXferBuffer[];
|
||||
__xdata uint8_t i2cbuffer[18];
|
||||
|
||||
bool supportsNFCWake() {
|
||||
P1PULL |= (1 << 3);
|
||||
timerDelay(33300); // wait 25 ms
|
||||
uint32_t pcount = 0;
|
||||
P1PULL &= ~(1 << 3);
|
||||
while (P1_3 && pcount < 10000) {
|
||||
pcount++;
|
||||
}
|
||||
if (pcount < 10000) {
|
||||
// P1_3 (Field Detect) dropped to 'low' pretty fast, this means the load on this pin is high
|
||||
pr("This tag currently does not support NFC wake, load on the FD pin (P1.3) is pretty high.\nOn some boards, a pull-up resistor backpowers the NFC IC. Consider removing it!\n");
|
||||
return false;
|
||||
} else {
|
||||
// No reason to believe this pin is currently loaded down severely
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
||||
void loadRawNTag(uint16_t blocksize) {
|
||||
struct I2cTransaction __xdata i2ctrans;
|
||||
if (blocksize > 864) blocksize = 864;
|
||||
|
||||
@@ -2,6 +2,7 @@
|
||||
#define _I2CDEV_H_
|
||||
#include <stdint.h>
|
||||
|
||||
bool supportsNFCWake();
|
||||
void loadURLtoNTag();
|
||||
void loadRawNTag(uint16_t blocksize);
|
||||
bool i2cCheckDevice(uint8_t address);
|
||||
|
||||
@@ -23,8 +23,6 @@
|
||||
|
||||
// #define DEBUG_MODE
|
||||
|
||||
uint8_t __xdata capabilities = 0;
|
||||
|
||||
void displayLoop() {
|
||||
powerUp(INIT_BASE | INIT_UART);
|
||||
|
||||
@@ -180,16 +178,22 @@ void main() {
|
||||
}
|
||||
}
|
||||
|
||||
pr("BOOTED> %d.%d.%d%s", fwVersion / 100, (fwVersion % 100) / 10, (fwVersion % 10), fwVersionSuffix);
|
||||
pr("BOOTED> %d.%d.%d%s\n", fwVersion / 100, (fwVersion % 100) / 10, (fwVersion % 10), fwVersionSuffix);
|
||||
|
||||
#ifdef HAS_BUTTON
|
||||
capabilities |= CAPABILITY_HAS_WAKE_BUTTON;
|
||||
#endif
|
||||
powerUp(INIT_I2C);
|
||||
if (i2cCheckDevice(0x55)){
|
||||
if (i2cCheckDevice(0x55)) {
|
||||
powerDown(INIT_I2C);
|
||||
capabilities |= CAPABILITY_HAS_NFC;
|
||||
if (supportsNFCWake()) {
|
||||
pr("This board supports NFC wake!\n");
|
||||
capabilities |= CAPABILITY_NFC_WAKE;
|
||||
}
|
||||
} else {
|
||||
powerDown(INIT_I2C);
|
||||
}
|
||||
powerDown(INIT_I2C);
|
||||
|
||||
pr("MAC>%02X%02X", mSelfMac[0], mSelfMac[1]);
|
||||
pr("%02X%02X", mSelfMac[2], mSelfMac[3]);
|
||||
|
||||
@@ -39,6 +39,8 @@ bool __xdata lowBattery = false;
|
||||
uint16_t __xdata longDataReqCounter = 0;
|
||||
uint16_t __xdata voltageCheckCounter = 0;
|
||||
|
||||
uint8_t __xdata capabilities = 0;
|
||||
|
||||
bool __xdata spiActive = false;
|
||||
bool __xdata uartActive = false;
|
||||
bool __xdata eepromActive = false;
|
||||
@@ -130,7 +132,7 @@ static void configI2C(const bool setup) {
|
||||
P1FUNC |= (1 << 4) | (1 << 5);
|
||||
P1PULL |= (1 << 4) | (1 << 5);
|
||||
i2cInit();
|
||||
i2cCheckDevice(0x50); // first transaction after init fails, this makes sure everything is ready for the first transaction
|
||||
i2cCheckDevice(0x50); // first transaction after init fails, this makes sure everything is ready for the first transaction
|
||||
} else {
|
||||
P1DIR |= (1 << 6);
|
||||
P1_6 = 0;
|
||||
@@ -259,13 +261,23 @@ void doSleep(const uint32_t __xdata t) {
|
||||
|
||||
#ifdef HAS_BUTTON
|
||||
// Button setup on TEST pin 1.0 (input pullup)
|
||||
P1FUNC &= ~(1 << 0);
|
||||
P1DIR |= (1 << 0);
|
||||
P1PULL |= (1 << 0);
|
||||
P1LVLSEL |= (1 << 0);
|
||||
P1INTEN = (1 << 0);
|
||||
P1CHSTA &= ~(1 << 0);
|
||||
P1FUNC &= ~(1 << 0);
|
||||
P1DIR |= (1 << 0);
|
||||
P1PULL |= (1 << 0);
|
||||
P1LVLSEL |= (1 << 0);
|
||||
P1INTEN = (1 << 0);
|
||||
P1CHSTA &= ~(1 << 0);
|
||||
#endif
|
||||
|
||||
if (capabilities & CAPABILITY_NFC_WAKE) {
|
||||
P1FUNC &= ~(1 << 3);
|
||||
P1DIR |= (1 << 3);
|
||||
P1PULL |= (1 << 3);
|
||||
P1LVLSEL |= (1 << 3);
|
||||
P1INTEN = (1 << 3);
|
||||
P1CHSTA &= ~(1 << 3);
|
||||
}
|
||||
|
||||
// sleepy
|
||||
sleepForMsec(t);
|
||||
#ifdef HAS_BUTTON
|
||||
@@ -274,6 +286,11 @@ void doSleep(const uint32_t __xdata t) {
|
||||
wakeUpReason = WAKEUP_REASON_GPIO;
|
||||
P1CHSTA &= ~(1 << 0);
|
||||
}
|
||||
|
||||
if (P1CHSTA && (1 << 3) && capabilities & CAPABILITY_NFC_WAKE) {
|
||||
wakeUpReason = WAKEUP_REASON_NFC;
|
||||
P1CHSTA &= ~(1 << 3);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
@@ -82,6 +82,8 @@ extern void initPowerSaving(const uint16_t initialValue);
|
||||
|
||||
extern uint8_t __xdata wakeUpReason;
|
||||
|
||||
extern uint8_t __xdata capabilities;
|
||||
|
||||
extern uint16_t __xdata nextCheckInFromAP;
|
||||
extern uint8_t __xdata dataReqLastAttempt;
|
||||
extern int8_t __xdata temperature;
|
||||
|
||||
@@ -116,6 +116,7 @@ struct AvailDataReq {
|
||||
|
||||
#define CAPABILITY_HAS_WAKE_BUTTON 0x20
|
||||
#define CAPABILITY_HAS_NFC 0x40
|
||||
#define CAPABILITY_NFC_WAKE 0x80
|
||||
|
||||
#define DATATYPE_NOUPDATE 0
|
||||
#define DATATYPE_IMG_BMP 2
|
||||
|
||||
@@ -50,9 +50,6 @@ uint8_t __xdata currentChannel = 0;
|
||||
static uint8_t __xdata inBuffer[128] = {0};
|
||||
static uint8_t __xdata outBuffer[128] = {0};
|
||||
|
||||
// get capabilities from main.c
|
||||
extern uint8_t __xdata capabilities;
|
||||
|
||||
// tools
|
||||
static uint8_t __xdata getPacketType(const void *__xdata buffer) {
|
||||
const struct MacFcs *__xdata fcs = buffer;
|
||||
|
||||
Reference in New Issue
Block a user