reformat everything

using @girtsf clang-format prefs settings.  This should allow us to turn
on auto format in our editors without causing spurious file changes.
1.2-legacy
geeksville 2020-03-18 19:15:51 -07:00
rodzic f6f9dfa463
commit 32ac5ac9ae
31 zmienionych plików z 1138 dodań i 1262 usunięć

Wyświetl plik

@ -1,20 +1,16 @@
#include "CustomRF95.h"
#include <pb_encode.h>
#include <pb_decode.h>
#include "configuration.h"
#include "assert.h"
#include "NodeDB.h"
#include "assert.h"
#include "configuration.h"
#include <pb_decode.h>
#include <pb_encode.h>
/// A temporary buffer used for sending/receving packets, sized to hold the biggest buffer we might need
#define MAX_RHPACKETLEN 251
static uint8_t radiobuf[MAX_RHPACKETLEN];
CustomRF95::CustomRF95(MemoryPool<MeshPacket> &_pool, PointerQueue<MeshPacket> &_rxDest)
: RH_RF95(NSS_GPIO, DIO0_GPIO),
pool(_pool),
rxDest(_rxDest),
txQueue(MAX_TX_QUEUE),
sendingPacket(NULL)
: RH_RF95(NSS_GPIO, DIO0_GPIO), pool(_pool), rxDest(_rxDest), txQueue(MAX_TX_QUEUE), sendingPacket(NULL)
{
}
@ -22,7 +18,7 @@ bool CustomRF95::canSleep()
{
// We allow initializing mode, because sometimes while testing we don't ever call init() to turn on the hardware
DEBUG_MSG("canSleep, mode=%d, isRx=%d, txEmpty=%d, txGood=%d\n", _mode, _isReceiving, txQueue.isEmpty(), _txGood);
return (_mode == RHModeInitialising || _mode == RHModeIdle || _mode == RHModeRx) && !_isReceiving && txQueue.isEmpty();
return (_mode == RHModeInitialising || _mode == RHModeIdle || _mode == RHModeRx) && !_isReceiving && txQueue.isEmpty();
}
bool CustomRF95::sleep()
@ -47,17 +43,14 @@ bool CustomRF95::init()
ErrorCode CustomRF95::send(MeshPacket *p)
{
// We wait _if_ we are partially though receiving a packet (rather than just merely waiting for one).
// To do otherwise would be doubly bad because not only would we drop the packet that was on the way in,
// To do otherwise would be doubly bad because not only would we drop the packet that was on the way in,
// we almost certainly guarantee no one outside will like the packet we are sending.
if (_mode == RHModeIdle || (_mode == RHModeRx && !_isReceiving))
{
if (_mode == RHModeIdle || (_mode == RHModeRx && !_isReceiving)) {
// if the radio is idle, we can send right away
DEBUG_MSG("immedate send on mesh (txGood=%d,rxGood=%d,rxBad=%d)\n", txGood(), rxGood(), rxBad());
startSend(p);
return ERRNO_OK;
}
else
{
} else {
DEBUG_MSG("enquing packet for send from=0x%x, to=0x%x\n", p->from, p->to);
ErrorCode res = txQueue.enqueue(p, 0) ? ERRNO_OK : ERRNO_UNKNOWN;
@ -68,7 +61,8 @@ ErrorCode CustomRF95::send(MeshPacket *p)
}
}
// After doing standard behavior, check to see if a new packet arrived or one was sent and start a new send or receive as necessary
// After doing standard behavior, check to see if a new packet arrived or one was sent and start a new send or receive as
// necessary
void CustomRF95::handleInterrupt()
{
RH_RF95::handleInterrupt();
@ -85,8 +79,7 @@ void CustomRF95::handleInterrupt()
}
// If we just finished receiving a packet, forward it into a queue
if (_rxBufValid)
{
if (_rxBufValid) {
// We received a packet
// Skip the 4 headers that are at the beginning of the rxBuf
@ -95,7 +88,7 @@ void CustomRF95::handleInterrupt()
// FIXME - throws exception if called in ISR context: frequencyError() - probably the floating point math
int32_t freqerr = -1, snr = lastSNR();
//DEBUG_MSG("Received packet from mesh src=0x%x,dest=0x%x,id=%d,len=%d rxGood=%d,rxBad=%d,freqErr=%d,snr=%d\n",
// DEBUG_MSG("Received packet from mesh src=0x%x,dest=0x%x,id=%d,len=%d rxGood=%d,rxBad=%d,freqErr=%d,snr=%d\n",
// srcaddr, destaddr, id, rxlen, rf95.rxGood(), rf95.rxBad(), freqerr, snr);
MeshPacket *mp = pool.allocZeroed();
@ -111,18 +104,14 @@ void CustomRF95::handleInterrupt()
// Note: we can't create it at this point, because it might be a bogus User node allocation. But odds are we will
// already have a record we can hide this debugging info in.
NodeInfo *info = nodeDB.getNode(mp->from);
if (info)
{
if (info) {
info->snr = snr;
info->frequency_error = freqerr;
}
if (!pb_decode_from_bytes(payload, payloadLen, SubPacket_fields, p))
{
if (!pb_decode_from_bytes(payload, payloadLen, SubPacket_fields, p)) {
pool.releaseFromISR(mp, &higherPriWoken);
}
else
{
} else {
// parsing was successful, queue for our recipient
mp->has_payload = true;
@ -141,7 +130,7 @@ void CustomRF95::handleInterrupt()
}
/** The ISR doesn't have any good work to do, give a new assignment.
*
*
* Return true if a higher pri task has woken
*/
bool CustomRF95::handleIdleISR()
@ -152,8 +141,7 @@ bool CustomRF95::handleIdleISR()
MeshPacket *txp = txQueue.dequeuePtrFromISR(0);
if (txp)
startSend(txp);
else
{
else {
// Nothing to send, let's switch back to receive mode
setModeRx();
}

Wyświetl plik

@ -1,15 +1,14 @@
#pragma once
#include <RH_RF95.h>
#include <RHMesh.h>
#include "MemoryPool.h"
#include "mesh.pb.h"
#include "PointerQueue.h"
#include "MeshTypes.h"
#include "PointerQueue.h"
#include "mesh.pb.h"
#include <RHMesh.h>
#include <RH_RF95.h>
#define MAX_TX_QUEUE 16 // max number of packets which can be waiting for transmission
/**
* A version of the RF95 driver which is smart enough to manage packets via queues (no polling or blocking in user threads!)
*/
@ -22,7 +21,7 @@ class CustomRF95 : public RH_RF95
PointerQueue<MeshPacket> txQueue;
MeshPacket *sendingPacket; // The packet we are currently sending
public:
public:
/** pool is the pool we will alloc our rx packets from
* rxDest is where we will send any rx packets, it becomes receivers responsibility to return packet to the pool
*/
@ -30,7 +29,7 @@ public:
/**
* Return true if we think the board can go to sleep (i.e. our tx queue is empty, we are not sending or receiving)
*
*
* This method must be used before putting the CPU into deep or light sleep.
*/
bool canSleep();
@ -45,11 +44,12 @@ public:
bool init();
protected:
// After doing standard behavior, check to see if a new packet arrived or one was sent and start a new send or receive as necessary
protected:
// After doing standard behavior, check to see if a new packet arrived or one was sent and start a new send or receive as
// necessary
virtual void handleInterrupt();
private:
private:
/// Send a new packet - this low level call can be called from either ISR or userspace
void startSend(MeshPacket *txp);

Wyświetl plik

@ -35,7 +35,8 @@ void GPS::setup()
isConnected = ublox.begin(_serial_gps);
// try a second time, the ublox lib serial parsing is buggy?
if(!isConnected) isConnected = ublox.begin(_serial_gps);
if (!isConnected)
isConnected = ublox.begin(_serial_gps);
if (isConnected) {
DEBUG_MSG("Connected to GPS successfully, TXpin=%d\n", GPS_TX_PIN);

Wyświetl plik

@ -1,24 +1,24 @@
#pragma once
#include "PeriodicTask.h"
#include "Observer.h"
#include "sys/time.h"
#include "PeriodicTask.h"
#include "SparkFun_Ublox_Arduino_Library.h"
#include "sys/time.h"
/**
* A gps class that only reads from the GPS periodically (and FIXME - eventually keeps the gps powered down except when reading)
*
*
* When new data is available it will notify observers.
*/
class GPS : public PeriodicTask, public Observable
{
SFE_UBLOX_GPS ublox;
public:
public:
double latitude, longitude;
uint32_t altitude;
bool isConnected; // Do we have a GPS we are talking to
GPS();
/// Return time since 1970 in secs. Until we have a GPS lock we will be returning time based at zero
@ -45,9 +45,8 @@ public:
/// Restart our lock attempt - try to get and broadcast a GPS reading ASAP
void startLock();
private:
private:
void readFromRTC();
};
extern GPS gps;

Wyświetl plik

@ -7,11 +7,10 @@
/**
* A pool based allocator
*
*
* Eventually this routine will even be safe for ISR use...
*/
template <class T>
class MemoryPool
template <class T> class MemoryPool
{
PointerQueue<T> dead;
@ -19,7 +18,7 @@ class MemoryPool
size_t maxElements;
public:
public:
MemoryPool(size_t _maxElements) : dead(_maxElements), maxElements(_maxElements)
{
buf = new T[maxElements];
@ -29,10 +28,7 @@ public:
release(&buf[i]);
}
~MemoryPool()
{
delete[] buf;
}
~MemoryPool() { delete[] buf; }
/// Return a queable object which has been prefilled with zeros. Panic if no buffer is available
T *allocZeroed()
@ -43,7 +39,8 @@ public:
return p;
}
/// Return a queable object which has been prefilled with zeros - allow timeout to wait for available buffers (you probably don't want this version)
/// Return a queable object which has been prefilled with zeros - allow timeout to wait for available buffers (you probably
/// don't want this version)
T *allocZeroed(TickType_t maxWait)
{
T *p = dead.dequeuePtr(maxWait);
@ -67,13 +64,17 @@ public:
void release(T *p)
{
assert(dead.enqueue(p, 0));
assert(p >= buf && (p - buf) < maxElements); // sanity check to make sure a programmer didn't free something that didn't come from this pool
assert(p >= buf &&
(p - buf) <
maxElements); // sanity check to make sure a programmer didn't free something that didn't come from this pool
}
/// Return a buffer from an ISR, if higherPriWoken is set to true you have some work to do ;-)
void releaseFromISR(T *p, BaseType_t *higherPriWoken)
{
assert(dead.enqueueFromISR(p, higherPriWoken));
assert(p >= buf && (p - buf) < maxElements); // sanity check to make sure a programmer didn't free something that didn't come from this pool
assert(p >= buf &&
(p - buf) <
maxElements); // sanity check to make sure a programmer didn't free something that didn't come from this pool
}
};

Wyświetl plik

@ -1,21 +1,22 @@
#include "BluetoothUtil.h"
#include "MeshBluetoothService.h"
#include <esp_gatt_defs.h>
#include <BLE2902.h>
#include "BluetoothUtil.h"
#include <Arduino.h>
#include <BLE2902.h>
#include <assert.h>
#include <esp_gatt_defs.h>
#include "mesh.pb.h"
#include "MeshService.h"
#include "mesh-pb-constants.h"
#include "NodeDB.h"
#include "configuration.h"
#include "PowerFSM.h"
#include "CallbackCharacteristic.h"
#include "MeshService.h"
#include "NodeDB.h"
#include "PowerFSM.h"
#include "configuration.h"
#include "mesh-pb-constants.h"
#include "mesh.pb.h"
#include "GPS.h"
// This scratch buffer is used for various bluetooth reads/writes - but it is safe because only one bt operation can be in proccess at once
// This scratch buffer is used for various bluetooth reads/writes - but it is safe because only one bt operation can be in
// proccess at once
static uint8_t trBytes[_max(_max(_max(_max(ToRadio_size, RadioConfig_size), User_size), MyNodeInfo_size), FromRadio_size)];
class ProtobufCharacteristic : public CallbackCharacteristic
@ -23,11 +24,9 @@ class ProtobufCharacteristic : public CallbackCharacteristic
const pb_msgdesc_t *fields;
void *my_struct;
public:
public:
ProtobufCharacteristic(const char *uuid, uint32_t btprops, const pb_msgdesc_t *_fields, void *_my_struct)
: CallbackCharacteristic(uuid, btprops),
fields(_fields),
my_struct(_my_struct)
: CallbackCharacteristic(uuid, btprops), fields(_fields), my_struct(_my_struct)
{
setCallbacks(this);
}
@ -46,7 +45,7 @@ public:
writeToDest(c, my_struct);
}
protected:
protected:
/// like onWrite, but we provide an different destination to write to, for use by subclasses that
/// want to optionally ignore parts of writes.
/// returns true for success
@ -61,9 +60,10 @@ protected:
class NodeInfoCharacteristic : public BLECharacteristic, public BLEKeepAliveCallbacks
{
public:
public:
NodeInfoCharacteristic()
: BLECharacteristic("d31e02e0-c8ab-4d3f-9cc9-0b8466bdabe8", BLECharacteristic::PROPERTY_WRITE | BLECharacteristic::PROPERTY_READ)
: BLECharacteristic("d31e02e0-c8ab-4d3f-9cc9-0b8466bdabe8",
BLECharacteristic::PROPERTY_WRITE | BLECharacteristic::PROPERTY_READ)
{
setCallbacks(this);
}
@ -74,14 +74,12 @@ public:
const NodeInfo *info = nodeDB.readNextInfo();
if (info)
{
DEBUG_MSG("Sending nodeinfo: num=0x%x, lastseen=%u, id=%s, name=%s\n", info->num, info->position.time, info->user.id, info->user.long_name);
if (info) {
DEBUG_MSG("Sending nodeinfo: num=0x%x, lastseen=%u, id=%s, name=%s\n", info->num, info->position.time, info->user.id,
info->user.long_name);
size_t numbytes = pb_encode_to_bytes(trBytes, sizeof(trBytes), NodeInfo_fields, info);
c->setValue(trBytes, numbytes);
}
else
{
} else {
c->setValue(trBytes, 0); // Send an empty response
DEBUG_MSG("Done sending nodeinfos\n");
}
@ -95,13 +93,14 @@ public:
}
};
// wrap our protobuf version with something that forces the service to reload the config
class RadioCharacteristic : public ProtobufCharacteristic
{
public:
public:
RadioCharacteristic()
: ProtobufCharacteristic("b56786c8-839a-44a1-b98e-a1724c4a0262", BLECharacteristic::PROPERTY_WRITE | BLECharacteristic::PROPERTY_READ, RadioConfig_fields, &radioConfig)
: ProtobufCharacteristic("b56786c8-839a-44a1-b98e-a1724c4a0262",
BLECharacteristic::PROPERTY_WRITE | BLECharacteristic::PROPERTY_READ, RadioConfig_fields,
&radioConfig)
{
}
@ -125,33 +124,31 @@ public:
// wrap our protobuf version with something that forces the service to reload the owner
class OwnerCharacteristic : public ProtobufCharacteristic
{
public:
public:
OwnerCharacteristic()
: ProtobufCharacteristic("6ff1d8b6-e2de-41e3-8c0b-8fa384f64eb6", BLECharacteristic::PROPERTY_WRITE | BLECharacteristic::PROPERTY_READ, User_fields, &owner)
: ProtobufCharacteristic("6ff1d8b6-e2de-41e3-8c0b-8fa384f64eb6",
BLECharacteristic::PROPERTY_WRITE | BLECharacteristic::PROPERTY_READ, User_fields, &owner)
{
}
void onWrite(BLECharacteristic *c)
{
BLEKeepAliveCallbacks::onWrite(c); // NOTE: We do not call the standard ProtobufCharacteristic superclass, because we want custom write behavior
BLEKeepAliveCallbacks::onWrite(
c); // NOTE: We do not call the standard ProtobufCharacteristic superclass, because we want custom write behavior
static User o; // if the phone doesn't set ID we are careful to keep ours, we also always keep our macaddr
if (writeToDest(c, &o))
{
if (writeToDest(c, &o)) {
int changed = 0;
if (*o.long_name)
{
if (*o.long_name) {
changed |= strcmp(owner.long_name, o.long_name);
strcpy(owner.long_name, o.long_name);
}
if (*o.short_name)
{
if (*o.short_name) {
changed |= strcmp(owner.short_name, o.short_name);
strcpy(owner.short_name, o.short_name);
}
if (*o.id)
{
if (*o.id) {
changed |= strcmp(owner.id, o.id);
strcpy(owner.id, o.id);
}
@ -164,11 +161,8 @@ public:
class ToRadioCharacteristic : public CallbackCharacteristic
{
public:
ToRadioCharacteristic()
: CallbackCharacteristic("f75c76d2-129e-4dad-a1dd-7866124401e7", BLECharacteristic::PROPERTY_WRITE)
{
}
public:
ToRadioCharacteristic() : CallbackCharacteristic("f75c76d2-129e-4dad-a1dd-7866124401e7", BLECharacteristic::PROPERTY_WRITE) {}
void onWrite(BLECharacteristic *c)
{
@ -181,9 +175,8 @@ public:
class FromRadioCharacteristic : public CallbackCharacteristic
{
public:
FromRadioCharacteristic()
: CallbackCharacteristic("8ba2bcc2-ee02-4a55-a531-c525c5e454d5", BLECharacteristic::PROPERTY_READ)
public:
FromRadioCharacteristic() : CallbackCharacteristic("8ba2bcc2-ee02-4a55-a531-c525c5e454d5", BLECharacteristic::PROPERTY_READ)
{
}
@ -194,13 +187,10 @@ public:
// Someone is going to read our value as soon as this callback returns. So fill it with the next message in the queue
// or make empty if the queue is empty
if (!mp)
{
if (!mp) {
DEBUG_MSG("toPhone queue is empty\n");
c->setValue((uint8_t *)"", 0);
}
else
{
} else {
static FromRadio fRadio;
// Encapsulate as a FromRadio packet
@ -219,10 +209,11 @@ public:
class FromNumCharacteristic : public CallbackCharacteristic
{
public:
public:
FromNumCharacteristic()
: CallbackCharacteristic("ed9da18c-a800-4f66-a670-aa7547e34453",
BLECharacteristic::PROPERTY_WRITE | BLECharacteristic::PROPERTY_READ | BLECharacteristic::PROPERTY_NOTIFY)
: CallbackCharacteristic("ed9da18c-a800-4f66-a670-aa7547e34453", BLECharacteristic::PROPERTY_WRITE |
BLECharacteristic::PROPERTY_READ |
BLECharacteristic::PROPERTY_NOTIFY)
{
}
@ -240,8 +231,7 @@ FromNumCharacteristic *meshFromNumCharacteristic;
*/
void bluetoothNotifyFromNum(uint32_t newValue)
{
if (meshFromNumCharacteristic)
{
if (meshFromNumCharacteristic) {
// if bt not running ignore
meshFromNumCharacteristic->setValue(newValue);
meshFromNumCharacteristic->notify();
@ -265,7 +255,10 @@ BLEService *createMeshBluetoothService(BLEServer *server)
addWithDesc(service, new ToRadioCharacteristic, "toRadio");
addWithDesc(service, new FromRadioCharacteristic, "fromNum");
addWithDesc(service, new ProtobufCharacteristic("ea9f3f82-8dc4-4733-9452-1f6da28892a2", BLECharacteristic::PROPERTY_READ, MyNodeInfo_fields, &myNodeInfo), "myNode");
addWithDesc(service,
new ProtobufCharacteristic("ea9f3f82-8dc4-4733-9452-1f6da28892a2", BLECharacteristic::PROPERTY_READ,
MyNodeInfo_fields, &myNodeInfo),
"myNode");
addWithDesc(service, new RadioCharacteristic, "radio");
addWithDesc(service, new OwnerCharacteristic, "owner");
addWithDesc(service, new NodeInfoCharacteristic, "nodeinfo");
@ -276,8 +269,7 @@ BLEService *createMeshBluetoothService(BLEServer *server)
// We only add to advertisting once, because the ESP32 arduino code is dumb and that object never dies
static bool firstTime = true;
if (firstTime)
{
if (firstTime) {
firstTime = false;
server->getAdvertising()->addServiceUUID(service->getUUID());
}
@ -295,8 +287,6 @@ void stopMeshBluetoothService()
meshService->stop();
}
void destroyMeshBluetoothService()
{
assert(meshService);

Wyświetl plik

@ -1,10 +1,10 @@
#pragma once
#include <BLEService.h>
#include <BLEServer.h>
#include <Arduino.h>
#include <BLEServer.h>
#include <BLEService.h>
BLEService *createMeshBluetoothService(BLEServer* server);
BLEService *createMeshBluetoothService(BLEServer *server);
void destroyMeshBluetoothService();
/**

Wyświetl plik

@ -1,16 +1,17 @@
#include <SPI.h>
#include "RH_RF95.h"
#include <RHMesh.h>
#include <SPI.h>
#include <assert.h>
#include <pb_encode.h>
#include <pb_decode.h>
#include "MeshRadio.h"
#include "configuration.h"
#include "NodeDB.h"
#include "configuration.h"
#include <pb_decode.h>
#include <pb_encode.h>
/// 16 bytes of random PSK for our _public_ default channel that all devices power up on
static const uint8_t defaultpsk[] = {0xd4, 0xf1, 0xbb, 0x3a, 0x20, 0x29, 0x07, 0x59, 0xf0, 0xbc, 0xff, 0xab, 0xcf, 0x4e, 0x69, 0xbf};
static const uint8_t defaultpsk[] = {0xd4, 0xf1, 0xbb, 0x3a, 0x20, 0x29, 0x07, 0x59,
0xf0, 0xbc, 0xff, 0xab, 0xcf, 0x4e, 0x69, 0xbf};
/**
* ## LoRaWAN for North America
@ -19,126 +20,125 @@ LoRaWAN defines 64, 125 kHz channels from 902.3 to 914.9 MHz increments.
The maximum output power for North America is +30 dBM.
The band is from 902 to 928 MHz. It mentions channel number and its respective channel frequency. All the 13 channels are separated by 2.16 MHz with respect to the adjacent channels.
Channel zero starts at 903.08 MHz center frequency.
The band is from 902 to 928 MHz. It mentions channel number and its respective channel frequency. All the 13 channels are
separated by 2.16 MHz with respect to the adjacent channels. Channel zero starts at 903.08 MHz center frequency.
*/
/// Sometimes while debugging it is useful to set this false, to disable rf95 accesses
bool useHardware = true;
MeshRadio::MeshRadio(MemoryPool<MeshPacket> &_pool, PointerQueue<MeshPacket> &_rxDest)
: rf95(_pool, _rxDest),
manager(rf95)
MeshRadio::MeshRadio(MemoryPool<MeshPacket> &_pool, PointerQueue<MeshPacket> &_rxDest) : rf95(_pool, _rxDest), manager(rf95)
{
myNodeInfo.num_channels = NUM_CHANNELS;
myNodeInfo.num_channels = NUM_CHANNELS;
//radioConfig.modem_config = RadioConfig_ModemConfig_Bw125Cr45Sf128; // medium range and fast
//channelSettings.modem_config = ChannelSettings_ModemConfig_Bw500Cr45Sf128; // short range and fast, but wide bandwidth so incompatible radios can talk together
channelSettings.modem_config = ChannelSettings_ModemConfig_Bw125Cr48Sf4096; // slow and long range
// radioConfig.modem_config = RadioConfig_ModemConfig_Bw125Cr45Sf128; // medium range and fast
// channelSettings.modem_config = ChannelSettings_ModemConfig_Bw500Cr45Sf128; // short range and fast, but wide bandwidth so
// incompatible radios can talk together
channelSettings.modem_config = ChannelSettings_ModemConfig_Bw125Cr48Sf4096; // slow and long range
channelSettings.tx_power = 23;
memcpy(&channelSettings.psk, &defaultpsk, sizeof(channelSettings.psk));
strcpy(channelSettings.name, "Default");
// Can't print strings this early - serial not setup yet
// DEBUG_MSG("Set meshradio defaults name=%s\n", channelSettings.name);
channelSettings.tx_power = 23;
memcpy(&channelSettings.psk, &defaultpsk, sizeof(channelSettings.psk));
strcpy(channelSettings.name, "Default");
// Can't print strings this early - serial not setup yet
// DEBUG_MSG("Set meshradio defaults name=%s\n", channelSettings.name);
}
bool MeshRadio::init()
{
if (!useHardware)
return true;
if (!useHardware)
return true;
DEBUG_MSG("Starting meshradio init...\n");
DEBUG_MSG("Starting meshradio init...\n");
#ifdef RESET_GPIO
pinMode(RESET_GPIO, OUTPUT); // Deassert reset
digitalWrite(RESET_GPIO, HIGH);
pinMode(RESET_GPIO, OUTPUT); // Deassert reset
digitalWrite(RESET_GPIO, HIGH);
// pulse reset
digitalWrite(RESET_GPIO, LOW);
delay(10);
digitalWrite(RESET_GPIO, HIGH);
delay(10);
// pulse reset
digitalWrite(RESET_GPIO, LOW);
delay(10);
digitalWrite(RESET_GPIO, HIGH);
delay(10);
#endif
manager.setThisAddress(nodeDB.getNodeNum()); // Note: we must do this here, because the nodenum isn't inited at constructor time.
manager.setThisAddress(
nodeDB.getNodeNum()); // Note: we must do this here, because the nodenum isn't inited at constructor time.
if (!manager.init())
{
DEBUG_MSG("LoRa radio init failed\n");
DEBUG_MSG("Uncomment '#define SERIAL_DEBUG' in RH_RF95.cpp for detailed debug info\n");
return false;
}
if (!manager.init()) {
DEBUG_MSG("LoRa radio init failed\n");
DEBUG_MSG("Uncomment '#define SERIAL_DEBUG' in RH_RF95.cpp for detailed debug info\n");
return false;
}
// not needed - defaults on
// rf95.setPayloadCRC(true);
// not needed - defaults on
// rf95.setPayloadCRC(true);
reloadConfig();
reloadConfig();
return true;
return true;
}
/** hash a string into an integer
*
*
* djb2 by Dan Bernstein.
* http://www.cse.yorku.ca/~oz/hash.html
*/
unsigned long hash(char *str)
{
unsigned long hash = 5381;
int c;
unsigned long hash = 5381;
int c;
while ((c = *str++) != 0)
hash = ((hash << 5) + hash) + (unsigned char)c; /* hash * 33 + c */
while ((c = *str++) != 0)
hash = ((hash << 5) + hash) + (unsigned char)c; /* hash * 33 + c */
return hash;
return hash;
}
void MeshRadio::reloadConfig()
{
rf95.setModeIdle(); // Need to be idle before doing init
rf95.setModeIdle(); // Need to be idle before doing init
// Set up default configuration
// No Sync Words in LORA mode.
rf95.setModemConfig((RH_RF95::ModemConfigChoice)channelSettings.modem_config); // Radio default
// setModemConfig(Bw125Cr48Sf4096); // slow and reliable?
// rf95.setPreambleLength(8); // Default is 8
// Set up default configuration
// No Sync Words in LORA mode.
rf95.setModemConfig(
(RH_RF95::ModemConfigChoice)channelSettings.modem_config); // Radio default
// setModemConfig(Bw125Cr48Sf4096); // slow and reliable?
// rf95.setPreambleLength(8); // Default is 8
// Defaults after init are 434.0MHz, modulation GFSK_Rb250Fd250, +13dbM
int channel_num = hash(channelSettings.name) % NUM_CHANNELS;
float center_freq = CH0 + CH_SPACING * channel_num;
if (!rf95.setFrequency(center_freq))
{
DEBUG_MSG("setFrequency failed\n");
assert(0); // fixme panic
}
// Defaults after init are 434.0MHz, modulation GFSK_Rb250Fd250, +13dbM
int channel_num = hash(channelSettings.name) % NUM_CHANNELS;
float center_freq = CH0 + CH_SPACING * channel_num;
if (!rf95.setFrequency(center_freq)) {
DEBUG_MSG("setFrequency failed\n");
assert(0); // fixme panic
}
// Defaults after init are 434.0MHz, 13dBm, Bw = 125 kHz, Cr = 4/5, Sf = 128chips/symbol, CRC on
// Defaults after init are 434.0MHz, 13dBm, Bw = 125 kHz, Cr = 4/5, Sf = 128chips/symbol, CRC on
// The default transmitter power is 13dBm, using PA_BOOST.
// If you are using RFM95/96/97/98 modules which uses the PA_BOOST transmitter pin, then
// you can set transmitter powers from 5 to 23 dBm:
// FIXME - can we do this? It seems to be in the Heltec board.
rf95.setTxPower(channelSettings.tx_power, false);
// The default transmitter power is 13dBm, using PA_BOOST.
// If you are using RFM95/96/97/98 modules which uses the PA_BOOST transmitter pin, then
// you can set transmitter powers from 5 to 23 dBm:
// FIXME - can we do this? It seems to be in the Heltec board.
rf95.setTxPower(channelSettings.tx_power, false);
DEBUG_MSG("Set radio: name=%s. config=%u, ch=%d, txpower=%d\n", channelSettings.name, channelSettings.modem_config, channel_num, channelSettings.tx_power);
DEBUG_MSG("Set radio: name=%s. config=%u, ch=%d, txpower=%d\n", channelSettings.name, channelSettings.modem_config,
channel_num, channelSettings.tx_power);
// Done with init tell radio to start receiving
rf95.setModeRx();
// Done with init tell radio to start receiving
rf95.setModeRx();
}
ErrorCode MeshRadio::send(MeshPacket *p)
{
if (useHardware)
return rf95.send(p);
else
{
rf95.pool.release(p);
return ERRNO_OK;
}
if (useHardware)
return rf95.send(p);
else {
rf95.pool.release(p);
return ERRNO_OK;
}
}
void MeshRadio::loop()
{
// Currently does nothing, since we do it all in ISRs now
// Currently does nothing, since we do it all in ISRs now
}

Wyświetl plik

@ -1,36 +1,36 @@
#pragma once
#include "CustomRF95.h"
#include <RHMesh.h>
#include "MemoryPool.h"
#include "mesh.pb.h"
#include "PointerQueue.h"
#include "MeshTypes.h"
#include "PointerQueue.h"
#include "configuration.h"
#include "mesh.pb.h"
#include <RHMesh.h>
// US channel settings
#define CH0_US 903.08f // MHz
#define CH_SPACING_US 2.16f // MHz
#define CH0_US 903.08f // MHz
#define CH_SPACING_US 2.16f // MHz
#define NUM_CHANNELS_US 13
// EU433 channel settings
#define CH0_EU433 433.175f // MHz
#define CH_SPACING_EU433 0.2f // MHz
#define CH0_EU433 433.175f // MHz
#define CH_SPACING_EU433 0.2f // MHz
#define NUM_CHANNELS_EU433 8
// EU865 channel settings
#define CH0_EU865 865.2f // MHz
#define CH_SPACING_EU865 0.3f // MHz
#define CH0_EU865 865.2f // MHz
#define CH_SPACING_EU865 0.3f // MHz
#define NUM_CHANNELS_EU865 10
// CN channel settings
#define CH0_CN 470.0f // MHz
#define CH_SPACING_CN 2.0f // MHz FIXME, this is just a guess for 470-510
#define CH0_CN 470.0f // MHz
#define CH_SPACING_CN 2.0f // MHz FIXME, this is just a guess for 470-510
#define NUM_CHANNELS_CN 20
// JP channel settings
#define CH0_JP 920.0f // MHz
#define CH_SPACING_JP 0.5f // MHz FIXME, this is just a guess for 920-925
#define CH0_JP 920.0f // MHz
#define CH_SPACING_JP 0.5f // MHz FIXME, this is just a guess for 920-925
#define NUM_CHANNELS_JP 10
// FIXME add defs for other regions and use them here
@ -56,15 +56,16 @@
#define NUM_CHANNELS NUM_CHANNELS_JP
#else
#error "HW_VERSION not set"
#endif
#endif
/**
* A raw low level interface to our mesh. Only understands nodenums and bytes (not protobufs or node ids)
*/
class MeshRadio {
public:
CustomRF95 rf95; // the raw radio interface - for now I'm leaving public - because this class is shrinking to be almost nothing
class MeshRadio
{
public:
CustomRF95
rf95; // the raw radio interface - for now I'm leaving public - because this class is shrinking to be almost nothing
/** pool is the pool we will alloc our rx packets from
* rxDest is where we will send any rx packets, it becomes receivers responsibility to return packet to the pool
@ -85,8 +86,7 @@ public:
/// The radioConfig object just changed, call this to force the hw to change to the new settings
void reloadConfig();
private:
private:
// RHDatagram manager;
// RHReliableDatagram manager; // don't use mesh yet
RHMesh manager;
@ -98,5 +98,3 @@ private:
/// enqueue a received packet in rxDest
void handleReceive(MeshPacket *p);
};

Wyświetl plik

@ -2,37 +2,41 @@
#include <Arduino.h>
#include <assert.h>
#include "main.h"
#include "mesh-pb-constants.h"
#include "MeshService.h"
#include "MeshBluetoothService.h"
#include "NodeDB.h"
#include "GPS.h"
#include "MeshBluetoothService.h"
#include "MeshService.h"
#include "NodeDB.h"
#include "Periodic.h"
#include "PowerFSM.h"
#include "main.h"
#include "mesh-pb-constants.h"
/*
receivedPacketQueue - this is a queue of messages we've received from the mesh, which we are keeping to deliver to the phone.
It is implemented with a FreeRTos queue (wrapped with a little RTQueue class) of pointers to MeshPacket protobufs (which were alloced with new).
After a packet ptr is removed from the queue and processed it should be deleted. (eventually we should move sent packets into a 'sentToPhone' queue
of packets we can delete just as soon as we are sure the phone has acked those packets - when the phone writes to FromNum)
It is implemented with a FreeRTos queue (wrapped with a little RTQueue class) of pointers to MeshPacket protobufs (which were
alloced with new). After a packet ptr is removed from the queue and processed it should be deleted. (eventually we should move
sent packets into a 'sentToPhone' queue of packets we can delete just as soon as we are sure the phone has acked those packets -
when the phone writes to FromNum)
mesh - an instance of Mesh class. Which manages the interface to the mesh radio library, reception of packets from other nodes, arbitrating to select
a node number and keeping the current nodedb.
mesh - an instance of Mesh class. Which manages the interface to the mesh radio library, reception of packets from other nodes,
arbitrating to select a node number and keeping the current nodedb.
*/
/* Broadcast when a newly powered mesh node wants to find a node num it can use
The algoritm is as follows:
* when a node starts up, it broadcasts their user and the normal flow is for all other nodes to reply with their User as well (so the new node can build its node db)
* If a node ever receives a User (not just the first broadcast) message where the sender node number equals our node number, that indicates a collision has occurred and the following steps should happen:
* when a node starts up, it broadcasts their user and the normal flow is for all other nodes to reply with their User as well (so
the new node can build its node db)
* If a node ever receives a User (not just the first broadcast) message where the sender node number equals our node number, that
indicates a collision has occurred and the following steps should happen:
If the receiving node (that was already in the mesh)'s macaddr is LOWER than the new User who just tried to sign in: it gets to keep its nodenum. We send a broadcast message
of OUR User (we use a broadcast so that the other node can receive our message, considering we have the same id - it also serves to let observers correct their nodedb) - this case is rare so it should be okay.
If the receiving node (that was already in the mesh)'s macaddr is LOWER than the new User who just tried to sign in: it gets to
keep its nodenum. We send a broadcast message of OUR User (we use a broadcast so that the other node can receive our message,
considering we have the same id - it also serves to let observers correct their nodedb) - this case is rare so it should be okay.
If any node receives a User where the macaddr is GTE than their local macaddr, they have been vetoed and should pick a new random nodenum (filtering against whatever it knows about the nodedb) and
rebroadcast their User.
If any node receives a User where the macaddr is GTE than their local macaddr, they have been vetoed and should pick a new random
nodenum (filtering against whatever it knows about the nodedb) and rebroadcast their User.
FIXME in the initial proof of concept we just skip the entire want/deny flow and just hand pick node numbers at first.
*/
@ -40,15 +44,15 @@ FIXME in the initial proof of concept we just skip the entire want/deny flow and
MeshService service;
// I think this is right, one packet for each of the three fifos + one packet being currently assembled for TX or RX
#define MAX_PACKETS (MAX_RX_TOPHONE + MAX_RX_FROMRADIO + MAX_TX_QUEUE + 2) // max number of packets which can be in flight (either queued from reception or queued for sending)
#define MAX_PACKETS \
(MAX_RX_TOPHONE + MAX_RX_FROMRADIO + MAX_TX_QUEUE + \
2) // max number of packets which can be in flight (either queued from reception or queued for sending)
#define MAX_RX_FROMRADIO 4 // max number of packets destined to our queue, we dispatch packets quickly so it doesn't need to be big
#define MAX_RX_FROMRADIO \
4 // max number of packets destined to our queue, we dispatch packets quickly so it doesn't need to be big
MeshService::MeshService()
: packetPool(MAX_PACKETS),
toPhoneQueue(MAX_RX_TOPHONE),
fromRadioQueue(MAX_RX_FROMRADIO),
fromNum(0),
: packetPool(MAX_PACKETS), toPhoneQueue(MAX_RX_TOPHONE), fromRadioQueue(MAX_RX_FROMRADIO), fromNum(0),
radio(packetPool, fromRadioQueue)
{
// assert(MAX_RX_TOPHONE == 32); // FIXME, delete this, just checking my clever macro
@ -88,29 +92,25 @@ MeshPacket *MeshService::handleFromRadioUser(MeshPacket *mp)
// we win if we have a lower macaddr
bool weWin = memcmp(&owner.macaddr, &mp->payload.variant.user.macaddr, sizeof(owner.macaddr)) < 0;
if (isCollision)
{
if (weWin)
{
if (isCollision) {
if (weWin) {
DEBUG_MSG("NOTE! Received a nodenum collision and we are vetoing\n");
packetPool.release(mp); // discard it
mp = NULL;
sendOurOwner(); // send our owner as a _broadcast_ because that other guy is mistakenly using our nodenum
}
else
{
} else {
// we lost, we need to try for a new nodenum!
DEBUG_MSG("NOTE! Received a nodenum collision we lost, so picking a new nodenum\n");
nodeDB.updateFrom(*mp); // update the DB early - before trying to repick (so we don't select the same node number again)
nodeDB.updateFrom(
*mp); // update the DB early - before trying to repick (so we don't select the same node number again)
nodeDB.pickNewNodeNum();
sendOurOwner(); // broadcast our new attempt at a node number
}
}
else if (wasBroadcast)
{
// If we haven't yet abandoned the packet and it was a broadcast, reply (just to them) with our User record so they can build their DB
} else if (wasBroadcast) {
// If we haven't yet abandoned the packet and it was a broadcast, reply (just to them) with our User record so they can
// build their DB
// Someone just sent us a User, reply with our Owner
DEBUG_MSG("Received broadcast Owner from 0x%x, replying with our owner\n", mp->from);
@ -126,12 +126,10 @@ MeshPacket *MeshService::handleFromRadioUser(MeshPacket *mp)
void MeshService::handleIncomingPosition(MeshPacket *mp)
{
if (mp->has_payload && mp->payload.which_variant == SubPacket_position_tag)
{
if (mp->has_payload && mp->payload.which_variant == SubPacket_position_tag) {
DEBUG_MSG("handled incoming position time=%u\n", mp->payload.variant.position.time);
if (mp->payload.variant.position.time)
{
if (mp->payload.variant.position.time) {
struct timeval tv;
uint32_t secs = mp->payload.variant.position.time;
@ -153,21 +151,18 @@ void MeshService::handleFromRadio(MeshPacket *mp)
if (!myNodeInfo.has_gps)
handleIncomingPosition(mp);
if (mp->has_payload && mp->payload.which_variant == SubPacket_user_tag)
{
if (mp->has_payload && mp->payload.which_variant == SubPacket_user_tag) {
mp = handleFromRadioUser(mp);
}
// If we veto a received User packet, we don't put it into the DB or forward it to the phone (to prevent confusing it)
if (mp)
{
if (mp) {
DEBUG_MSG("Forwarding to phone, from=0x%x, rx_time=%u\n", mp->from, mp->rx_time);
nodeDB.updateFrom(*mp); // update our DB state based off sniffing every RX packet from the radio
fromNum++;
if (toPhoneQueue.numFree() == 0)
{
if (toPhoneQueue.numFree() == 0) {
DEBUG_MSG("NOTE: tophone queue is full, discarding oldest\n");
MeshPacket *d = toPhoneQueue.dequeuePtr(0);
if (d)
@ -177,8 +172,7 @@ void MeshService::handleFromRadio(MeshPacket *mp)
if (mp->payload.want_response)
sendNetworkPing(mp->from);
}
else
} else
DEBUG_MSG("Dropping vetoed User message\n");
}
@ -186,8 +180,7 @@ void MeshService::handleFromRadio()
{
MeshPacket *mp;
uint32_t oldFromNum = fromNum;
while ((mp = fromRadioQueue.dequeuePtr(0)) != NULL)
{
while ((mp = fromRadioQueue.dequeuePtr(0)) != NULL) {
handleFromRadio(mp);
}
if (oldFromNum != fromNum) // We don't want to generate extra notifies for multiple new packets
@ -227,23 +220,20 @@ void MeshService::handleToRadio(std::string s)
{
static ToRadio r; // this is a static scratch object, any data must be copied elsewhere before returning
if (pb_decode_from_bytes((const uint8_t *)s.c_str(), s.length(), ToRadio_fields, &r))
{
switch (r.which_variant)
{
case ToRadio_packet_tag:
{
if (pb_decode_from_bytes((const uint8_t *)s.c_str(), s.length(), ToRadio_fields, &r)) {
switch (r.which_variant) {
case ToRadio_packet_tag: {
// If our phone is sending a position, see if we can use it to set our RTC
handleIncomingPosition(&r.variant.packet); // If it is a position packet, perhaps set our clock
r.variant.packet.rx_time = gps.getValidTime(); // Record the time the packet arrived from the phone (so we update our nodedb for the local node)
r.variant.packet.rx_time = gps.getValidTime(); // Record the time the packet arrived from the phone (so we update our
// nodedb for the local node)
// Send the packet into the mesh
sendToMesh(packetPool.allocCopy(r.variant.packet));
bool loopback = false; // if true send any packet the phone sends back itself (for testing)
if (loopback)
{
if (loopback) {
MeshPacket *mp = packetPool.allocCopy(r.variant.packet);
handleFromRadio(mp);
bluetoothNotifyFromNum(fromNum); // tell the phone a new packet arrived
@ -254,8 +244,7 @@ void MeshService::handleToRadio(std::string s)
DEBUG_MSG("Error: unexpected ToRadio variant\n");
break;
}
}
else {
} else {
DEBUG_MSG("Error: ignoring malformed toradio\n");
}
}
@ -264,10 +253,10 @@ void MeshService::sendToMesh(MeshPacket *p)
{
nodeDB.updateFrom(*p); // update our local DB for this packet (because phone might have sent position packets etc...)
// Strip out any time information before sending packets to other nodes - to keep the wire size small (and because other nodes shouldn't trust it anyways)
// Note: for now, we allow a device with a local GPS to include the time, so that gpsless devices can get time.
if (p->has_payload && p->payload.which_variant == SubPacket_position_tag)
{
// Strip out any time information before sending packets to other nodes - to keep the wire size small (and because other
// nodes shouldn't trust it anyways) Note: for now, we allow a device with a local GPS to include the time, so that gpsless
// devices can get time.
if (p->has_payload && p->payload.which_variant == SubPacket_position_tag) {
if (!myNodeInfo.has_gps)
p->payload.variant.position.time = 0;
else
@ -277,8 +266,7 @@ void MeshService::sendToMesh(MeshPacket *p)
// If the phone sent a packet just to us, don't send it out into the network
if (p->to == nodeDB.getNodeNum())
DEBUG_MSG("Dropping locally processed message\n");
else
{
else {
// Note: We might return !OK if our fifo was full, at that point the only option we have is to drop it
if (radio.send(p) != ERRNO_OK)
DEBUG_MSG("Dropped packet because send queue was full!\n");
@ -319,7 +307,8 @@ void MeshService::sendOurPosition(NodeNum dest)
p->to = dest;
p->payload.which_variant = SubPacket_position_tag;
p->payload.variant.position = node->position;
p->payload.variant.position.time = gps.getValidTime(); // This nodedb timestamp might be stale, so update it if our clock is valid.
p->payload.variant.position.time =
gps.getValidTime(); // This nodedb timestamp might be stale, so update it if our clock is valid.
sendToMesh(p);
}
@ -331,7 +320,7 @@ void MeshService::onGPSChanged()
Position &pos = p->payload.variant.position;
// !zero or !zero lat/long means valid
if(gps.latitude != 0 || gps.longitude != 0) {
if (gps.latitude != 0 || gps.longitude != 0) {
if (gps.altitude != 0)
pos.altitude = gps.altitude;
pos.latitude = gps.latitude;
@ -342,15 +331,12 @@ void MeshService::onGPSChanged()
// We limit our GPS broadcasts to a max rate
static uint32_t lastGpsSend;
uint32_t now = millis();
if (lastGpsSend == 0 || now - lastGpsSend > radioConfig.preferences.position_broadcast_secs * 1000)
{
if (lastGpsSend == 0 || now - lastGpsSend > radioConfig.preferences.position_broadcast_secs * 1000) {
lastGpsSend = now;
DEBUG_MSG("Sending position to mesh\n");
sendToMesh(p);
}
else
{
} else {
// We don't need to send this packet to anyone else, but it still serves as a nice uniform way to update our local state
nodeDB.updateFrom(*p);

Wyświetl plik

@ -3,17 +3,17 @@
#include <Arduino.h>
#include <assert.h>
#include "mesh.pb.h"
#include "MeshRadio.h"
#include "PointerQueue.h"
#include "MemoryPool.h"
#include "MeshRadio.h"
#include "Observer.h"
#include "PointerQueue.h"
#include "mesh.pb.h"
/**
* Top level app for this service. keeps the mesh, the radio config and the queue of received packets.
*
*
*/
class MeshService: private Observer
class MeshService : private Observer
{
MemoryPool<MeshPacket> packetPool;
@ -30,14 +30,13 @@ class MeshService: private Observer
/// The current nonce for the newest packet which has been queued for the phone
uint32_t fromNum;
public:
public:
MeshRadio radio;
MeshService();
void init();
/// Do idle processing (mostly processing messages which have been queued from the radio)
void loop();
@ -56,21 +55,24 @@ public:
/// The owner User record just got updated, update our node DB and broadcast the info into the mesh
void reloadOwner() { sendOurOwner(); }
/// Allocate and return a meshpacket which defaults as send to broadcast from the current node.
MeshPacket *allocForSending();
/// Called when the user wakes up our GUI, normally sends our latest location to the mesh (if we have it), otherwise at least sends our owner
/// Called when the user wakes up our GUI, normally sends our latest location to the mesh (if we have it), otherwise at least
/// sends our owner
void sendNetworkPing(NodeNum dest = NODENUM_BROADCAST);
/// Send our owner info to a particular node
/// Send our owner info to a particular node
void sendOurOwner(NodeNum dest = NODENUM_BROADCAST);
private:
private:
/// Broadcasts our last known position
void sendOurPosition(NodeNum dest = NODENUM_BROADCAST);
/// Send a packet into the mesh - note p must have been allocated from packetPool. We will return it to that pool after sending.
/// This is the ONLY function you should use for sending messages into the mesh, because it also updates the nodedb cache
/// Send a packet into the mesh - note p must have been allocated from packetPool. We will return it to that pool after
/// sending. This is the ONLY function you should use for sending messages into the mesh, because it also updates the nodedb
/// cache
void sendToMesh(MeshPacket *p);
/// Called when our gps position has changed - updates nodedb and sends Location message out into the mesh
@ -92,4 +94,3 @@ private:
};
extern MeshService service;

Wyświetl plik

@ -1,6 +1,6 @@
#pragma once
// low level types
// low level types
#include <Arduino.h>

Wyświetl plik

@ -5,13 +5,13 @@
#include "FS.h"
#include "SPIFFS.h"
#include <pb_encode.h>
#include <pb_decode.h>
#include "GPS.h"
#include "NodeDB.h"
#include "PowerFSM.h"
#include "configuration.h"
#include "mesh-pb-constants.h"
#include "NodeDB.h"
#include "GPS.h"
#include "PowerFSM.h"
#include <pb_decode.h>
#include <pb_encode.h>
NodeDB nodeDB;
@ -22,7 +22,7 @@ RadioConfig &radioConfig = devicestate.radio;
ChannelSettings &channelSettings = radioConfig.channel_settings;
/*
DeviceState versions used to be defined in the .proto file but really only this function cares. So changed to a
DeviceState versions used to be defined in the .proto file but really only this function cares. So changed to a
#define here.
*/
@ -31,8 +31,8 @@ DeviceState versions used to be defined in the .proto file but really only this
#define FS SPIFFS
/**
*
/**
*
* Normally userids are unique and start with +country code to look like Signal phone numbers.
* But there are some special ids used when we haven't yet been configured by a user. In that case
* we use !macaddr (no colons).
@ -41,9 +41,7 @@ User &owner = devicestate.owner;
static uint8_t ourMacAddr[6];
NodeDB::NodeDB() : nodes(devicestate.node_db), numNodes(&devicestate.node_db_count)
{
}
NodeDB::NodeDB() : nodes(devicestate.node_db), numNodes(&devicestate.node_db_count) {}
void NodeDB::init()
{
@ -78,8 +76,8 @@ void NodeDB::init()
// Init our blank owner info to reasonable defaults
esp_efuse_mac_get_default(ourMacAddr);
sprintf(owner.id, "!%02x%02x%02x%02x%02x%02x", ourMacAddr[0],
ourMacAddr[1], ourMacAddr[2], ourMacAddr[3], ourMacAddr[4], ourMacAddr[5]);
sprintf(owner.id, "!%02x%02x%02x%02x%02x%02x", ourMacAddr[0], ourMacAddr[1], ourMacAddr[2], ourMacAddr[3], ourMacAddr[4],
ourMacAddr[5]);
memcpy(owner.macaddr, ourMacAddr, sizeof(owner.macaddr));
// make each node start with ad different random seed (but okay that the sequence is the same each boot)
@ -112,7 +110,7 @@ void NodeDB::init()
#define NUM_RESERVED 4
/**
* get our starting (provisional) nodenum from flash.
* get our starting (provisional) nodenum from flash.
*/
void NodeDB::pickNewNodeNum()
{
@ -122,8 +120,7 @@ void NodeDB::pickNewNodeNum()
r = NUM_RESERVED; // don't pick a reserved node number
NodeInfo *found;
while ((found = getNode(r)) && memcmp(found->user.macaddr, owner.macaddr, sizeof(owner.macaddr)))
{
while ((found = getNode(r)) && memcmp(found->user.macaddr, owner.macaddr, sizeof(owner.macaddr))) {
NodeNum n = random(NUM_RESERVED, NODENUM_BROADCAST); // try a new random choice
DEBUG_MSG("NOTE! Our desired nodenum 0x%x is in use, so trying for 0x%x\n", r, n);
r = n;
@ -140,36 +137,29 @@ void NodeDB::loadFromDisk()
static DeviceState scratch;
File f = FS.open(preffile);
if (f)
{
if (f) {
DEBUG_MSG("Loading saved preferences\n");
pb_istream_t stream = {&readcb, &f, DeviceState_size};
//DEBUG_MSG("Preload channel name=%s\n", channelSettings.name);
// DEBUG_MSG("Preload channel name=%s\n", channelSettings.name);
memset(&scratch, 0, sizeof(scratch));
if (!pb_decode(&stream, DeviceState_fields, &scratch))
{
if (!pb_decode(&stream, DeviceState_fields, &scratch)) {
DEBUG_MSG("Error: can't decode protobuf %s\n", PB_GET_ERROR(&stream));
// FIXME - report failure to phone
}
else
{
} else {
if (scratch.version < DEVICESTATE_MIN_VER)
DEBUG_MSG("Warn: devicestate is old, discarding\n");
else
{
else {
DEBUG_MSG("Loaded saved preferences version %d\n", scratch.version);
devicestate = scratch;
}
//DEBUG_MSG("Postload channel name=%s\n", channelSettings.name);
// DEBUG_MSG("Postload channel name=%s\n", channelSettings.name);
}
f.close();
}
else
{
} else {
DEBUG_MSG("No saved preferences found\n");
}
}
@ -177,17 +167,15 @@ void NodeDB::loadFromDisk()
void NodeDB::saveToDisk()
{
File f = FS.open(preftmp, "w");
if (f)
{
if (f) {
DEBUG_MSG("Writing preferences\n");
pb_ostream_t stream = {&writecb, &f, SIZE_MAX, 0};
//DEBUG_MSG("Presave channel name=%s\n", channelSettings.name);
// DEBUG_MSG("Presave channel name=%s\n", channelSettings.name);
devicestate.version = DEVICESTATE_CUR_VER;
if (!pb_encode(&stream, DeviceState_fields, &devicestate))
{
if (!pb_encode(&stream, DeviceState_fields, &devicestate)) {
DEBUG_MSG("Error: can't write protobuf %s\n", PB_GET_ERROR(&stream));
// FIXME - report failure to phone
}
@ -199,9 +187,7 @@ void NodeDB::saveToDisk()
DEBUG_MSG("Warning: Can't remove old pref file\n");
if (!FS.rename(preftmp, preffile))
DEBUG_MSG("Error: can't rename new pref file\n");
}
else
{
} else {
DEBUG_MSG("ERROR: can't write prefs\n"); // FIXME report to app
}
}
@ -245,8 +231,7 @@ size_t NodeDB::getNumOnlineNodes()
/// we updateGUI and updateGUIforNode if we think our this change is big enough for a redraw
void NodeDB::updateFrom(const MeshPacket &mp)
{
if (mp.has_payload)
{
if (mp.has_payload) {
const SubPacket &p = mp.payload;
DEBUG_MSG("Update DB node 0x%x for variant %d, rx_time=%u\n", mp.from, p.which_variant, mp.rx_time);
@ -256,16 +241,13 @@ void NodeDB::updateFrom(const MeshPacket &mp)
if (oldNumNodes != *numNodes)
updateGUI = true; // we just created a nodeinfo
if (mp.rx_time)
{ // if the packet has a valid timestamp use it to update our last_seen
if (mp.rx_time) { // if the packet has a valid timestamp use it to update our last_seen
info->has_position = true; // at least the time is valid
info->position.time = mp.rx_time;
}
switch (p.which_variant)
{
case SubPacket_position_tag:
{
switch (p.which_variant) {
case SubPacket_position_tag: {
// we carefully preserve the old time, because we always trust our local timestamps more
uint32_t oldtime = info->position.time;
info->position = p.variant.position;
@ -275,14 +257,12 @@ void NodeDB::updateFrom(const MeshPacket &mp)
break;
}
case SubPacket_data_tag:
{
case SubPacket_data_tag: {
// Keep a copy of the most recent text message.
if (p.variant.data.typ == Data_Type_CLEAR_TEXT)
{
DEBUG_MSG("Received text msg from=0%0x, msg=%.*s\n", mp.from, p.variant.data.payload.size, p.variant.data.payload.bytes);
if (mp.to == NODENUM_BROADCAST || mp.to == nodeDB.getNodeNum())
{
if (p.variant.data.typ == Data_Type_CLEAR_TEXT) {
DEBUG_MSG("Received text msg from=0%0x, msg=%.*s\n", mp.from, p.variant.data.payload.size,
p.variant.data.payload.bytes);
if (mp.to == NODENUM_BROADCAST || mp.to == nodeDB.getNodeNum()) {
// We only store/display messages destined for us.
devicestate.rx_text_message = mp;
devicestate.has_rx_text_message = true;
@ -293,18 +273,17 @@ void NodeDB::updateFrom(const MeshPacket &mp)
break;
}
case SubPacket_user_tag:
{
case SubPacket_user_tag: {
DEBUG_MSG("old user %s/%s/%s\n", info->user.id, info->user.long_name, info->user.short_name);
bool changed = memcmp(&info->user, &p.variant.user, sizeof(info->user)); // Both of these blocks start as filled with zero so I think this is okay
bool changed = memcmp(&info->user, &p.variant.user,
sizeof(info->user)); // Both of these blocks start as filled with zero so I think this is okay
info->user = p.variant.user;
DEBUG_MSG("updating changed=%d user %s/%s/%s\n", changed, info->user.id, info->user.long_name, info->user.short_name);
info->has_user = true;
if (changed)
{
if (changed) {
updateGUIforNode = info;
powerFSM.trigger(EVENT_NODEDB_UPDATED);
@ -337,8 +316,7 @@ NodeInfo *NodeDB::getOrCreateNode(NodeNum n)
{
NodeInfo *info = getNode(n);
if (!info)
{
if (!info) {
// add the node
assert(*numNodes < MAX_NUM_NODES);
info = &nodes[(*numNodes)++];

Wyświetl plik

@ -3,8 +3,8 @@
#include <Arduino.h>
#include <assert.h>
#include "mesh-pb-constants.h"
#include "MeshTypes.h"
#include "mesh-pb-constants.h"
extern DeviceState devicestate;
extern MyNodeInfo &myNodeInfo;
@ -28,10 +28,10 @@ class NodeDB
int readPointer = 0;
public:
bool updateGUI = false; // we think the gui should definitely be redrawn, screen will clear this once handled
public:
bool updateGUI = false; // we think the gui should definitely be redrawn, screen will clear this once handled
NodeInfo *updateGUIforNode = NULL; // if currently showing this node, we think you should update the GUI
bool updateTextMessage = false; // if true, the GUI should show a new text message
bool updateTextMessage = false; // if true, the GUI should show a new text message
/// don't do mesh based algoritm for node id assignment (initially)
/// instead just store in flash - possibly even in the initial alpha release do this hack
@ -56,10 +56,11 @@ public:
// bool handleWantNodeNum(NodeNum n);
/* void handleDenyNodeNum(NodeNum FIXME read mesh proto docs, perhaps picking a random node num is not a great idea
and instead we should use a special 'im unconfigured node number' and include our desired node number in the wantnum message. the
unconfigured node num would only be used while initially joining the mesh so low odds of conflicting (especially if we randomly select
from a small number of nodenums which can be used temporarily for this operation). figure out what the lower level
mesh sw does if it does conflict? would it be better for people who are replying with denynode num to just broadcast their denial?)
and instead we should use a special 'im unconfigured node number' and include our desired node number in the wantnum message.
the unconfigured node num would only be used while initially joining the mesh so low odds of conflicting (especially if we
randomly select from a small number of nodenums which can be used temporarily for this operation). figure out what the lower
level mesh sw does if it does conflict? would it be better for people who are replying with denynode num to just broadcast
their denial?)
*/
/// Called from bluetooth when the user wants to start reading the node DB from scratch.
@ -74,13 +75,16 @@ public:
/// Find a node in our DB, return null for missing
NodeInfo *getNode(NodeNum n);
NodeInfo *getNodeByIndex(size_t x) { assert(x < *numNodes); return &nodes[x]; }
NodeInfo *getNodeByIndex(size_t x)
{
assert(x < *numNodes);
return &nodes[x];
}
/// Return the number of nodes we've heard from recently (within the last 2 hrs?)
size_t getNumOnlineNodes();
private:
private:
/// Find a node in our DB, create an empty NodeInfo if missing
NodeInfo *getOrCreateNode(NodeNum n);
@ -89,4 +93,3 @@ private:
};
extern NodeDB nodeDB;

Wyświetl plik

@ -10,14 +10,14 @@ class Observer
{
Observable *observed;
public:
public:
Observer() : observed(NULL) {}
virtual ~Observer();
void observe(Observable *o);
private:
private:
friend class Observable;
virtual void onNotify(Observable *o) = 0;
@ -27,23 +27,15 @@ class Observable
{
std::list<Observer *> observers;
public:
public:
void notifyObservers()
{
for (std::list<Observer *>::const_iterator iterator = observers.begin(); iterator != observers.end(); ++iterator)
{
for (std::list<Observer *>::const_iterator iterator = observers.begin(); iterator != observers.end(); ++iterator) {
(*iterator)->onNotify(this);
}
}
void addObserver(Observer *o)
{
observers.push_back(o);
}
void addObserver(Observer *o) { observers.push_back(o); }
void removeObserver(Observer *o)
{
observers.remove(o);
}
void removeObserver(Observer *o) { observers.remove(o); }
};

Wyświetl plik

@ -1,22 +1,21 @@
#pragma once
#include <Arduino.h>
#include "PeriodicTask.h"
#include <Arduino.h>
/**
* Periodically invoke a callback.
*
*
* This just provides C style callback conventions rather than a virtual function - FIXME, remove?
*/
class Periodic : public PeriodicTask
{
uint32_t (*callback)();
uint32_t (*callback)();
public:
// callback returns the period for the next callback invocation (or 0 if we should no longer be called)
Periodic(uint32_t (*_callback)()) : callback(_callback) {}
public:
// callback returns the period for the next callback invocation (or 0 if we should no longer be called)
Periodic(uint32_t (*_callback)()) : callback(_callback) {}
protected:
void doTask();
protected:
void doTask();
};

Wyświetl plik

@ -5,13 +5,10 @@
/**
* A wrapper for freertos queues that assumes each element is a pointer
*/
template <class T>
class PointerQueue : public TypedQueue<T *>
template <class T> class PointerQueue : public TypedQueue<T *>
{
public:
PointerQueue(int maxElements) : TypedQueue<T *>(maxElements)
{
}
public:
PointerQueue(int maxElements) : TypedQueue<T *>(maxElements) {}
// returns a ptr or null if the queue was empty
T *dequeuePtr(TickType_t maxWait = portMAX_DELAY)

Wyświetl plik

@ -124,22 +124,19 @@ static void screenPress()
screen.onPress();
}
static void bootEnter() {
}
static void bootEnter() {}
State stateSDS(sdsEnter, NULL, NULL, "SDS");
State stateLS(lsEnter, lsIdle, lsExit, "LS");
State stateNB(nbEnter, NULL, NULL, "NB");
State stateDARK(darkEnter, NULL, NULL, "DARK");
State stateBOOT(bootEnter , NULL, NULL, "BOOT");
State stateBOOT(bootEnter, NULL, NULL, "BOOT");
State stateON(onEnter, NULL, NULL, "ON");
Fsm powerFSM(&stateBOOT);
void PowerFSM_setup()
{
powerFSM.add_timed_transition(&stateBOOT, &stateON, 3 * 1000, NULL,
"boot timeout");
powerFSM.add_timed_transition(&stateBOOT, &stateON, 3 * 1000, NULL, "boot timeout");
powerFSM.add_transition(&stateLS, &stateDARK, EVENT_WAKE_TIMER, wakeForPing, "Wake timer");

Wyświetl plik

@ -1,17 +1,17 @@
#pragma once
#pragma once
#include <Fsm.h>
// See sw-design.md for documentation
#define EVENT_PRESS 1
#define EVENT_PRESS 1
#define EVENT_WAKE_TIMER 2
#define EVENT_RECEIVED_PACKET 3
#define EVENT_PACKET_FOR_PHONE 4
#define EVENT_RECEIVED_TEXT_MSG 5
// #define EVENT_BOOT 6 // now done with a timed transition
#define EVENT_BLUETOOTH_PAIR 7
#define EVENT_NODEDB_UPDATED 8 // NodeDB has a big enough change that we think you should turn on the screen
#define EVENT_NODEDB_UPDATED 8 // NodeDB has a big enough change that we think you should turn on the screen
#define EVENT_CONTACT_FROM_PHONE 9 // the phone just talked to us over bluetooth
extern Fsm powerFSM;

Wyświetl plik

@ -10,8 +10,7 @@
* A wrapper for freertos queues. Note: each element object should be small
* and POD (Plain Old Data type) as elements are memcpied by value.
*/
template <class T>
class TypedQueue
template <class T> class TypedQueue
{
static_assert(std::is_pod<T>::value, "T must be pod");
QueueHandle_t h;
@ -23,38 +22,17 @@ class TypedQueue
assert(h);
}
~TypedQueue()
{
vQueueDelete(h);
}
~TypedQueue() { vQueueDelete(h); }
int numFree()
{
return uxQueueSpacesAvailable(h);
}
int numFree() { return uxQueueSpacesAvailable(h); }
bool isEmpty()
{
return uxQueueMessagesWaiting(h) == 0;
}
bool isEmpty() { return uxQueueMessagesWaiting(h) == 0; }
bool enqueue(T x, TickType_t maxWait = portMAX_DELAY)
{
return xQueueSendToBack(h, &x, maxWait) == pdTRUE;
}
bool enqueue(T x, TickType_t maxWait = portMAX_DELAY) { return xQueueSendToBack(h, &x, maxWait) == pdTRUE; }
bool enqueueFromISR(T x, BaseType_t *higherPriWoken)
{
return xQueueSendToBackFromISR(h, &x, higherPriWoken) == pdTRUE;
}
bool enqueueFromISR(T x, BaseType_t *higherPriWoken) { return xQueueSendToBackFromISR(h, &x, higherPriWoken) == pdTRUE; }
bool dequeue(T *p, TickType_t maxWait = portMAX_DELAY)
{
return xQueueReceive(h, p, maxWait) == pdTRUE;
}
bool dequeue(T *p, TickType_t maxWait = portMAX_DELAY) { return xQueueReceive(h, p, maxWait) == pdTRUE; }
bool dequeueFromISR(T *p, BaseType_t *higherPriWoken)
{
return xQueueReceiveFromISR(h, p, higherPriWoken);
}
bool dequeueFromISR(T *p, BaseType_t *higherPriWoken) { return xQueueReceiveFromISR(h, p, higherPriWoken); }
};

Wyświetl plik

@ -41,10 +41,11 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
// Select which board is being used. If the outside build environment has sent a choice, just use that
#if !defined(T_BEAM_V10) && !defined(HELTEC_LORA32)
// #define T_BEAM_V10 // AKA Rev1 (second board released)
#define HELTEC_LORA32
#define T_BEAM_V10 // AKA Rev1 (second board released)
// #define HELTEC_LORA32
#define HW_VERSION_US // We encode the hardware freq range in the hw version string, so sw update can eventually install the correct build
#define HW_VERSION_US // We encode the hardware freq range in the hw version string, so sw update can eventually install the
// correct build
#endif
// If we are using the JTAG port for debugging, some pins must be left free for that (and things like GPS have to be disabled)

Wyświetl plik

@ -1,423 +1,423 @@
const uint8_t Custom_ArialMT_Plain_10[] PROGMEM = {
0x0A, // Width: 10
0x0A, // Height: 10
0x20, // First Char: 32
0xE0, // Numbers of Chars: 224
0x0A, // Width: 10
0x0A, // Height: 10
0x20, // First Char: 32
0xE0, // Numbers of Chars: 224
// Jump Table:
0xFF, 0xFF, 0x00, 0x03, // 32:65535
0x00, 0x00, 0x04, 0x03, // 33:0
0x00, 0x04, 0x05, 0x04, // 34:4
0x00, 0x09, 0x09, 0x06, // 35:9
0x00, 0x12, 0x0A, 0x06, // 36:18
0x00, 0x1C, 0x10, 0x09, // 37:28
0x00, 0x2C, 0x0E, 0x07, // 38:44
0x00, 0x3A, 0x01, 0x02, // 39:58
0x00, 0x3B, 0x06, 0x03, // 40:59
0x00, 0x41, 0x06, 0x03, // 41:65
0x00, 0x47, 0x05, 0x04, // 42:71
0x00, 0x4C, 0x09, 0x06, // 43:76
0x00, 0x55, 0x04, 0x03, // 44:85
0x00, 0x59, 0x03, 0x03, // 45:89
0x00, 0x5C, 0x04, 0x03, // 46:92
0x00, 0x60, 0x05, 0x03, // 47:96
0x00, 0x65, 0x0A, 0x06, // 48:101
0x00, 0x6F, 0x08, 0x06, // 49:111
0x00, 0x77, 0x0A, 0x06, // 50:119
0x00, 0x81, 0x0A, 0x06, // 51:129
0x00, 0x8B, 0x0B, 0x06, // 52:139
0x00, 0x96, 0x0A, 0x06, // 53:150
0x00, 0xA0, 0x0A, 0x06, // 54:160
0x00, 0xAA, 0x09, 0x06, // 55:170
0x00, 0xB3, 0x0A, 0x06, // 56:179
0x00, 0xBD, 0x0A, 0x06, // 57:189
0x00, 0xC7, 0x04, 0x03, // 58:199
0x00, 0xCB, 0x04, 0x03, // 59:203
0x00, 0xCF, 0x0A, 0x06, // 60:207
0x00, 0xD9, 0x09, 0x06, // 61:217
0x00, 0xE2, 0x09, 0x06, // 62:226
0x00, 0xEB, 0x0B, 0x06, // 63:235
0x00, 0xF6, 0x14, 0x0A, // 64:246
0x01, 0x0A, 0x0E, 0x07, // 65:266
0x01, 0x18, 0x0C, 0x07, // 66:280
0x01, 0x24, 0x0C, 0x07, // 67:292
0x01, 0x30, 0x0B, 0x07, // 68:304
0x01, 0x3B, 0x0C, 0x07, // 69:315
0x01, 0x47, 0x09, 0x06, // 70:327
0x01, 0x50, 0x0D, 0x08, // 71:336
0x01, 0x5D, 0x0C, 0x07, // 72:349
0x01, 0x69, 0x04, 0x03, // 73:361
0x01, 0x6D, 0x08, 0x05, // 74:365
0x01, 0x75, 0x0E, 0x07, // 75:373
0x01, 0x83, 0x0C, 0x06, // 76:387
0x01, 0x8F, 0x10, 0x08, // 77:399
0x01, 0x9F, 0x0C, 0x07, // 78:415
0x01, 0xAB, 0x0E, 0x08, // 79:427
0x01, 0xB9, 0x0B, 0x07, // 80:441
0x01, 0xC4, 0x0E, 0x08, // 81:452
0x01, 0xD2, 0x0C, 0x07, // 82:466
0x01, 0xDE, 0x0C, 0x07, // 83:478
0x01, 0xEA, 0x0B, 0x06, // 84:490
0x01, 0xF5, 0x0C, 0x07, // 85:501
0x02, 0x01, 0x0D, 0x07, // 86:513
0x02, 0x0E, 0x11, 0x09, // 87:526
0x02, 0x1F, 0x0E, 0x07, // 88:543
0x02, 0x2D, 0x0D, 0x07, // 89:557
0x02, 0x3A, 0x0C, 0x06, // 90:570
0x02, 0x46, 0x06, 0x03, // 91:582
0x02, 0x4C, 0x06, 0x03, // 92:588
0x02, 0x52, 0x04, 0x03, // 93:594
0x02, 0x56, 0x09, 0x05, // 94:598
0x02, 0x5F, 0x0C, 0x06, // 95:607
0x02, 0x6B, 0x03, 0x03, // 96:619
0x02, 0x6E, 0x0A, 0x06, // 97:622
0x02, 0x78, 0x0A, 0x06, // 98:632
0x02, 0x82, 0x0A, 0x05, // 99:642
0x02, 0x8C, 0x0A, 0x06, // 100:652
0x02, 0x96, 0x0A, 0x06, // 101:662
0x02, 0xA0, 0x05, 0x03, // 102:672
0x02, 0xA5, 0x0A, 0x06, // 103:677
0x02, 0xAF, 0x0A, 0x06, // 104:687
0x02, 0xB9, 0x04, 0x02, // 105:697
0x02, 0xBD, 0x04, 0x02, // 106:701
0x02, 0xC1, 0x08, 0x05, // 107:705
0x02, 0xC9, 0x04, 0x02, // 108:713
0x02, 0xCD, 0x10, 0x08, // 109:717
0x02, 0xDD, 0x0A, 0x06, // 110:733
0x02, 0xE7, 0x0A, 0x06, // 111:743
0x02, 0xF1, 0x0A, 0x06, // 112:753
0x02, 0xFB, 0x0A, 0x06, // 113:763
0x03, 0x05, 0x05, 0x03, // 114:773
0x03, 0x0A, 0x08, 0x05, // 115:778
0x03, 0x12, 0x06, 0x03, // 116:786
0x03, 0x18, 0x0A, 0x06, // 117:792
0x03, 0x22, 0x09, 0x05, // 118:802
0x03, 0x2B, 0x0E, 0x07, // 119:811
0x03, 0x39, 0x0A, 0x05, // 120:825
0x03, 0x43, 0x09, 0x05, // 121:835
0x03, 0x4C, 0x0A, 0x05, // 122:844
0x03, 0x56, 0x06, 0x03, // 123:854
0x03, 0x5C, 0x04, 0x03, // 124:860
0x03, 0x60, 0x05, 0x03, // 125:864
0x03, 0x65, 0x09, 0x06, // 126:869
0xFF, 0xFF, 0x00, 0x00, // 127:65535
0xFF, 0xFF, 0x00, 0x0A, // 128:65535
0xFF, 0xFF, 0x00, 0x0A, // 129:65535
0xFF, 0xFF, 0x00, 0x0A, // 130:65535
0xFF, 0xFF, 0x00, 0x0A, // 131:65535
0xFF, 0xFF, 0x00, 0x0A, // 132:65535
0xFF, 0xFF, 0x00, 0x0A, // 133:65535
0xFF, 0xFF, 0x00, 0x0A, // 134:65535
0xFF, 0xFF, 0x00, 0x0A, // 135:65535
0xFF, 0xFF, 0x00, 0x0A, // 136:65535
0xFF, 0xFF, 0x00, 0x0A, // 137:65535
0xFF, 0xFF, 0x00, 0x0A, // 138:65535
0xFF, 0xFF, 0x00, 0x0A, // 139:65535
0xFF, 0xFF, 0x00, 0x0A, // 140:65535
0xFF, 0xFF, 0x00, 0x0A, // 141:65535
0xFF, 0xFF, 0x00, 0x0A, // 142:65535
0xFF, 0xFF, 0x00, 0x0A, // 143:65535
0xFF, 0xFF, 0x00, 0x0A, // 144:65535
0xFF, 0xFF, 0x00, 0x0A, // 145:65535
0xFF, 0xFF, 0x00, 0x0A, // 146:65535
0xFF, 0xFF, 0x00, 0x0A, // 147:65535
0xFF, 0xFF, 0x00, 0x0A, // 148:65535
0xFF, 0xFF, 0x00, 0x0A, // 149:65535
0xFF, 0xFF, 0x00, 0x0A, // 150:65535
0xFF, 0xFF, 0x00, 0x0A, // 151:65535
0xFF, 0xFF, 0x00, 0x0A, // 152:65535
0xFF, 0xFF, 0x00, 0x0A, // 153:65535
0xFF, 0xFF, 0x00, 0x0A, // 154:65535
0xFF, 0xFF, 0x00, 0x0A, // 155:65535
0xFF, 0xFF, 0x00, 0x0A, // 156:65535
0xFF, 0xFF, 0x00, 0x0A, // 157:65535
0xFF, 0xFF, 0x00, 0x0A, // 158:65535
0xFF, 0xFF, 0x00, 0x0A, // 159:65535
0xFF, 0xFF, 0x00, 0x03, // 160:65535
0x03, 0x6E, 0x04, 0x03, // 161:878
0x03, 0x72, 0x0A, 0x06, // 162:882
0x03, 0x7C, 0x0C, 0x06, // 163:892
0x03, 0x88, 0x0A, 0x06, // 164:904
0x03, 0x92, 0x0A, 0x06, // 165:914
0x03, 0x9C, 0x04, 0x03, // 166:924
0x03, 0xA0, 0x0A, 0x06, // 167:928
0x03, 0xAA, 0x05, 0x03, // 168:938
0x03, 0xAF, 0x0D, 0x07, // 169:943
0x03, 0xBC, 0x07, 0x04, // 170:956
0x03, 0xC3, 0x0A, 0x06, // 171:963
0x03, 0xCD, 0x09, 0x06, // 172:973
0x03, 0xD6, 0x03, 0x03, // 173:982
0x03, 0xD9, 0x0D, 0x07, // 174:985
0x03, 0xE6, 0x0B, 0x06, // 175:998
0x03, 0xF1, 0x07, 0x04, // 176:1009
0x03, 0xF8, 0x0A, 0x05, // 177:1016
0x04, 0x02, 0x05, 0x03, // 178:1026
0x04, 0x07, 0x05, 0x03, // 179:1031
0x04, 0x0C, 0x05, 0x03, // 180:1036
0x04, 0x11, 0x0A, 0x06, // 181:1041
0x04, 0x1B, 0x09, 0x05, // 182:1051
0x04, 0x24, 0x03, 0x03, // 183:1060
0x04, 0x27, 0x06, 0x03, // 184:1063
0x04, 0x2D, 0x05, 0x03, // 185:1069
0x04, 0x32, 0x07, 0x04, // 186:1074
0x04, 0x39, 0x0A, 0x06, // 187:1081
0x04, 0x43, 0x10, 0x08, // 188:1091
0x04, 0x53, 0x10, 0x08, // 189:1107
0x04, 0x63, 0x10, 0x08, // 190:1123
0x04, 0x73, 0x0A, 0x06, // 191:1139
0x04, 0x7D, 0x0E, 0x07, // 192:1149
0x04, 0x8B, 0x0E, 0x07, // 193:1163
0x04, 0x99, 0x0E, 0x07, // 194:1177
0x04, 0xA7, 0x0E, 0x07, // 195:1191
0x04, 0xB5, 0x0E, 0x07, // 196:1205
0x04, 0xC3, 0x0E, 0x07, // 197:1219
0x04, 0xD1, 0x12, 0x0A, // 198:1233
0x04, 0xE3, 0x0C, 0x07, // 199:1251
0x04, 0xEF, 0x0C, 0x07, // 200:1263
0x04, 0xFB, 0x0C, 0x07, // 201:1275
0x05, 0x07, 0x0C, 0x07, // 202:1287
0x05, 0x13, 0x0C, 0x07, // 203:1299
0x05, 0x1F, 0x05, 0x03, // 204:1311
0x05, 0x24, 0x04, 0x03, // 205:1316
0x05, 0x28, 0x04, 0x03, // 206:1320
0x05, 0x2C, 0x05, 0x03, // 207:1324
0x05, 0x31, 0x0B, 0x07, // 208:1329
0x05, 0x3C, 0x0C, 0x07, // 209:1340
0x05, 0x48, 0x0E, 0x08, // 210:1352
0x05, 0x56, 0x0E, 0x08, // 211:1366
0x05, 0x64, 0x0E, 0x08, // 212:1380
0x05, 0x72, 0x0E, 0x08, // 213:1394
0x05, 0x80, 0x0E, 0x08, // 214:1408
0x05, 0x8E, 0x0A, 0x06, // 215:1422
0x05, 0x98, 0x0D, 0x08, // 216:1432
0x05, 0xA5, 0x0C, 0x07, // 217:1445
0x05, 0xB1, 0x0C, 0x07, // 218:1457
0x05, 0xBD, 0x0C, 0x07, // 219:1469
0x05, 0xC9, 0x0C, 0x07, // 220:1481
0x05, 0xD5, 0x0D, 0x07, // 221:1493
0x05, 0xE2, 0x0B, 0x07, // 222:1506
0x05, 0xED, 0x0C, 0x06, // 223:1517
0x05, 0xF9, 0x0A, 0x06, // 224:1529
0x06, 0x03, 0x0A, 0x06, // 225:1539
0x06, 0x0D, 0x0A, 0x06, // 226:1549
0x06, 0x17, 0x0A, 0x06, // 227:1559
0x06, 0x21, 0x0A, 0x06, // 228:1569
0x06, 0x2B, 0x0A, 0x06, // 229:1579
0x06, 0x35, 0x10, 0x09, // 230:1589
0x06, 0x45, 0x0A, 0x05, // 231:1605
0x06, 0x4F, 0x0A, 0x06, // 232:1615
0x06, 0x59, 0x0A, 0x06, // 233:1625
0x06, 0x63, 0x0A, 0x06, // 234:1635
0x06, 0x6D, 0x0A, 0x06, // 235:1645
0x06, 0x77, 0x05, 0x03, // 236:1655
0x06, 0x7C, 0x04, 0x03, // 237:1660
0x06, 0x80, 0x05, 0x03, // 238:1664
0x06, 0x85, 0x05, 0x03, // 239:1669
0x06, 0x8A, 0x0A, 0x06, // 240:1674
0x06, 0x94, 0x0A, 0x06, // 241:1684
0x06, 0x9E, 0x0A, 0x06, // 242:1694
0x06, 0xA8, 0x0A, 0x06, // 243:1704
0x06, 0xB2, 0x0A, 0x06, // 244:1714
0x06, 0xBC, 0x0A, 0x06, // 245:1724
0x06, 0xC6, 0x0A, 0x06, // 246:1734
0x06, 0xD0, 0x09, 0x05, // 247:1744
0x06, 0xD9, 0x0A, 0x06, // 248:1753
0x06, 0xE3, 0x0A, 0x06, // 249:1763
0x06, 0xED, 0x0A, 0x06, // 250:1773
0x06, 0xF7, 0x0A, 0x06, // 251:1783
0x07, 0x01, 0x0A, 0x06, // 252:1793
0x07, 0x0B, 0x09, 0x05, // 253:1803
0x07, 0x14, 0x0A, 0x06, // 254:1812
0x07, 0x1E, 0x09, 0x05, // 255:1822
// Jump Table:
0xFF, 0xFF, 0x00, 0x03, // 32:65535
0x00, 0x00, 0x04, 0x03, // 33:0
0x00, 0x04, 0x05, 0x04, // 34:4
0x00, 0x09, 0x09, 0x06, // 35:9
0x00, 0x12, 0x0A, 0x06, // 36:18
0x00, 0x1C, 0x10, 0x09, // 37:28
0x00, 0x2C, 0x0E, 0x07, // 38:44
0x00, 0x3A, 0x01, 0x02, // 39:58
0x00, 0x3B, 0x06, 0x03, // 40:59
0x00, 0x41, 0x06, 0x03, // 41:65
0x00, 0x47, 0x05, 0x04, // 42:71
0x00, 0x4C, 0x09, 0x06, // 43:76
0x00, 0x55, 0x04, 0x03, // 44:85
0x00, 0x59, 0x03, 0x03, // 45:89
0x00, 0x5C, 0x04, 0x03, // 46:92
0x00, 0x60, 0x05, 0x03, // 47:96
0x00, 0x65, 0x0A, 0x06, // 48:101
0x00, 0x6F, 0x08, 0x06, // 49:111
0x00, 0x77, 0x0A, 0x06, // 50:119
0x00, 0x81, 0x0A, 0x06, // 51:129
0x00, 0x8B, 0x0B, 0x06, // 52:139
0x00, 0x96, 0x0A, 0x06, // 53:150
0x00, 0xA0, 0x0A, 0x06, // 54:160
0x00, 0xAA, 0x09, 0x06, // 55:170
0x00, 0xB3, 0x0A, 0x06, // 56:179
0x00, 0xBD, 0x0A, 0x06, // 57:189
0x00, 0xC7, 0x04, 0x03, // 58:199
0x00, 0xCB, 0x04, 0x03, // 59:203
0x00, 0xCF, 0x0A, 0x06, // 60:207
0x00, 0xD9, 0x09, 0x06, // 61:217
0x00, 0xE2, 0x09, 0x06, // 62:226
0x00, 0xEB, 0x0B, 0x06, // 63:235
0x00, 0xF6, 0x14, 0x0A, // 64:246
0x01, 0x0A, 0x0E, 0x07, // 65:266
0x01, 0x18, 0x0C, 0x07, // 66:280
0x01, 0x24, 0x0C, 0x07, // 67:292
0x01, 0x30, 0x0B, 0x07, // 68:304
0x01, 0x3B, 0x0C, 0x07, // 69:315
0x01, 0x47, 0x09, 0x06, // 70:327
0x01, 0x50, 0x0D, 0x08, // 71:336
0x01, 0x5D, 0x0C, 0x07, // 72:349
0x01, 0x69, 0x04, 0x03, // 73:361
0x01, 0x6D, 0x08, 0x05, // 74:365
0x01, 0x75, 0x0E, 0x07, // 75:373
0x01, 0x83, 0x0C, 0x06, // 76:387
0x01, 0x8F, 0x10, 0x08, // 77:399
0x01, 0x9F, 0x0C, 0x07, // 78:415
0x01, 0xAB, 0x0E, 0x08, // 79:427
0x01, 0xB9, 0x0B, 0x07, // 80:441
0x01, 0xC4, 0x0E, 0x08, // 81:452
0x01, 0xD2, 0x0C, 0x07, // 82:466
0x01, 0xDE, 0x0C, 0x07, // 83:478
0x01, 0xEA, 0x0B, 0x06, // 84:490
0x01, 0xF5, 0x0C, 0x07, // 85:501
0x02, 0x01, 0x0D, 0x07, // 86:513
0x02, 0x0E, 0x11, 0x09, // 87:526
0x02, 0x1F, 0x0E, 0x07, // 88:543
0x02, 0x2D, 0x0D, 0x07, // 89:557
0x02, 0x3A, 0x0C, 0x06, // 90:570
0x02, 0x46, 0x06, 0x03, // 91:582
0x02, 0x4C, 0x06, 0x03, // 92:588
0x02, 0x52, 0x04, 0x03, // 93:594
0x02, 0x56, 0x09, 0x05, // 94:598
0x02, 0x5F, 0x0C, 0x06, // 95:607
0x02, 0x6B, 0x03, 0x03, // 96:619
0x02, 0x6E, 0x0A, 0x06, // 97:622
0x02, 0x78, 0x0A, 0x06, // 98:632
0x02, 0x82, 0x0A, 0x05, // 99:642
0x02, 0x8C, 0x0A, 0x06, // 100:652
0x02, 0x96, 0x0A, 0x06, // 101:662
0x02, 0xA0, 0x05, 0x03, // 102:672
0x02, 0xA5, 0x0A, 0x06, // 103:677
0x02, 0xAF, 0x0A, 0x06, // 104:687
0x02, 0xB9, 0x04, 0x02, // 105:697
0x02, 0xBD, 0x04, 0x02, // 106:701
0x02, 0xC1, 0x08, 0x05, // 107:705
0x02, 0xC9, 0x04, 0x02, // 108:713
0x02, 0xCD, 0x10, 0x08, // 109:717
0x02, 0xDD, 0x0A, 0x06, // 110:733
0x02, 0xE7, 0x0A, 0x06, // 111:743
0x02, 0xF1, 0x0A, 0x06, // 112:753
0x02, 0xFB, 0x0A, 0x06, // 113:763
0x03, 0x05, 0x05, 0x03, // 114:773
0x03, 0x0A, 0x08, 0x05, // 115:778
0x03, 0x12, 0x06, 0x03, // 116:786
0x03, 0x18, 0x0A, 0x06, // 117:792
0x03, 0x22, 0x09, 0x05, // 118:802
0x03, 0x2B, 0x0E, 0x07, // 119:811
0x03, 0x39, 0x0A, 0x05, // 120:825
0x03, 0x43, 0x09, 0x05, // 121:835
0x03, 0x4C, 0x0A, 0x05, // 122:844
0x03, 0x56, 0x06, 0x03, // 123:854
0x03, 0x5C, 0x04, 0x03, // 124:860
0x03, 0x60, 0x05, 0x03, // 125:864
0x03, 0x65, 0x09, 0x06, // 126:869
0xFF, 0xFF, 0x00, 0x00, // 127:65535
0xFF, 0xFF, 0x00, 0x0A, // 128:65535
0xFF, 0xFF, 0x00, 0x0A, // 129:65535
0xFF, 0xFF, 0x00, 0x0A, // 130:65535
0xFF, 0xFF, 0x00, 0x0A, // 131:65535
0xFF, 0xFF, 0x00, 0x0A, // 132:65535
0xFF, 0xFF, 0x00, 0x0A, // 133:65535
0xFF, 0xFF, 0x00, 0x0A, // 134:65535
0xFF, 0xFF, 0x00, 0x0A, // 135:65535
0xFF, 0xFF, 0x00, 0x0A, // 136:65535
0xFF, 0xFF, 0x00, 0x0A, // 137:65535
0xFF, 0xFF, 0x00, 0x0A, // 138:65535
0xFF, 0xFF, 0x00, 0x0A, // 139:65535
0xFF, 0xFF, 0x00, 0x0A, // 140:65535
0xFF, 0xFF, 0x00, 0x0A, // 141:65535
0xFF, 0xFF, 0x00, 0x0A, // 142:65535
0xFF, 0xFF, 0x00, 0x0A, // 143:65535
0xFF, 0xFF, 0x00, 0x0A, // 144:65535
0xFF, 0xFF, 0x00, 0x0A, // 145:65535
0xFF, 0xFF, 0x00, 0x0A, // 146:65535
0xFF, 0xFF, 0x00, 0x0A, // 147:65535
0xFF, 0xFF, 0x00, 0x0A, // 148:65535
0xFF, 0xFF, 0x00, 0x0A, // 149:65535
0xFF, 0xFF, 0x00, 0x0A, // 150:65535
0xFF, 0xFF, 0x00, 0x0A, // 151:65535
0xFF, 0xFF, 0x00, 0x0A, // 152:65535
0xFF, 0xFF, 0x00, 0x0A, // 153:65535
0xFF, 0xFF, 0x00, 0x0A, // 154:65535
0xFF, 0xFF, 0x00, 0x0A, // 155:65535
0xFF, 0xFF, 0x00, 0x0A, // 156:65535
0xFF, 0xFF, 0x00, 0x0A, // 157:65535
0xFF, 0xFF, 0x00, 0x0A, // 158:65535
0xFF, 0xFF, 0x00, 0x0A, // 159:65535
0xFF, 0xFF, 0x00, 0x03, // 160:65535
0x03, 0x6E, 0x04, 0x03, // 161:878
0x03, 0x72, 0x0A, 0x06, // 162:882
0x03, 0x7C, 0x0C, 0x06, // 163:892
0x03, 0x88, 0x0A, 0x06, // 164:904
0x03, 0x92, 0x0A, 0x06, // 165:914
0x03, 0x9C, 0x04, 0x03, // 166:924
0x03, 0xA0, 0x0A, 0x06, // 167:928
0x03, 0xAA, 0x05, 0x03, // 168:938
0x03, 0xAF, 0x0D, 0x07, // 169:943
0x03, 0xBC, 0x07, 0x04, // 170:956
0x03, 0xC3, 0x0A, 0x06, // 171:963
0x03, 0xCD, 0x09, 0x06, // 172:973
0x03, 0xD6, 0x03, 0x03, // 173:982
0x03, 0xD9, 0x0D, 0x07, // 174:985
0x03, 0xE6, 0x0B, 0x06, // 175:998
0x03, 0xF1, 0x07, 0x04, // 176:1009
0x03, 0xF8, 0x0A, 0x05, // 177:1016
0x04, 0x02, 0x05, 0x03, // 178:1026
0x04, 0x07, 0x05, 0x03, // 179:1031
0x04, 0x0C, 0x05, 0x03, // 180:1036
0x04, 0x11, 0x0A, 0x06, // 181:1041
0x04, 0x1B, 0x09, 0x05, // 182:1051
0x04, 0x24, 0x03, 0x03, // 183:1060
0x04, 0x27, 0x06, 0x03, // 184:1063
0x04, 0x2D, 0x05, 0x03, // 185:1069
0x04, 0x32, 0x07, 0x04, // 186:1074
0x04, 0x39, 0x0A, 0x06, // 187:1081
0x04, 0x43, 0x10, 0x08, // 188:1091
0x04, 0x53, 0x10, 0x08, // 189:1107
0x04, 0x63, 0x10, 0x08, // 190:1123
0x04, 0x73, 0x0A, 0x06, // 191:1139
0x04, 0x7D, 0x0E, 0x07, // 192:1149
0x04, 0x8B, 0x0E, 0x07, // 193:1163
0x04, 0x99, 0x0E, 0x07, // 194:1177
0x04, 0xA7, 0x0E, 0x07, // 195:1191
0x04, 0xB5, 0x0E, 0x07, // 196:1205
0x04, 0xC3, 0x0E, 0x07, // 197:1219
0x04, 0xD1, 0x12, 0x0A, // 198:1233
0x04, 0xE3, 0x0C, 0x07, // 199:1251
0x04, 0xEF, 0x0C, 0x07, // 200:1263
0x04, 0xFB, 0x0C, 0x07, // 201:1275
0x05, 0x07, 0x0C, 0x07, // 202:1287
0x05, 0x13, 0x0C, 0x07, // 203:1299
0x05, 0x1F, 0x05, 0x03, // 204:1311
0x05, 0x24, 0x04, 0x03, // 205:1316
0x05, 0x28, 0x04, 0x03, // 206:1320
0x05, 0x2C, 0x05, 0x03, // 207:1324
0x05, 0x31, 0x0B, 0x07, // 208:1329
0x05, 0x3C, 0x0C, 0x07, // 209:1340
0x05, 0x48, 0x0E, 0x08, // 210:1352
0x05, 0x56, 0x0E, 0x08, // 211:1366
0x05, 0x64, 0x0E, 0x08, // 212:1380
0x05, 0x72, 0x0E, 0x08, // 213:1394
0x05, 0x80, 0x0E, 0x08, // 214:1408
0x05, 0x8E, 0x0A, 0x06, // 215:1422
0x05, 0x98, 0x0D, 0x08, // 216:1432
0x05, 0xA5, 0x0C, 0x07, // 217:1445
0x05, 0xB1, 0x0C, 0x07, // 218:1457
0x05, 0xBD, 0x0C, 0x07, // 219:1469
0x05, 0xC9, 0x0C, 0x07, // 220:1481
0x05, 0xD5, 0x0D, 0x07, // 221:1493
0x05, 0xE2, 0x0B, 0x07, // 222:1506
0x05, 0xED, 0x0C, 0x06, // 223:1517
0x05, 0xF9, 0x0A, 0x06, // 224:1529
0x06, 0x03, 0x0A, 0x06, // 225:1539
0x06, 0x0D, 0x0A, 0x06, // 226:1549
0x06, 0x17, 0x0A, 0x06, // 227:1559
0x06, 0x21, 0x0A, 0x06, // 228:1569
0x06, 0x2B, 0x0A, 0x06, // 229:1579
0x06, 0x35, 0x10, 0x09, // 230:1589
0x06, 0x45, 0x0A, 0x05, // 231:1605
0x06, 0x4F, 0x0A, 0x06, // 232:1615
0x06, 0x59, 0x0A, 0x06, // 233:1625
0x06, 0x63, 0x0A, 0x06, // 234:1635
0x06, 0x6D, 0x0A, 0x06, // 235:1645
0x06, 0x77, 0x05, 0x03, // 236:1655
0x06, 0x7C, 0x04, 0x03, // 237:1660
0x06, 0x80, 0x05, 0x03, // 238:1664
0x06, 0x85, 0x05, 0x03, // 239:1669
0x06, 0x8A, 0x0A, 0x06, // 240:1674
0x06, 0x94, 0x0A, 0x06, // 241:1684
0x06, 0x9E, 0x0A, 0x06, // 242:1694
0x06, 0xA8, 0x0A, 0x06, // 243:1704
0x06, 0xB2, 0x0A, 0x06, // 244:1714
0x06, 0xBC, 0x0A, 0x06, // 245:1724
0x06, 0xC6, 0x0A, 0x06, // 246:1734
0x06, 0xD0, 0x09, 0x05, // 247:1744
0x06, 0xD9, 0x0A, 0x06, // 248:1753
0x06, 0xE3, 0x0A, 0x06, // 249:1763
0x06, 0xED, 0x0A, 0x06, // 250:1773
0x06, 0xF7, 0x0A, 0x06, // 251:1783
0x07, 0x01, 0x0A, 0x06, // 252:1793
0x07, 0x0B, 0x09, 0x05, // 253:1803
0x07, 0x14, 0x0A, 0x06, // 254:1812
0x07, 0x1E, 0x09, 0x05, // 255:1822
// Font Data:
0x00,0x00,0xF8,0x02, // 33
0x38,0x00,0x00,0x00,0x38, // 34
0xA0,0x03,0xE0,0x00,0xB8,0x03,0xE0,0x00,0xB8, // 35
0x30,0x01,0x28,0x02,0xF8,0x07,0x48,0x02,0x90,0x01, // 36
0x00,0x00,0x30,0x00,0x48,0x00,0x30,0x03,0xC0,0x00,0xB0,0x01,0x48,0x02,0x80,0x01, // 37
0x80,0x01,0x50,0x02,0x68,0x02,0xA8,0x02,0x18,0x01,0x80,0x03,0x80,0x02, // 38
0x38, // 39
0xE0,0x03,0x10,0x04,0x08,0x08, // 40
0x08,0x08,0x10,0x04,0xE0,0x03, // 41
0x28,0x00,0x18,0x00,0x28, // 42
0x40,0x00,0x40,0x00,0xF0,0x01,0x40,0x00,0x40, // 43
0x00,0x00,0x00,0x06, // 44
0x80,0x00,0x80, // 45
0x00,0x00,0x00,0x02, // 46
0x00,0x03,0xE0,0x00,0x18, // 47
0xF0,0x01,0x08,0x02,0x08,0x02,0x08,0x02,0xF0,0x01, // 48
0x00,0x00,0x20,0x00,0x10,0x00,0xF8,0x03, // 49
0x10,0x02,0x08,0x03,0x88,0x02,0x48,0x02,0x30,0x02, // 50
0x10,0x01,0x08,0x02,0x48,0x02,0x48,0x02,0xB0,0x01, // 51
0xC0,0x00,0xA0,0x00,0x90,0x00,0x88,0x00,0xF8,0x03,0x80, // 52
0x60,0x01,0x38,0x02,0x28,0x02,0x28,0x02,0xC8,0x01, // 53
0xF0,0x01,0x28,0x02,0x28,0x02,0x28,0x02,0xD0,0x01, // 54
0x08,0x00,0x08,0x03,0xC8,0x00,0x38,0x00,0x08, // 55
0xB0,0x01,0x48,0x02,0x48,0x02,0x48,0x02,0xB0,0x01, // 56
0x70,0x01,0x88,0x02,0x88,0x02,0x88,0x02,0xF0,0x01, // 57
0x00,0x00,0x20,0x02, // 58
0x00,0x00,0x20,0x06, // 59
0x00,0x00,0x40,0x00,0xA0,0x00,0xA0,0x00,0x10,0x01, // 60
0xA0,0x00,0xA0,0x00,0xA0,0x00,0xA0,0x00,0xA0, // 61
0x00,0x00,0x10,0x01,0xA0,0x00,0xA0,0x00,0x40, // 62
0x10,0x00,0x08,0x00,0x08,0x00,0xC8,0x02,0x48,0x00,0x30, // 63
0x00,0x00,0xC0,0x03,0x30,0x04,0xD0,0x09,0x28,0x0A,0x28,0x0A,0xC8,0x0B,0x68,0x0A,0x10,0x05,0xE0,0x04, // 64
0x00,0x02,0xC0,0x01,0xB0,0x00,0x88,0x00,0xB0,0x00,0xC0,0x01,0x00,0x02, // 65
0x00,0x00,0xF8,0x03,0x48,0x02,0x48,0x02,0x48,0x02,0xF0,0x01, // 66
0x00,0x00,0xF0,0x01,0x08,0x02,0x08,0x02,0x08,0x02,0x10,0x01, // 67
0x00,0x00,0xF8,0x03,0x08,0x02,0x08,0x02,0x10,0x01,0xE0, // 68
0x00,0x00,0xF8,0x03,0x48,0x02,0x48,0x02,0x48,0x02,0x48,0x02, // 69
0x00,0x00,0xF8,0x03,0x48,0x00,0x48,0x00,0x08, // 70
0x00,0x00,0xE0,0x00,0x10,0x01,0x08,0x02,0x48,0x02,0x50,0x01,0xC0, // 71
0x00,0x00,0xF8,0x03,0x40,0x00,0x40,0x00,0x40,0x00,0xF8,0x03, // 72
0x00,0x00,0xF8,0x03, // 73
0x00,0x03,0x00,0x02,0x00,0x02,0xF8,0x01, // 74
0x00,0x00,0xF8,0x03,0x80,0x00,0x60,0x00,0x90,0x00,0x08,0x01,0x00,0x02, // 75
0x00,0x00,0xF8,0x03,0x00,0x02,0x00,0x02,0x00,0x02,0x00,0x02, // 76
0x00,0x00,0xF8,0x03,0x30,0x00,0xC0,0x01,0x00,0x02,0xC0,0x01,0x30,0x00,0xF8,0x03, // 77
0x00,0x00,0xF8,0x03,0x30,0x00,0x40,0x00,0x80,0x01,0xF8,0x03, // 78
0x00,0x00,0xF0,0x01,0x08,0x02,0x08,0x02,0x08,0x02,0x08,0x02,0xF0,0x01, // 79
0x00,0x00,0xF8,0x03,0x48,0x00,0x48,0x00,0x48,0x00,0x30, // 80
0x00,0x00,0xF0,0x01,0x08,0x02,0x08,0x02,0x08,0x03,0x08,0x03,0xF0,0x02, // 81
0x00,0x00,0xF8,0x03,0x48,0x00,0x48,0x00,0xC8,0x00,0x30,0x03, // 82
0x00,0x00,0x30,0x01,0x48,0x02,0x48,0x02,0x48,0x02,0x90,0x01, // 83
0x00,0x00,0x08,0x00,0x08,0x00,0xF8,0x03,0x08,0x00,0x08, // 84
0x00,0x00,0xF8,0x01,0x00,0x02,0x00,0x02,0x00,0x02,0xF8,0x01, // 85
0x08,0x00,0x70,0x00,0x80,0x01,0x00,0x02,0x80,0x01,0x70,0x00,0x08, // 86
0x18,0x00,0xE0,0x01,0x00,0x02,0xF0,0x01,0x08,0x00,0xF0,0x01,0x00,0x02,0xE0,0x01,0x18, // 87
0x00,0x02,0x08,0x01,0x90,0x00,0x60,0x00,0x90,0x00,0x08,0x01,0x00,0x02, // 88
0x08,0x00,0x10,0x00,0x20,0x00,0xC0,0x03,0x20,0x00,0x10,0x00,0x08, // 89
0x08,0x03,0x88,0x02,0xC8,0x02,0x68,0x02,0x38,0x02,0x18,0x02, // 90
0x00,0x00,0xF8,0x0F,0x08,0x08, // 91
0x18,0x00,0xE0,0x00,0x00,0x03, // 92
0x08,0x08,0xF8,0x0F, // 93
0x40,0x00,0x30,0x00,0x08,0x00,0x30,0x00,0x40, // 94
0x00,0x08,0x00,0x08,0x00,0x08,0x00,0x08,0x00,0x08,0x00,0x08, // 95
0x08,0x00,0x10, // 96
0x00,0x00,0x00,0x03,0xA0,0x02,0xA0,0x02,0xE0,0x03, // 97
0x00,0x00,0xF8,0x03,0x20,0x02,0x20,0x02,0xC0,0x01, // 98
0x00,0x00,0xC0,0x01,0x20,0x02,0x20,0x02,0x40,0x01, // 99
0x00,0x00,0xC0,0x01,0x20,0x02,0x20,0x02,0xF8,0x03, // 100
0x00,0x00,0xC0,0x01,0xA0,0x02,0xA0,0x02,0xC0,0x02, // 101
0x20,0x00,0xF0,0x03,0x28, // 102
0x00,0x00,0xC0,0x05,0x20,0x0A,0x20,0x0A,0xE0,0x07, // 103
0x00,0x00,0xF8,0x03,0x20,0x00,0x20,0x00,0xC0,0x03, // 104
0x00,0x00,0xE8,0x03, // 105
0x00,0x08,0xE8,0x07, // 106
0xF8,0x03,0x80,0x00,0xC0,0x01,0x20,0x02, // 107
0x00,0x00,0xF8,0x03, // 108
0x00,0x00,0xE0,0x03,0x20,0x00,0x20,0x00,0xE0,0x03,0x20,0x00,0x20,0x00,0xC0,0x03, // 109
0x00,0x00,0xE0,0x03,0x20,0x00,0x20,0x00,0xC0,0x03, // 110
0x00,0x00,0xC0,0x01,0x20,0x02,0x20,0x02,0xC0,0x01, // 111
0x00,0x00,0xE0,0x0F,0x20,0x02,0x20,0x02,0xC0,0x01, // 112
0x00,0x00,0xC0,0x01,0x20,0x02,0x20,0x02,0xE0,0x0F, // 113
0x00,0x00,0xE0,0x03,0x20, // 114
0x40,0x02,0xA0,0x02,0xA0,0x02,0x20,0x01, // 115
0x20,0x00,0xF8,0x03,0x20,0x02, // 116
0x00,0x00,0xE0,0x01,0x00,0x02,0x00,0x02,0xE0,0x03, // 117
0x20,0x00,0xC0,0x01,0x00,0x02,0xC0,0x01,0x20, // 118
0xE0,0x01,0x00,0x02,0xC0,0x01,0x20,0x00,0xC0,0x01,0x00,0x02,0xE0,0x01, // 119
0x20,0x02,0x40,0x01,0x80,0x00,0x40,0x01,0x20,0x02, // 120
0x20,0x00,0xC0,0x09,0x00,0x06,0xC0,0x01,0x20, // 121
0x20,0x02,0x20,0x03,0xA0,0x02,0x60,0x02,0x20,0x02, // 122
0x80,0x00,0x78,0x0F,0x08,0x08, // 123
0x00,0x00,0xF8,0x0F, // 124
0x08,0x08,0x78,0x0F,0x80, // 125
0xC0,0x00,0x40,0x00,0xC0,0x00,0x80,0x00,0xC0, // 126
0x00,0x00,0xA0,0x0F, // 161
0x00,0x00,0xC0,0x01,0xA0,0x0F,0x78,0x02,0x40,0x01, // 162
0x40,0x02,0x70,0x03,0xC8,0x02,0x48,0x02,0x08,0x02,0x10,0x02, // 163
0x00,0x00,0xE0,0x01,0x20,0x01,0x20,0x01,0xE0,0x01, // 164
0x48,0x01,0x70,0x01,0xC0,0x03,0x70,0x01,0x48,0x01, // 165
0x00,0x00,0x38,0x0F, // 166
0xD0,0x04,0x28,0x09,0x48,0x09,0x48,0x0A,0x90,0x05, // 167
0x08,0x00,0x00,0x00,0x08, // 168
0xE0,0x00,0x10,0x01,0x48,0x02,0xA8,0x02,0xA8,0x02,0x10,0x01,0xE0, // 169
0x68,0x00,0x68,0x00,0x68,0x00,0x78, // 170
0x00,0x00,0x80,0x01,0x40,0x02,0x80,0x01,0x40,0x02, // 171
0x20,0x00,0x20,0x00,0x20,0x00,0x20,0x00,0xE0, // 172
0x80,0x00,0x80, // 173
0xE0,0x00,0x10,0x01,0xE8,0x02,0x68,0x02,0xC8,0x02,0x10,0x01,0xE0, // 174
0x02,0x00,0x02,0x00,0x02,0x00,0x02,0x00,0x02,0x00,0x02, // 175
0x00,0x00,0x38,0x00,0x28,0x00,0x38, // 176
0x40,0x02,0x40,0x02,0xF0,0x03,0x40,0x02,0x40,0x02, // 177
0x48,0x00,0x68,0x00,0x58, // 178
0x48,0x00,0x58,0x00,0x68, // 179
0x00,0x00,0x10,0x00,0x08, // 180
0x00,0x00,0xE0,0x0F,0x00,0x02,0x00,0x02,0xE0,0x03, // 181
0x70,0x00,0xF8,0x0F,0x08,0x00,0xF8,0x0F,0x08, // 182
0x00,0x00,0x40, // 183
0x00,0x00,0x00,0x14,0x00,0x18, // 184
0x00,0x00,0x10,0x00,0x78, // 185
0x30,0x00,0x48,0x00,0x48,0x00,0x30, // 186
0x00,0x00,0x40,0x02,0x80,0x01,0x40,0x02,0x80,0x01, // 187
0x00,0x00,0x10,0x02,0x78,0x01,0xC0,0x00,0x20,0x01,0x90,0x01,0xC8,0x03,0x00,0x01, // 188
0x00,0x00,0x10,0x02,0x78,0x01,0x80,0x00,0x60,0x00,0x50,0x02,0x48,0x03,0xC0,0x02, // 189
0x48,0x00,0x58,0x00,0x68,0x03,0x80,0x00,0x60,0x01,0x90,0x01,0xC8,0x03,0x00,0x01, // 190
0x00,0x00,0x00,0x06,0x00,0x09,0xA0,0x09,0x00,0x04, // 191
0x00,0x02,0xC0,0x01,0xB0,0x00,0x89,0x00,0xB2,0x00,0xC0,0x01,0x00,0x02, // 192
0x00,0x02,0xC0,0x01,0xB0,0x00,0x8A,0x00,0xB1,0x00,0xC0,0x01,0x00,0x02, // 193
0x00,0x02,0xC0,0x01,0xB2,0x00,0x89,0x00,0xB2,0x00,0xC0,0x01,0x00,0x02, // 194
0x00,0x02,0xC2,0x01,0xB1,0x00,0x8A,0x00,0xB1,0x00,0xC0,0x01,0x00,0x02, // 195
0x00,0x02,0xC0,0x01,0xB2,0x00,0x88,0x00,0xB2,0x00,0xC0,0x01,0x00,0x02, // 196
0x00,0x02,0xC0,0x01,0xBE,0x00,0x8A,0x00,0xBE,0x00,0xC0,0x01,0x00,0x02, // 197
0x00,0x03,0xC0,0x00,0xE0,0x00,0x98,0x00,0x88,0x00,0xF8,0x03,0x48,0x02,0x48,0x02,0x48,0x02, // 198
0x00,0x00,0xF0,0x01,0x08,0x02,0x08,0x16,0x08,0x1A,0x10,0x01, // 199
0x00,0x00,0xF8,0x03,0x49,0x02,0x4A,0x02,0x48,0x02,0x48,0x02, // 200
0x00,0x00,0xF8,0x03,0x48,0x02,0x4A,0x02,0x49,0x02,0x48,0x02, // 201
0x00,0x00,0xFA,0x03,0x49,0x02,0x4A,0x02,0x48,0x02,0x48,0x02, // 202
0x00,0x00,0xF8,0x03,0x4A,0x02,0x48,0x02,0x4A,0x02,0x48,0x02, // 203
0x00,0x00,0xF9,0x03,0x02, // 204
0x02,0x00,0xF9,0x03, // 205
0x01,0x00,0xFA,0x03, // 206
0x02,0x00,0xF8,0x03,0x02, // 207
0x40,0x00,0xF8,0x03,0x48,0x02,0x48,0x02,0x10,0x01,0xE0, // 208
0x00,0x00,0xFA,0x03,0x31,0x00,0x42,0x00,0x81,0x01,0xF8,0x03, // 209
0x00,0x00,0xF0,0x01,0x08,0x02,0x09,0x02,0x0A,0x02,0x08,0x02,0xF0,0x01, // 210
0x00,0x00,0xF0,0x01,0x08,0x02,0x0A,0x02,0x09,0x02,0x08,0x02,0xF0,0x01, // 211
0x00,0x00,0xF0,0x01,0x08,0x02,0x0A,0x02,0x09,0x02,0x0A,0x02,0xF0,0x01, // 212
0x00,0x00,0xF0,0x01,0x0A,0x02,0x09,0x02,0x0A,0x02,0x09,0x02,0xF0,0x01, // 213
0x00,0x00,0xF0,0x01,0x0A,0x02,0x08,0x02,0x0A,0x02,0x08,0x02,0xF0,0x01, // 214
0x10,0x01,0xA0,0x00,0xE0,0x00,0xA0,0x00,0x10,0x01, // 215
0x00,0x00,0xF0,0x02,0x08,0x03,0xC8,0x02,0x28,0x02,0x18,0x03,0xE8, // 216
0x00,0x00,0xF8,0x01,0x01,0x02,0x02,0x02,0x00,0x02,0xF8,0x01, // 217
0x00,0x00,0xF8,0x01,0x02,0x02,0x01,0x02,0x00,0x02,0xF8,0x01, // 218
0x00,0x00,0xF8,0x01,0x02,0x02,0x01,0x02,0x02,0x02,0xF8,0x01, // 219
0x00,0x00,0xF8,0x01,0x02,0x02,0x00,0x02,0x02,0x02,0xF8,0x01, // 220
0x08,0x00,0x10,0x00,0x20,0x00,0xC2,0x03,0x21,0x00,0x10,0x00,0x08, // 221
0x00,0x00,0xF8,0x03,0x10,0x01,0x10,0x01,0x10,0x01,0xE0, // 222
0x00,0x00,0xF0,0x03,0x08,0x01,0x48,0x02,0xB0,0x02,0x80,0x01, // 223
0x00,0x00,0x00,0x03,0xA4,0x02,0xA8,0x02,0xE0,0x03, // 224
0x00,0x00,0x00,0x03,0xA8,0x02,0xA4,0x02,0xE0,0x03, // 225
0x00,0x00,0x00,0x03,0xA8,0x02,0xA4,0x02,0xE8,0x03, // 226
0x00,0x00,0x08,0x03,0xA4,0x02,0xA8,0x02,0xE4,0x03, // 227
0x00,0x00,0x00,0x03,0xA8,0x02,0xA0,0x02,0xE8,0x03, // 228
0x00,0x00,0x00,0x03,0xAE,0x02,0xAA,0x02,0xEE,0x03, // 229
0x00,0x00,0x40,0x03,0xA0,0x02,0xA0,0x02,0xC0,0x01,0xA0,0x02,0xA0,0x02,0xC0,0x02, // 230
0x00,0x00,0xC0,0x01,0x20,0x16,0x20,0x1A,0x40,0x01, // 231
0x00,0x00,0xC0,0x01,0xA4,0x02,0xA8,0x02,0xC0,0x02, // 232
0x00,0x00,0xC0,0x01,0xA8,0x02,0xA4,0x02,0xC0,0x02, // 233
0x00,0x00,0xC0,0x01,0xA8,0x02,0xA4,0x02,0xC8,0x02, // 234
0x00,0x00,0xC0,0x01,0xA8,0x02,0xA0,0x02,0xC8,0x02, // 235
0x00,0x00,0xE4,0x03,0x08, // 236
0x08,0x00,0xE4,0x03, // 237
0x08,0x00,0xE4,0x03,0x08, // 238
0x08,0x00,0xE0,0x03,0x08, // 239
0x00,0x00,0xC0,0x01,0x28,0x02,0x38,0x02,0xE0,0x01, // 240
0x00,0x00,0xE8,0x03,0x24,0x00,0x28,0x00,0xC4,0x03, // 241
0x00,0x00,0xC0,0x01,0x24,0x02,0x28,0x02,0xC0,0x01, // 242
0x00,0x00,0xC0,0x01,0x28,0x02,0x24,0x02,0xC0,0x01, // 243
0x00,0x00,0xC0,0x01,0x28,0x02,0x24,0x02,0xC8,0x01, // 244
0x00,0x00,0xC8,0x01,0x24,0x02,0x28,0x02,0xC4,0x01, // 245
0x00,0x00,0xC0,0x01,0x28,0x02,0x20,0x02,0xC8,0x01, // 246
0x40,0x00,0x40,0x00,0x50,0x01,0x40,0x00,0x40, // 247
0x00,0x00,0xC0,0x02,0xA0,0x03,0x60,0x02,0xA0,0x01, // 248
0x00,0x00,0xE0,0x01,0x04,0x02,0x08,0x02,0xE0,0x03, // 249
0x00,0x00,0xE0,0x01,0x08,0x02,0x04,0x02,0xE0,0x03, // 250
0x00,0x00,0xE8,0x01,0x04,0x02,0x08,0x02,0xE0,0x03, // 251
0x00,0x00,0xE0,0x01,0x08,0x02,0x00,0x02,0xE8,0x03, // 252
0x20,0x00,0xC0,0x09,0x08,0x06,0xC4,0x01,0x20, // 253
0x00,0x00,0xF8,0x0F,0x20,0x02,0x20,0x02,0xC0,0x01, // 254
0x20,0x00,0xC8,0x09,0x00,0x06,0xC8,0x01,0x20 // 255
// Font Data:
0x00, 0x00, 0xF8, 0x02, // 33
0x38, 0x00, 0x00, 0x00, 0x38, // 34
0xA0, 0x03, 0xE0, 0x00, 0xB8, 0x03, 0xE0, 0x00, 0xB8, // 35
0x30, 0x01, 0x28, 0x02, 0xF8, 0x07, 0x48, 0x02, 0x90, 0x01, // 36
0x00, 0x00, 0x30, 0x00, 0x48, 0x00, 0x30, 0x03, 0xC0, 0x00, 0xB0, 0x01, 0x48, 0x02, 0x80, 0x01, // 37
0x80, 0x01, 0x50, 0x02, 0x68, 0x02, 0xA8, 0x02, 0x18, 0x01, 0x80, 0x03, 0x80, 0x02, // 38
0x38, // 39
0xE0, 0x03, 0x10, 0x04, 0x08, 0x08, // 40
0x08, 0x08, 0x10, 0x04, 0xE0, 0x03, // 41
0x28, 0x00, 0x18, 0x00, 0x28, // 42
0x40, 0x00, 0x40, 0x00, 0xF0, 0x01, 0x40, 0x00, 0x40, // 43
0x00, 0x00, 0x00, 0x06, // 44
0x80, 0x00, 0x80, // 45
0x00, 0x00, 0x00, 0x02, // 46
0x00, 0x03, 0xE0, 0x00, 0x18, // 47
0xF0, 0x01, 0x08, 0x02, 0x08, 0x02, 0x08, 0x02, 0xF0, 0x01, // 48
0x00, 0x00, 0x20, 0x00, 0x10, 0x00, 0xF8, 0x03, // 49
0x10, 0x02, 0x08, 0x03, 0x88, 0x02, 0x48, 0x02, 0x30, 0x02, // 50
0x10, 0x01, 0x08, 0x02, 0x48, 0x02, 0x48, 0x02, 0xB0, 0x01, // 51
0xC0, 0x00, 0xA0, 0x00, 0x90, 0x00, 0x88, 0x00, 0xF8, 0x03, 0x80, // 52
0x60, 0x01, 0x38, 0x02, 0x28, 0x02, 0x28, 0x02, 0xC8, 0x01, // 53
0xF0, 0x01, 0x28, 0x02, 0x28, 0x02, 0x28, 0x02, 0xD0, 0x01, // 54
0x08, 0x00, 0x08, 0x03, 0xC8, 0x00, 0x38, 0x00, 0x08, // 55
0xB0, 0x01, 0x48, 0x02, 0x48, 0x02, 0x48, 0x02, 0xB0, 0x01, // 56
0x70, 0x01, 0x88, 0x02, 0x88, 0x02, 0x88, 0x02, 0xF0, 0x01, // 57
0x00, 0x00, 0x20, 0x02, // 58
0x00, 0x00, 0x20, 0x06, // 59
0x00, 0x00, 0x40, 0x00, 0xA0, 0x00, 0xA0, 0x00, 0x10, 0x01, // 60
0xA0, 0x00, 0xA0, 0x00, 0xA0, 0x00, 0xA0, 0x00, 0xA0, // 61
0x00, 0x00, 0x10, 0x01, 0xA0, 0x00, 0xA0, 0x00, 0x40, // 62
0x10, 0x00, 0x08, 0x00, 0x08, 0x00, 0xC8, 0x02, 0x48, 0x00, 0x30, // 63
0x00, 0x00, 0xC0, 0x03, 0x30, 0x04, 0xD0, 0x09, 0x28, 0x0A, 0x28, 0x0A, 0xC8, 0x0B, 0x68, 0x0A, 0x10, 0x05, 0xE0, 0x04, // 64
0x00, 0x02, 0xC0, 0x01, 0xB0, 0x00, 0x88, 0x00, 0xB0, 0x00, 0xC0, 0x01, 0x00, 0x02, // 65
0x00, 0x00, 0xF8, 0x03, 0x48, 0x02, 0x48, 0x02, 0x48, 0x02, 0xF0, 0x01, // 66
0x00, 0x00, 0xF0, 0x01, 0x08, 0x02, 0x08, 0x02, 0x08, 0x02, 0x10, 0x01, // 67
0x00, 0x00, 0xF8, 0x03, 0x08, 0x02, 0x08, 0x02, 0x10, 0x01, 0xE0, // 68
0x00, 0x00, 0xF8, 0x03, 0x48, 0x02, 0x48, 0x02, 0x48, 0x02, 0x48, 0x02, // 69
0x00, 0x00, 0xF8, 0x03, 0x48, 0x00, 0x48, 0x00, 0x08, // 70
0x00, 0x00, 0xE0, 0x00, 0x10, 0x01, 0x08, 0x02, 0x48, 0x02, 0x50, 0x01, 0xC0, // 71
0x00, 0x00, 0xF8, 0x03, 0x40, 0x00, 0x40, 0x00, 0x40, 0x00, 0xF8, 0x03, // 72
0x00, 0x00, 0xF8, 0x03, // 73
0x00, 0x03, 0x00, 0x02, 0x00, 0x02, 0xF8, 0x01, // 74
0x00, 0x00, 0xF8, 0x03, 0x80, 0x00, 0x60, 0x00, 0x90, 0x00, 0x08, 0x01, 0x00, 0x02, // 75
0x00, 0x00, 0xF8, 0x03, 0x00, 0x02, 0x00, 0x02, 0x00, 0x02, 0x00, 0x02, // 76
0x00, 0x00, 0xF8, 0x03, 0x30, 0x00, 0xC0, 0x01, 0x00, 0x02, 0xC0, 0x01, 0x30, 0x00, 0xF8, 0x03, // 77
0x00, 0x00, 0xF8, 0x03, 0x30, 0x00, 0x40, 0x00, 0x80, 0x01, 0xF8, 0x03, // 78
0x00, 0x00, 0xF0, 0x01, 0x08, 0x02, 0x08, 0x02, 0x08, 0x02, 0x08, 0x02, 0xF0, 0x01, // 79
0x00, 0x00, 0xF8, 0x03, 0x48, 0x00, 0x48, 0x00, 0x48, 0x00, 0x30, // 80
0x00, 0x00, 0xF0, 0x01, 0x08, 0x02, 0x08, 0x02, 0x08, 0x03, 0x08, 0x03, 0xF0, 0x02, // 81
0x00, 0x00, 0xF8, 0x03, 0x48, 0x00, 0x48, 0x00, 0xC8, 0x00, 0x30, 0x03, // 82
0x00, 0x00, 0x30, 0x01, 0x48, 0x02, 0x48, 0x02, 0x48, 0x02, 0x90, 0x01, // 83
0x00, 0x00, 0x08, 0x00, 0x08, 0x00, 0xF8, 0x03, 0x08, 0x00, 0x08, // 84
0x00, 0x00, 0xF8, 0x01, 0x00, 0x02, 0x00, 0x02, 0x00, 0x02, 0xF8, 0x01, // 85
0x08, 0x00, 0x70, 0x00, 0x80, 0x01, 0x00, 0x02, 0x80, 0x01, 0x70, 0x00, 0x08, // 86
0x18, 0x00, 0xE0, 0x01, 0x00, 0x02, 0xF0, 0x01, 0x08, 0x00, 0xF0, 0x01, 0x00, 0x02, 0xE0, 0x01, 0x18, // 87
0x00, 0x02, 0x08, 0x01, 0x90, 0x00, 0x60, 0x00, 0x90, 0x00, 0x08, 0x01, 0x00, 0x02, // 88
0x08, 0x00, 0x10, 0x00, 0x20, 0x00, 0xC0, 0x03, 0x20, 0x00, 0x10, 0x00, 0x08, // 89
0x08, 0x03, 0x88, 0x02, 0xC8, 0x02, 0x68, 0x02, 0x38, 0x02, 0x18, 0x02, // 90
0x00, 0x00, 0xF8, 0x0F, 0x08, 0x08, // 91
0x18, 0x00, 0xE0, 0x00, 0x00, 0x03, // 92
0x08, 0x08, 0xF8, 0x0F, // 93
0x40, 0x00, 0x30, 0x00, 0x08, 0x00, 0x30, 0x00, 0x40, // 94
0x00, 0x08, 0x00, 0x08, 0x00, 0x08, 0x00, 0x08, 0x00, 0x08, 0x00, 0x08, // 95
0x08, 0x00, 0x10, // 96
0x00, 0x00, 0x00, 0x03, 0xA0, 0x02, 0xA0, 0x02, 0xE0, 0x03, // 97
0x00, 0x00, 0xF8, 0x03, 0x20, 0x02, 0x20, 0x02, 0xC0, 0x01, // 98
0x00, 0x00, 0xC0, 0x01, 0x20, 0x02, 0x20, 0x02, 0x40, 0x01, // 99
0x00, 0x00, 0xC0, 0x01, 0x20, 0x02, 0x20, 0x02, 0xF8, 0x03, // 100
0x00, 0x00, 0xC0, 0x01, 0xA0, 0x02, 0xA0, 0x02, 0xC0, 0x02, // 101
0x20, 0x00, 0xF0, 0x03, 0x28, // 102
0x00, 0x00, 0xC0, 0x05, 0x20, 0x0A, 0x20, 0x0A, 0xE0, 0x07, // 103
0x00, 0x00, 0xF8, 0x03, 0x20, 0x00, 0x20, 0x00, 0xC0, 0x03, // 104
0x00, 0x00, 0xE8, 0x03, // 105
0x00, 0x08, 0xE8, 0x07, // 106
0xF8, 0x03, 0x80, 0x00, 0xC0, 0x01, 0x20, 0x02, // 107
0x00, 0x00, 0xF8, 0x03, // 108
0x00, 0x00, 0xE0, 0x03, 0x20, 0x00, 0x20, 0x00, 0xE0, 0x03, 0x20, 0x00, 0x20, 0x00, 0xC0, 0x03, // 109
0x00, 0x00, 0xE0, 0x03, 0x20, 0x00, 0x20, 0x00, 0xC0, 0x03, // 110
0x00, 0x00, 0xC0, 0x01, 0x20, 0x02, 0x20, 0x02, 0xC0, 0x01, // 111
0x00, 0x00, 0xE0, 0x0F, 0x20, 0x02, 0x20, 0x02, 0xC0, 0x01, // 112
0x00, 0x00, 0xC0, 0x01, 0x20, 0x02, 0x20, 0x02, 0xE0, 0x0F, // 113
0x00, 0x00, 0xE0, 0x03, 0x20, // 114
0x40, 0x02, 0xA0, 0x02, 0xA0, 0x02, 0x20, 0x01, // 115
0x20, 0x00, 0xF8, 0x03, 0x20, 0x02, // 116
0x00, 0x00, 0xE0, 0x01, 0x00, 0x02, 0x00, 0x02, 0xE0, 0x03, // 117
0x20, 0x00, 0xC0, 0x01, 0x00, 0x02, 0xC0, 0x01, 0x20, // 118
0xE0, 0x01, 0x00, 0x02, 0xC0, 0x01, 0x20, 0x00, 0xC0, 0x01, 0x00, 0x02, 0xE0, 0x01, // 119
0x20, 0x02, 0x40, 0x01, 0x80, 0x00, 0x40, 0x01, 0x20, 0x02, // 120
0x20, 0x00, 0xC0, 0x09, 0x00, 0x06, 0xC0, 0x01, 0x20, // 121
0x20, 0x02, 0x20, 0x03, 0xA0, 0x02, 0x60, 0x02, 0x20, 0x02, // 122
0x80, 0x00, 0x78, 0x0F, 0x08, 0x08, // 123
0x00, 0x00, 0xF8, 0x0F, // 124
0x08, 0x08, 0x78, 0x0F, 0x80, // 125
0xC0, 0x00, 0x40, 0x00, 0xC0, 0x00, 0x80, 0x00, 0xC0, // 126
0x00, 0x00, 0xA0, 0x0F, // 161
0x00, 0x00, 0xC0, 0x01, 0xA0, 0x0F, 0x78, 0x02, 0x40, 0x01, // 162
0x40, 0x02, 0x70, 0x03, 0xC8, 0x02, 0x48, 0x02, 0x08, 0x02, 0x10, 0x02, // 163
0x00, 0x00, 0xE0, 0x01, 0x20, 0x01, 0x20, 0x01, 0xE0, 0x01, // 164
0x48, 0x01, 0x70, 0x01, 0xC0, 0x03, 0x70, 0x01, 0x48, 0x01, // 165
0x00, 0x00, 0x38, 0x0F, // 166
0xD0, 0x04, 0x28, 0x09, 0x48, 0x09, 0x48, 0x0A, 0x90, 0x05, // 167
0x08, 0x00, 0x00, 0x00, 0x08, // 168
0xE0, 0x00, 0x10, 0x01, 0x48, 0x02, 0xA8, 0x02, 0xA8, 0x02, 0x10, 0x01, 0xE0, // 169
0x68, 0x00, 0x68, 0x00, 0x68, 0x00, 0x78, // 170
0x00, 0x00, 0x80, 0x01, 0x40, 0x02, 0x80, 0x01, 0x40, 0x02, // 171
0x20, 0x00, 0x20, 0x00, 0x20, 0x00, 0x20, 0x00, 0xE0, // 172
0x80, 0x00, 0x80, // 173
0xE0, 0x00, 0x10, 0x01, 0xE8, 0x02, 0x68, 0x02, 0xC8, 0x02, 0x10, 0x01, 0xE0, // 174
0x02, 0x00, 0x02, 0x00, 0x02, 0x00, 0x02, 0x00, 0x02, 0x00, 0x02, // 175
0x00, 0x00, 0x38, 0x00, 0x28, 0x00, 0x38, // 176
0x40, 0x02, 0x40, 0x02, 0xF0, 0x03, 0x40, 0x02, 0x40, 0x02, // 177
0x48, 0x00, 0x68, 0x00, 0x58, // 178
0x48, 0x00, 0x58, 0x00, 0x68, // 179
0x00, 0x00, 0x10, 0x00, 0x08, // 180
0x00, 0x00, 0xE0, 0x0F, 0x00, 0x02, 0x00, 0x02, 0xE0, 0x03, // 181
0x70, 0x00, 0xF8, 0x0F, 0x08, 0x00, 0xF8, 0x0F, 0x08, // 182
0x00, 0x00, 0x40, // 183
0x00, 0x00, 0x00, 0x14, 0x00, 0x18, // 184
0x00, 0x00, 0x10, 0x00, 0x78, // 185
0x30, 0x00, 0x48, 0x00, 0x48, 0x00, 0x30, // 186
0x00, 0x00, 0x40, 0x02, 0x80, 0x01, 0x40, 0x02, 0x80, 0x01, // 187
0x00, 0x00, 0x10, 0x02, 0x78, 0x01, 0xC0, 0x00, 0x20, 0x01, 0x90, 0x01, 0xC8, 0x03, 0x00, 0x01, // 188
0x00, 0x00, 0x10, 0x02, 0x78, 0x01, 0x80, 0x00, 0x60, 0x00, 0x50, 0x02, 0x48, 0x03, 0xC0, 0x02, // 189
0x48, 0x00, 0x58, 0x00, 0x68, 0x03, 0x80, 0x00, 0x60, 0x01, 0x90, 0x01, 0xC8, 0x03, 0x00, 0x01, // 190
0x00, 0x00, 0x00, 0x06, 0x00, 0x09, 0xA0, 0x09, 0x00, 0x04, // 191
0x00, 0x02, 0xC0, 0x01, 0xB0, 0x00, 0x89, 0x00, 0xB2, 0x00, 0xC0, 0x01, 0x00, 0x02, // 192
0x00, 0x02, 0xC0, 0x01, 0xB0, 0x00, 0x8A, 0x00, 0xB1, 0x00, 0xC0, 0x01, 0x00, 0x02, // 193
0x00, 0x02, 0xC0, 0x01, 0xB2, 0x00, 0x89, 0x00, 0xB2, 0x00, 0xC0, 0x01, 0x00, 0x02, // 194
0x00, 0x02, 0xC2, 0x01, 0xB1, 0x00, 0x8A, 0x00, 0xB1, 0x00, 0xC0, 0x01, 0x00, 0x02, // 195
0x00, 0x02, 0xC0, 0x01, 0xB2, 0x00, 0x88, 0x00, 0xB2, 0x00, 0xC0, 0x01, 0x00, 0x02, // 196
0x00, 0x02, 0xC0, 0x01, 0xBE, 0x00, 0x8A, 0x00, 0xBE, 0x00, 0xC0, 0x01, 0x00, 0x02, // 197
0x00, 0x03, 0xC0, 0x00, 0xE0, 0x00, 0x98, 0x00, 0x88, 0x00, 0xF8, 0x03, 0x48, 0x02, 0x48, 0x02, 0x48, 0x02, // 198
0x00, 0x00, 0xF0, 0x01, 0x08, 0x02, 0x08, 0x16, 0x08, 0x1A, 0x10, 0x01, // 199
0x00, 0x00, 0xF8, 0x03, 0x49, 0x02, 0x4A, 0x02, 0x48, 0x02, 0x48, 0x02, // 200
0x00, 0x00, 0xF8, 0x03, 0x48, 0x02, 0x4A, 0x02, 0x49, 0x02, 0x48, 0x02, // 201
0x00, 0x00, 0xFA, 0x03, 0x49, 0x02, 0x4A, 0x02, 0x48, 0x02, 0x48, 0x02, // 202
0x00, 0x00, 0xF8, 0x03, 0x4A, 0x02, 0x48, 0x02, 0x4A, 0x02, 0x48, 0x02, // 203
0x00, 0x00, 0xF9, 0x03, 0x02, // 204
0x02, 0x00, 0xF9, 0x03, // 205
0x01, 0x00, 0xFA, 0x03, // 206
0x02, 0x00, 0xF8, 0x03, 0x02, // 207
0x40, 0x00, 0xF8, 0x03, 0x48, 0x02, 0x48, 0x02, 0x10, 0x01, 0xE0, // 208
0x00, 0x00, 0xFA, 0x03, 0x31, 0x00, 0x42, 0x00, 0x81, 0x01, 0xF8, 0x03, // 209
0x00, 0x00, 0xF0, 0x01, 0x08, 0x02, 0x09, 0x02, 0x0A, 0x02, 0x08, 0x02, 0xF0, 0x01, // 210
0x00, 0x00, 0xF0, 0x01, 0x08, 0x02, 0x0A, 0x02, 0x09, 0x02, 0x08, 0x02, 0xF0, 0x01, // 211
0x00, 0x00, 0xF0, 0x01, 0x08, 0x02, 0x0A, 0x02, 0x09, 0x02, 0x0A, 0x02, 0xF0, 0x01, // 212
0x00, 0x00, 0xF0, 0x01, 0x0A, 0x02, 0x09, 0x02, 0x0A, 0x02, 0x09, 0x02, 0xF0, 0x01, // 213
0x00, 0x00, 0xF0, 0x01, 0x0A, 0x02, 0x08, 0x02, 0x0A, 0x02, 0x08, 0x02, 0xF0, 0x01, // 214
0x10, 0x01, 0xA0, 0x00, 0xE0, 0x00, 0xA0, 0x00, 0x10, 0x01, // 215
0x00, 0x00, 0xF0, 0x02, 0x08, 0x03, 0xC8, 0x02, 0x28, 0x02, 0x18, 0x03, 0xE8, // 216
0x00, 0x00, 0xF8, 0x01, 0x01, 0x02, 0x02, 0x02, 0x00, 0x02, 0xF8, 0x01, // 217
0x00, 0x00, 0xF8, 0x01, 0x02, 0x02, 0x01, 0x02, 0x00, 0x02, 0xF8, 0x01, // 218
0x00, 0x00, 0xF8, 0x01, 0x02, 0x02, 0x01, 0x02, 0x02, 0x02, 0xF8, 0x01, // 219
0x00, 0x00, 0xF8, 0x01, 0x02, 0x02, 0x00, 0x02, 0x02, 0x02, 0xF8, 0x01, // 220
0x08, 0x00, 0x10, 0x00, 0x20, 0x00, 0xC2, 0x03, 0x21, 0x00, 0x10, 0x00, 0x08, // 221
0x00, 0x00, 0xF8, 0x03, 0x10, 0x01, 0x10, 0x01, 0x10, 0x01, 0xE0, // 222
0x00, 0x00, 0xF0, 0x03, 0x08, 0x01, 0x48, 0x02, 0xB0, 0x02, 0x80, 0x01, // 223
0x00, 0x00, 0x00, 0x03, 0xA4, 0x02, 0xA8, 0x02, 0xE0, 0x03, // 224
0x00, 0x00, 0x00, 0x03, 0xA8, 0x02, 0xA4, 0x02, 0xE0, 0x03, // 225
0x00, 0x00, 0x00, 0x03, 0xA8, 0x02, 0xA4, 0x02, 0xE8, 0x03, // 226
0x00, 0x00, 0x08, 0x03, 0xA4, 0x02, 0xA8, 0x02, 0xE4, 0x03, // 227
0x00, 0x00, 0x00, 0x03, 0xA8, 0x02, 0xA0, 0x02, 0xE8, 0x03, // 228
0x00, 0x00, 0x00, 0x03, 0xAE, 0x02, 0xAA, 0x02, 0xEE, 0x03, // 229
0x00, 0x00, 0x40, 0x03, 0xA0, 0x02, 0xA0, 0x02, 0xC0, 0x01, 0xA0, 0x02, 0xA0, 0x02, 0xC0, 0x02, // 230
0x00, 0x00, 0xC0, 0x01, 0x20, 0x16, 0x20, 0x1A, 0x40, 0x01, // 231
0x00, 0x00, 0xC0, 0x01, 0xA4, 0x02, 0xA8, 0x02, 0xC0, 0x02, // 232
0x00, 0x00, 0xC0, 0x01, 0xA8, 0x02, 0xA4, 0x02, 0xC0, 0x02, // 233
0x00, 0x00, 0xC0, 0x01, 0xA8, 0x02, 0xA4, 0x02, 0xC8, 0x02, // 234
0x00, 0x00, 0xC0, 0x01, 0xA8, 0x02, 0xA0, 0x02, 0xC8, 0x02, // 235
0x00, 0x00, 0xE4, 0x03, 0x08, // 236
0x08, 0x00, 0xE4, 0x03, // 237
0x08, 0x00, 0xE4, 0x03, 0x08, // 238
0x08, 0x00, 0xE0, 0x03, 0x08, // 239
0x00, 0x00, 0xC0, 0x01, 0x28, 0x02, 0x38, 0x02, 0xE0, 0x01, // 240
0x00, 0x00, 0xE8, 0x03, 0x24, 0x00, 0x28, 0x00, 0xC4, 0x03, // 241
0x00, 0x00, 0xC0, 0x01, 0x24, 0x02, 0x28, 0x02, 0xC0, 0x01, // 242
0x00, 0x00, 0xC0, 0x01, 0x28, 0x02, 0x24, 0x02, 0xC0, 0x01, // 243
0x00, 0x00, 0xC0, 0x01, 0x28, 0x02, 0x24, 0x02, 0xC8, 0x01, // 244
0x00, 0x00, 0xC8, 0x01, 0x24, 0x02, 0x28, 0x02, 0xC4, 0x01, // 245
0x00, 0x00, 0xC0, 0x01, 0x28, 0x02, 0x20, 0x02, 0xC8, 0x01, // 246
0x40, 0x00, 0x40, 0x00, 0x50, 0x01, 0x40, 0x00, 0x40, // 247
0x00, 0x00, 0xC0, 0x02, 0xA0, 0x03, 0x60, 0x02, 0xA0, 0x01, // 248
0x00, 0x00, 0xE0, 0x01, 0x04, 0x02, 0x08, 0x02, 0xE0, 0x03, // 249
0x00, 0x00, 0xE0, 0x01, 0x08, 0x02, 0x04, 0x02, 0xE0, 0x03, // 250
0x00, 0x00, 0xE8, 0x01, 0x04, 0x02, 0x08, 0x02, 0xE0, 0x03, // 251
0x00, 0x00, 0xE0, 0x01, 0x08, 0x02, 0x00, 0x02, 0xE8, 0x03, // 252
0x20, 0x00, 0xC0, 0x09, 0x08, 0x06, 0xC4, 0x01, 0x20, // 253
0x00, 0x00, 0xF8, 0x0F, 0x20, 0x02, 0x20, 0x02, 0xC0, 0x01, // 254
0x20, 0x00, 0xC8, 0x09, 0x00, 0x06, 0xC8, 0x01, 0x20 // 255
};

Wyświetl plik

@ -1,11 +1,8 @@
#define SATELLITE_IMAGE_WIDTH 16
#define SATELLITE_IMAGE_HEIGHT 15
const uint8_t SATELLITE_IMAGE[] PROGMEM = {
0x00, 0x08, 0x00, 0x1C, 0x00, 0x0E, 0x20, 0x07, 0x70, 0x02, 0xF8, 0x00,
0xF0, 0x01, 0xE0, 0x03, 0xC8, 0x01, 0x9C, 0x54, 0x0E, 0x52, 0x07, 0x48,
0x02, 0x26, 0x00, 0x10, 0x00, 0x0E
};
const uint8_t SATELLITE_IMAGE[] PROGMEM = {0x00, 0x08, 0x00, 0x1C, 0x00, 0x0E, 0x20, 0x07, 0x70, 0x02,
0xF8, 0x00, 0xF0, 0x01, 0xE0, 0x03, 0xC8, 0x01, 0x9C, 0x54,
0x0E, 0x52, 0x07, 0x48, 0x02, 0x26, 0x00, 0x10, 0x00, 0x0E};
const
#include "icon.xbm"
@ -14,7 +11,7 @@ const
#if 0
const
#include "compass.xbm"
#endif
#endif
#if 0
const uint8_t activeSymbol[] PROGMEM = {

Wyświetl plik

@ -9,38 +9,38 @@ namespace meshtastic
// Simple wrapper around FreeRTOS API for implementing a mutex lock.
class Lock
{
public:
Lock();
public:
Lock();
Lock(const Lock &) = delete;
Lock &operator=(const Lock &) = delete;
Lock(const Lock &) = delete;
Lock &operator=(const Lock &) = delete;
/// Locks the lock.
//
// Must not be called from an ISR.
void lock();
/// Locks the lock.
//
// Must not be called from an ISR.
void lock();
// Unlocks the lock.
//
// Must not be called from an ISR.
void unlock();
// Unlocks the lock.
//
// Must not be called from an ISR.
void unlock();
private:
SemaphoreHandle_t handle;
private:
SemaphoreHandle_t handle;
};
// RAII lock guard.
class LockGuard
{
public:
LockGuard(Lock *lock);
~LockGuard();
public:
LockGuard(Lock *lock);
~LockGuard();
LockGuard(const LockGuard &) = delete;
LockGuard &operator=(const LockGuard &) = delete;
LockGuard(const LockGuard &) = delete;
LockGuard &operator=(const LockGuard &) = delete;
private:
Lock *lock;
private:
Lock *lock;
};
} // namespace meshtastic

Wyświetl plik

@ -21,22 +21,22 @@
*/
#include "configuration.h"
#include "rom/rtc.h"
#include <driver/rtc_io.h>
#include <Wire.h>
#include "BluetoothUtil.h"
#include "MeshBluetoothService.h"
#include "MeshService.h"
#include "GPS.h"
#include "screen.h"
#include "MeshBluetoothService.h"
#include "MeshRadio.h"
#include "MeshService.h"
#include "NodeDB.h"
#include "Periodic.h"
#include "PowerFSM.h"
#include "configuration.h"
#include "esp32/pm.h"
#include "esp_pm.h"
#include "MeshRadio.h"
#include "rom/rtc.h"
#include "screen.h"
#include "sleep.h"
#include "PowerFSM.h"
#include <Wire.h>
#include <driver/rtc_io.h>
#ifdef T_BEAM_V10
#include "axp20x.h"
@ -67,84 +67,74 @@ bool bluetoothOn;
void scanI2Cdevice(void)
{
byte err, addr;
int nDevices = 0;
for (addr = 1; addr < 127; addr++)
{
Wire.beginTransmission(addr);
err = Wire.endTransmission();
if (err == 0)
{
DEBUG_MSG("I2C device found at address 0x%x\n", addr);
byte err, addr;
int nDevices = 0;
for (addr = 1; addr < 127; addr++) {
Wire.beginTransmission(addr);
err = Wire.endTransmission();
if (err == 0) {
DEBUG_MSG("I2C device found at address 0x%x\n", addr);
nDevices++;
nDevices++;
if (addr == SSD1306_ADDRESS)
{
ssd1306_found = true;
DEBUG_MSG("ssd1306 display found\n");
}
if (addr == SSD1306_ADDRESS) {
ssd1306_found = true;
DEBUG_MSG("ssd1306 display found\n");
}
#ifdef T_BEAM_V10
if (addr == AXP192_SLAVE_ADDRESS)
{
axp192_found = true;
DEBUG_MSG("axp192 PMU found\n");
}
if (addr == AXP192_SLAVE_ADDRESS) {
axp192_found = true;
DEBUG_MSG("axp192 PMU found\n");
}
#endif
} else if (err == 4) {
DEBUG_MSG("Unknow error at address 0x%x\n", addr);
}
}
else if (err == 4)
{
DEBUG_MSG("Unknow error at address 0x%x\n", addr);
}
}
if (nDevices == 0)
DEBUG_MSG("No I2C devices found\n");
else
DEBUG_MSG("done\n");
if (nDevices == 0)
DEBUG_MSG("No I2C devices found\n");
else
DEBUG_MSG("done\n");
}
/**
* Init the power manager chip
*
* axp192 power
DCDC1 0.7-3.5V @ 1200mA max -> OLED // If you turn this off you'll lose comms to the axp192 because the OLED and the axp192 share the same i2c bus, instead use ssd1306 sleep mode
DCDC2 -> unused
DCDC3 0.7-3.5V @ 700mA max -> ESP32 (keep this on!)
LDO1 30mA -> charges GPS backup battery // charges the tiny J13 battery by the GPS to power the GPS ram (for a couple of days), can not be turned off
LDO2 200mA -> LORA
LDO3 200mA -> GPS
*
* axp192 power
DCDC1 0.7-3.5V @ 1200mA max -> OLED // If you turn this off you'll lose comms to the axp192 because the OLED and the axp192
share the same i2c bus, instead use ssd1306 sleep mode DCDC2 -> unused DCDC3 0.7-3.5V @ 700mA max -> ESP32 (keep this on!) LDO1
30mA -> charges GPS backup battery // charges the tiny J13 battery by the GPS to power the GPS ram (for a couple of days), can
not be turned off LDO2 200mA -> LORA LDO3 200mA -> GPS
*/
void axp192Init()
{
#ifdef T_BEAM_V10
if (axp192_found)
{
if (!axp.begin(Wire, AXP192_SLAVE_ADDRESS))
{
DEBUG_MSG("AXP192 Begin PASS\n");
if (axp192_found) {
if (!axp.begin(Wire, AXP192_SLAVE_ADDRESS)) {
DEBUG_MSG("AXP192 Begin PASS\n");
// axp.setChgLEDMode(LED_BLINK_4HZ);
DEBUG_MSG("DCDC1: %s\n", axp.isDCDC1Enable() ? "ENABLE" : "DISABLE");
DEBUG_MSG("DCDC2: %s\n", axp.isDCDC2Enable() ? "ENABLE" : "DISABLE");
DEBUG_MSG("LDO2: %s\n", axp.isLDO2Enable() ? "ENABLE" : "DISABLE");
DEBUG_MSG("LDO3: %s\n", axp.isLDO3Enable() ? "ENABLE" : "DISABLE");
DEBUG_MSG("DCDC3: %s\n", axp.isDCDC3Enable() ? "ENABLE" : "DISABLE");
DEBUG_MSG("Exten: %s\n", axp.isExtenEnable() ? "ENABLE" : "DISABLE");
DEBUG_MSG("----------------------------------------\n");
// axp.setChgLEDMode(LED_BLINK_4HZ);
DEBUG_MSG("DCDC1: %s\n", axp.isDCDC1Enable() ? "ENABLE" : "DISABLE");
DEBUG_MSG("DCDC2: %s\n", axp.isDCDC2Enable() ? "ENABLE" : "DISABLE");
DEBUG_MSG("LDO2: %s\n", axp.isLDO2Enable() ? "ENABLE" : "DISABLE");
DEBUG_MSG("LDO3: %s\n", axp.isLDO3Enable() ? "ENABLE" : "DISABLE");
DEBUG_MSG("DCDC3: %s\n", axp.isDCDC3Enable() ? "ENABLE" : "DISABLE");
DEBUG_MSG("Exten: %s\n", axp.isExtenEnable() ? "ENABLE" : "DISABLE");
DEBUG_MSG("----------------------------------------\n");
axp.setPowerOutPut(AXP192_LDO2, AXP202_ON); // LORA radio
axp.setPowerOutPut(AXP192_LDO3, AXP202_ON); // GPS main power
axp.setPowerOutPut(AXP192_DCDC2, AXP202_ON);
axp.setPowerOutPut(AXP192_EXTEN, AXP202_ON);
axp.setPowerOutPut(AXP192_DCDC1, AXP202_ON);
axp.setDCDC1Voltage(3300); // for the OLED power
axp.setPowerOutPut(AXP192_LDO2, AXP202_ON); // LORA radio
axp.setPowerOutPut(AXP192_LDO3, AXP202_ON); // GPS main power
axp.setPowerOutPut(AXP192_DCDC2, AXP202_ON);
axp.setPowerOutPut(AXP192_EXTEN, AXP202_ON);
axp.setPowerOutPut(AXP192_DCDC1, AXP202_ON);
axp.setDCDC1Voltage(3300); // for the OLED power
DEBUG_MSG("DCDC1: %s\n", axp.isDCDC1Enable() ? "ENABLE" : "DISABLE");
DEBUG_MSG("DCDC2: %s\n", axp.isDCDC2Enable() ? "ENABLE" : "DISABLE");
DEBUG_MSG("LDO2: %s\n", axp.isLDO2Enable() ? "ENABLE" : "DISABLE");
DEBUG_MSG("LDO3: %s\n", axp.isLDO3Enable() ? "ENABLE" : "DISABLE");
DEBUG_MSG("DCDC3: %s\n", axp.isDCDC3Enable() ? "ENABLE" : "DISABLE");
DEBUG_MSG("Exten: %s\n", axp.isExtenEnable() ? "ENABLE" : "DISABLE");
DEBUG_MSG("DCDC1: %s\n", axp.isDCDC1Enable() ? "ENABLE" : "DISABLE");
DEBUG_MSG("DCDC2: %s\n", axp.isDCDC2Enable() ? "ENABLE" : "DISABLE");
DEBUG_MSG("LDO2: %s\n", axp.isLDO2Enable() ? "ENABLE" : "DISABLE");
DEBUG_MSG("LDO3: %s\n", axp.isLDO3Enable() ? "ENABLE" : "DISABLE");
DEBUG_MSG("DCDC3: %s\n", axp.isDCDC3Enable() ? "ENABLE" : "DISABLE");
DEBUG_MSG("Exten: %s\n", axp.isExtenEnable() ? "ENABLE" : "DISABLE");
#if 0
// cribbing from https://github.com/m5stack/M5StickC/blob/master/src/AXP192.cpp to fix charger to be more like 300ms.
@ -165,163 +155,154 @@ void axp192Init()
//val = 0x46;
//axp._writeByte(AXP202_OFF_CTL, 1, &val); // enable bat detection
#endif
axp.debugCharging();
axp.debugCharging();
#ifdef PMU_IRQ
pinMode(PMU_IRQ, INPUT_PULLUP);
attachInterrupt(PMU_IRQ, [] {
pmu_irq = true;
},
RISING);
pinMode(PMU_IRQ, INPUT_PULLUP);
attachInterrupt(
PMU_IRQ, [] { pmu_irq = true; }, RISING);
axp.adc1Enable(AXP202_BATT_CUR_ADC1, 1);
axp.enableIRQ(AXP202_VBUS_REMOVED_IRQ | AXP202_VBUS_CONNECT_IRQ | AXP202_BATT_REMOVED_IRQ | AXP202_BATT_CONNECT_IRQ, 1);
axp.clearIRQ();
axp.adc1Enable(AXP202_BATT_CUR_ADC1, 1);
axp.enableIRQ(AXP202_VBUS_REMOVED_IRQ | AXP202_VBUS_CONNECT_IRQ | AXP202_BATT_REMOVED_IRQ | AXP202_BATT_CONNECT_IRQ,
1);
axp.clearIRQ();
#endif
isCharging = axp.isChargeing() ? 1 : 0;
isUSBPowered = axp.isVBUSPlug() ? 1 : 0;
isCharging = axp.isChargeing() ? 1 : 0;
isUSBPowered = axp.isVBUSPlug() ? 1 : 0;
} else {
DEBUG_MSG("AXP192 Begin FAIL\n");
}
} else {
DEBUG_MSG("AXP192 not found\n");
}
else
{
DEBUG_MSG("AXP192 Begin FAIL\n");
}
}
else
{
DEBUG_MSG("AXP192 not found\n");
}
#endif
}
const char *getDeviceName()
{
uint8_t dmac[6];
assert(esp_efuse_mac_get_default(dmac) == ESP_OK);
uint8_t dmac[6];
assert(esp_efuse_mac_get_default(dmac) == ESP_OK);
// Meshtastic_ab3c
static char name[20];
sprintf(name, "Meshtastic_%02x%02x", dmac[4], dmac[5]);
return name;
// Meshtastic_ab3c
static char name[20];
sprintf(name, "Meshtastic_%02x%02x", dmac[4], dmac[5]);
return name;
}
void setup()
{
// Debug
#ifdef DEBUG_PORT
DEBUG_PORT.begin(SERIAL_BAUD);
DEBUG_PORT.begin(SERIAL_BAUD);
#endif
initDeepSleep();
initDeepSleep();
#ifdef VEXT_ENABLE
pinMode(VEXT_ENABLE, OUTPUT);
digitalWrite(VEXT_ENABLE, 0); // turn on the display power
pinMode(VEXT_ENABLE, OUTPUT);
digitalWrite(VEXT_ENABLE, 0); // turn on the display power
#endif
#ifdef RESET_OLED
pinMode(RESET_OLED, OUTPUT);
digitalWrite(RESET_OLED, 1);
pinMode(RESET_OLED, OUTPUT);
digitalWrite(RESET_OLED, 1);
#endif
#ifdef I2C_SDA
Wire.begin(I2C_SDA, I2C_SCL);
scanI2Cdevice();
Wire.begin(I2C_SDA, I2C_SCL);
scanI2Cdevice();
#endif
// Buttons & LED
// Buttons & LED
#ifdef BUTTON_PIN
pinMode(BUTTON_PIN, INPUT_PULLUP);
digitalWrite(BUTTON_PIN, 1);
pinMode(BUTTON_PIN, INPUT_PULLUP);
digitalWrite(BUTTON_PIN, 1);
#endif
#ifdef LED_PIN
pinMode(LED_PIN, OUTPUT);
digitalWrite(LED_PIN, 1); // turn on for now
pinMode(LED_PIN, OUTPUT);
digitalWrite(LED_PIN, 1); // turn on for now
#endif
// Hello
DEBUG_MSG("Meshtastic swver=%s, hwver=%s\n", xstr(APP_VERSION), xstr(HW_VERSION));
// Hello
DEBUG_MSG("Meshtastic swver=%s, hwver=%s\n", xstr(APP_VERSION), xstr(HW_VERSION));
// Don't init display if we don't have one or we are waking headless due to a timer event
if (wakeCause == ESP_SLEEP_WAKEUP_TIMER)
ssd1306_found = false; // forget we even have the hardware
// Don't init display if we don't have one or we are waking headless due to a timer event
if (wakeCause == ESP_SLEEP_WAKEUP_TIMER)
ssd1306_found = false; // forget we even have the hardware
// Initialize the screen first so we can show the logo while we start up everything else.
if (ssd1306_found)
screen.setup();
// Initialize the screen first so we can show the logo while we start up everything else.
if (ssd1306_found)
screen.setup();
axp192Init();
axp192Init();
screen.print("Started...\n");
screen.print("Started...\n");
// Init GPS
gps.setup();
// Init GPS
gps.setup();
service.init();
service.init();
// This must be _after_ service.init because we need our preferences loaded from flash to have proper timeout values
PowerFSM_setup(); // we will transition to ON in a couple of seconds, FIXME, only do this for cold boots, not waking from SDS
// This must be _after_ service.init because we need our preferences loaded from flash to have proper timeout values
PowerFSM_setup(); // we will transition to ON in a couple of seconds, FIXME, only do this for cold boots, not waking from SDS
// setBluetoothEnable(false); we now don't start bluetooth until we enter the proper state
setCPUFast(false); // 80MHz is fine for our slow peripherals
// setBluetoothEnable(false); we now don't start bluetooth until we enter the proper state
setCPUFast(false); // 80MHz is fine for our slow peripherals
}
void initBluetooth()
{
DEBUG_MSG("Starting bluetooth\n");
DEBUG_MSG("Starting bluetooth\n");
// FIXME - we are leaking like crazy
// AllocatorScope scope(btPool);
// FIXME - we are leaking like crazy
// AllocatorScope scope(btPool);
// Note: these callbacks might be coming in from a different thread.
BLEServer *serve = initBLE(
[](uint8_t pin) {
powerFSM.trigger(EVENT_BLUETOOTH_PAIR);
screen.startBluetoothPinScreen(pin);
},
[]() { screen.stopBluetoothPinScreen(); },
getDeviceName(), HW_VENDOR, xstr(APP_VERSION), xstr(HW_VERSION)); // FIXME, use a real name based on the macaddr
createMeshBluetoothService(serve);
// Note: these callbacks might be coming in from a different thread.
BLEServer *serve = initBLE(
[](uint8_t pin) {
powerFSM.trigger(EVENT_BLUETOOTH_PAIR);
screen.startBluetoothPinScreen(pin);
},
[]() { screen.stopBluetoothPinScreen(); }, getDeviceName(), HW_VENDOR, xstr(APP_VERSION),
xstr(HW_VERSION)); // FIXME, use a real name based on the macaddr
createMeshBluetoothService(serve);
// Start advertising - this must be done _after_ creating all services
serve->getAdvertising()->start();
// Start advertising - this must be done _after_ creating all services
serve->getAdvertising()->start();
}
void setBluetoothEnable(bool on)
{
if (on != bluetoothOn)
{
DEBUG_MSG("Setting bluetooth enable=%d\n", on);
if (on != bluetoothOn) {
DEBUG_MSG("Setting bluetooth enable=%d\n", on);
bluetoothOn = on;
if (on)
{
Serial.printf("Pre BT: %u heap size\n", ESP.getFreeHeap());
//ESP_ERROR_CHECK( heap_trace_start(HEAP_TRACE_LEAKS) );
initBluetooth();
bluetoothOn = on;
if (on) {
Serial.printf("Pre BT: %u heap size\n", ESP.getFreeHeap());
// ESP_ERROR_CHECK( heap_trace_start(HEAP_TRACE_LEAKS) );
initBluetooth();
} else {
// We have to totally teardown our bluetooth objects to prevent leaks
stopMeshBluetoothService(); // Must do before shutting down bluetooth
deinitBLE();
destroyMeshBluetoothService(); // must do after deinit, because it frees our service
Serial.printf("Shutdown BT: %u heap size\n", ESP.getFreeHeap());
// ESP_ERROR_CHECK( heap_trace_stop() );
// heap_trace_dump();
}
}
else
{
// We have to totally teardown our bluetooth objects to prevent leaks
stopMeshBluetoothService(); // Must do before shutting down bluetooth
deinitBLE();
destroyMeshBluetoothService(); // must do after deinit, because it frees our service
Serial.printf("Shutdown BT: %u heap size\n", ESP.getFreeHeap());
//ESP_ERROR_CHECK( heap_trace_stop() );
//heap_trace_dump();
}
}
}
uint32_t ledBlinker()
{
static bool ledOn;
ledOn ^= 1;
static bool ledOn;
ledOn ^= 1;
setLed(ledOn);
setLed(ledOn);
// have a very sparse duty cycle of LED being on, unless charging, then blink 0.5Hz square wave rate to indicate that
return isCharging ? 1000 : (ledOn ? 2 : 1000);
// have a very sparse duty cycle of LED being on, unless charging, then blink 0.5Hz square wave rate to indicate that
return isCharging ? 1000 : (ledOn ? 2 : 1000);
}
Periodic ledPeriodic(ledBlinker);
@ -345,83 +326,77 @@ Periodic axpDebugOutput(axpReads);
void loop()
{
uint32_t msecstosleep = 1000 * 30; // How long can we sleep before we again need to service the main loop?
uint32_t msecstosleep = 1000 * 30; // How long can we sleep before we again need to service the main loop?
powerFSM.run_machine();
gps.loop();
screen.loop();
service.loop();
powerFSM.run_machine();
gps.loop();
screen.loop();
service.loop();
ledPeriodic.loop();
// axpDebugOutput.loop();
loopBLE();
ledPeriodic.loop();
// axpDebugOutput.loop();
loopBLE();
// for debug printing
// service.radio.rf95.canSleep();
// for debug printing
// service.radio.rf95.canSleep();
#ifdef T_BEAM_V10
if (axp192_found)
{
if (axp192_found) {
#ifdef PMU_IRQ
if (pmu_irq)
{
pmu_irq = false;
axp.readIRQ();
if (pmu_irq) {
pmu_irq = false;
axp.readIRQ();
DEBUG_MSG("pmu irq!\n");
DEBUG_MSG("pmu irq!\n");
isCharging = axp.isChargeing() ? 1 : 0;
isUSBPowered = axp.isVBUSPlug() ? 1 : 0;
isCharging = axp.isChargeing() ? 1 : 0;
isUSBPowered = axp.isVBUSPlug() ? 1 : 0;
axp.clearIRQ();
}
axp.clearIRQ();
}
// FIXME AXP192 interrupt is not firing, remove this temporary polling of battery state
isCharging = axp.isChargeing() ? 1 : 0;
isUSBPowered = axp.isVBUSPlug() ? 1 : 0;
// FIXME AXP192 interrupt is not firing, remove this temporary polling of battery state
isCharging = axp.isChargeing() ? 1 : 0;
isUSBPowered = axp.isVBUSPlug() ? 1 : 0;
#endif
}
}
#endif
#ifdef BUTTON_PIN
// if user presses button for more than 3 secs, discard our network prefs and reboot (FIXME, use a debounce lib instead of this boilerplate)
static bool wasPressed = false;
// if user presses button for more than 3 secs, discard our network prefs and reboot (FIXME, use a debounce lib instead of
// this boilerplate)
static bool wasPressed = false;
if (!digitalRead(BUTTON_PIN))
{
if (!wasPressed)
{ // just started a new press
DEBUG_MSG("pressing\n");
if (!digitalRead(BUTTON_PIN)) {
if (!wasPressed) { // just started a new press
DEBUG_MSG("pressing\n");
//doLightSleep();
// esp_pm_dump_locks(stdout); // FIXME, do this someplace better
wasPressed = true;
// doLightSleep();
// esp_pm_dump_locks(stdout); // FIXME, do this someplace better
wasPressed = true;
powerFSM.trigger(EVENT_PRESS);
powerFSM.trigger(EVENT_PRESS);
}
} else if (wasPressed) {
// we just did a release
wasPressed = false;
}
}
else if (wasPressed)
{
// we just did a release
wasPressed = false;
}
#endif
// Show boot screen for first 3 seconds, then switch to normal operation.
static bool showingBootScreen = true;
if (showingBootScreen && (millis() > 3000))
{
screen.stopBootScreen();
showingBootScreen = false;
}
// Show boot screen for first 3 seconds, then switch to normal operation.
static bool showingBootScreen = true;
if (showingBootScreen && (millis() > 3000)) {
screen.stopBootScreen();
showingBootScreen = false;
}
// No GPS lock yet, let the OS put the main CPU in low power mode for 100ms (or until another interrupt comes in)
// i.e. don't just keep spinning in loop as fast as we can.
//DEBUG_MSG("msecs %d\n", msecstosleep);
// No GPS lock yet, let the OS put the main CPU in low power mode for 100ms (or until another interrupt comes in)
// i.e. don't just keep spinning in loop as fast as we can.
// DEBUG_MSG("msecs %d\n", msecstosleep);
// FIXME - until button press handling is done by interrupt (see polling above) we can't sleep very long at all or buttons feel slow
msecstosleep = 10;
// FIXME - until button press handling is done by interrupt (see polling above) we can't sleep very long at all or buttons
// feel slow
msecstosleep = 10;
delay(msecstosleep);
delay(msecstosleep);
}

Wyświetl plik

@ -1,10 +1,10 @@
#include <Arduino.h>
#include "configuration.h"
#include "mesh-pb-constants.h"
#include <pb_encode.h>
#include <pb_decode.h>
#include <assert.h>
#include "FS.h"
#include "configuration.h"
#include <Arduino.h>
#include <assert.h>
#include <pb_decode.h>
#include <pb_encode.h>
/// helper function for encoding a record as a protobuf, any failures to encode are fatal and we will panic
/// returns the encoded packet size
@ -12,42 +12,33 @@ size_t pb_encode_to_bytes(uint8_t *destbuf, size_t destbufsize, const pb_msgdesc
{
pb_ostream_t stream = pb_ostream_from_buffer(destbuf, destbufsize);
if (!pb_encode(&stream, fields, src_struct))
{
if (!pb_encode(&stream, fields, src_struct)) {
DEBUG_MSG("Error: can't encode protobuf %s\n", PB_GET_ERROR(&stream));
assert(0); // FIXME - panic
}
else
{
} else {
return stream.bytes_written;
}
}
/// helper function for decoding a record as a protobuf, we will return false if the decoding failed
bool pb_decode_from_bytes(const uint8_t *srcbuf, size_t srcbufsize, const pb_msgdesc_t *fields, void *dest_struct)
{
pb_istream_t stream = pb_istream_from_buffer(srcbuf, srcbufsize);
if (!pb_decode(&stream, fields, dest_struct))
{
if (!pb_decode(&stream, fields, dest_struct)) {
DEBUG_MSG("Error: can't decode protobuf %s, pb_msgdesc 0x%p\n", PB_GET_ERROR(&stream), fields);
return false;
}
else
{
} else {
return true;
}
}
/// Read from an Arduino File
bool readcb(pb_istream_t *stream, uint8_t *buf, size_t count)
{
File *file = (File *)stream->state;
bool status;
if (buf == NULL)
{
if (buf == NULL) {
while (count-- && file->read() != EOF)
;
return count == 0;
@ -61,11 +52,10 @@ bool readcb(pb_istream_t *stream, uint8_t *buf, size_t count)
return status;
}
/// Write to an arduino file
bool writecb(pb_ostream_t *stream, const uint8_t *buf, size_t count)
{
File *file = (File*) stream->state;
//DEBUG_MSG("writing %d bytes to protobuf file\n", count);
return file->write(buf, count) == count;
File *file = (File *)stream->state;
// DEBUG_MSG("writing %d bytes to protobuf file\n", count);
return file->write(buf, count) == count;
}

Wyświetl plik

@ -8,11 +8,10 @@
#define member_size(type, member) sizeof(((type *)0)->member)
/// max number of packets which can be waiting for delivery to android - note, this value comes from mesh.options protobuf
#define MAX_RX_TOPHONE (member_size(DeviceState, receive_queue) / member_size(DeviceState, receive_queue[0]))
#define MAX_RX_TOPHONE (member_size(DeviceState, receive_queue) / member_size(DeviceState, receive_queue[0]))
/// max number of nodes allowed in the mesh
#define MAX_NUM_NODES (member_size(DeviceState, node_db) / member_size(DeviceState, node_db[0]))
#define MAX_NUM_NODES (member_size(DeviceState, node_db) / member_size(DeviceState, node_db[0]))
/// helper function for encoding a record as a protobuf, any failures to encode are fatal and we will panic
/// returns the encoded packet size

Wyświetl plik

@ -96,8 +96,7 @@ static void drawTextMessageFrame(OLEDDisplay *display, OLEDDisplayUiState *state
// the max length of this buffer is much longer than we can possibly print
static char tempBuf[96];
snprintf(tempBuf, sizeof(tempBuf), " %s",
mp.payload.variant.data.payload.bytes);
snprintf(tempBuf, sizeof(tempBuf), " %s", mp.payload.variant.data.payload.bytes);
display->drawStringMaxWidth(4 + x, 10 + y, 128, tempBuf);
}

Wyświetl plik

@ -108,7 +108,7 @@ class Screen : public PeriodicTask
/// Rebuilds our list of frames (screens) to default ones.
void setFrames();
private:
private:
/// Queue of commands to execute in doTask.
TypedQueue<CmdItem> cmdQueue;
/// Whether we are using a display

Wyświetl plik

@ -1,18 +1,18 @@
#include "configuration.h"
#include "rom/rtc.h"
#include <driver/rtc_io.h>
#include <Wire.h>
#include "sleep.h"
#include "BluetoothUtil.h"
#include "MeshBluetoothService.h"
#include "MeshService.h"
#include "GPS.h"
#include "MeshBluetoothService.h"
#include "MeshRadio.h"
#include "MeshService.h"
#include "NodeDB.h"
#include "Periodic.h"
#include "configuration.h"
#include "esp32/pm.h"
#include "esp_pm.h"
#include "MeshRadio.h"
#include "main.h"
#include "sleep.h"
#include "rom/rtc.h"
#include <Wire.h>
#include <driver/rtc_io.h>
#ifdef T_BEAM_V10
#include "axp20x.h"
@ -32,197 +32,204 @@ esp_sleep_source_t wakeCause; // the reason we booted this time
/**
* Control CPU core speed (80MHz vs 240MHz)
*
*
* We leave CPU at full speed during init, but once loop is called switch to low speed (for a 50% power savings)
*
*
*/
void setCPUFast(bool on)
{
setCpuFrequencyMhz(on ? 240 : 80);
setCpuFrequencyMhz(on ? 240 : 80);
}
void setLed(bool ledOn)
{
#ifdef LED_PIN
// toggle the led so we can get some rough sense of how often loop is pausing
digitalWrite(LED_PIN, ledOn);
// toggle the led so we can get some rough sense of how often loop is pausing
digitalWrite(LED_PIN, ledOn);
#endif
#ifdef T_BEAM_V10
if (axp192_found)
{
// blink the axp led
axp.setChgLEDMode(ledOn ? AXP20X_LED_LOW_LEVEL : AXP20X_LED_OFF);
}
if (axp192_found) {
// blink the axp led
axp.setChgLEDMode(ledOn ? AXP20X_LED_LOW_LEVEL : AXP20X_LED_OFF);
}
#endif
}
void setGPSPower(bool on)
{
DEBUG_MSG("Setting GPS power=%d\n", on);
DEBUG_MSG("Setting GPS power=%d\n", on);
#ifdef T_BEAM_V10
if (axp192_found)
axp.setPowerOutPut(AXP192_LDO3, on ? AXP202_ON : AXP202_OFF); // GPS main power
if (axp192_found)
axp.setPowerOutPut(AXP192_LDO3, on ? AXP202_ON : AXP202_OFF); // GPS main power
#endif
}
// Perform power on init that we do on each wake from deep sleep
void initDeepSleep()
{
bootCount++;
wakeCause = esp_sleep_get_wakeup_cause();
/*
Not using yet because we are using wake on all buttons being low
bootCount++;
wakeCause = esp_sleep_get_wakeup_cause();
/*
Not using yet because we are using wake on all buttons being low
wakeButtons = esp_sleep_get_ext1_wakeup_status(); // If one of these buttons is set it was the reason we woke
if (wakeCause == ESP_SLEEP_WAKEUP_EXT1 && !wakeButtons) // we must have been using the 'all buttons rule for waking' to support busted boards, assume button one was pressed
wakeButtons = ((uint64_t)1) << buttons.gpios[0];
*/
wakeButtons = esp_sleep_get_ext1_wakeup_status(); // If one of these buttons is set it was the reason we woke
if (wakeCause == ESP_SLEEP_WAKEUP_EXT1 && !wakeButtons) // we must have been using the 'all buttons rule for waking' to
support busted boards, assume button one was pressed wakeButtons = ((uint64_t)1) << buttons.gpios[0];
*/
// If we booted because our timer ran out or the user pressed reset, send those as fake events
const char *reason = "reset"; // our best guess
RESET_REASON hwReason = rtc_get_reset_reason(0);
// If we booted because our timer ran out or the user pressed reset, send those as fake events
const char *reason = "reset"; // our best guess
RESET_REASON hwReason = rtc_get_reset_reason(0);
if (hwReason == RTCWDT_BROWN_OUT_RESET)
reason = "brownout";
if (hwReason == RTCWDT_BROWN_OUT_RESET)
reason = "brownout";
if (hwReason == TG0WDT_SYS_RESET)
reason = "taskWatchdog";
if (hwReason == TG0WDT_SYS_RESET)
reason = "taskWatchdog";
if (hwReason == TG1WDT_SYS_RESET)
reason = "intWatchdog";
if (hwReason == TG1WDT_SYS_RESET)
reason = "intWatchdog";
if (wakeCause == ESP_SLEEP_WAKEUP_TIMER)
reason = "timeout";
if (wakeCause == ESP_SLEEP_WAKEUP_TIMER)
reason = "timeout";
DEBUG_MSG("booted, wake cause %d (boot count %d), reset_reason=%s\n", wakeCause, bootCount, reason);
DEBUG_MSG("booted, wake cause %d (boot count %d), reset_reason=%s\n", wakeCause, bootCount, reason);
}
void doDeepSleep(uint64_t msecToWake)
{
DEBUG_MSG("Entering deep sleep for %llu seconds\n", msecToWake / 1000);
DEBUG_MSG("Entering deep sleep for %llu seconds\n", msecToWake / 1000);
// not using wifi yet, but once we are this is needed to shutoff the radio hw
// esp_wifi_stop();
// not using wifi yet, but once we are this is needed to shutoff the radio hw
// esp_wifi_stop();
BLEDevice::deinit(false); // We are required to shutdown bluetooth before deep or light sleep
BLEDevice::deinit(false); // We are required to shutdown bluetooth before deep or light sleep
screen.setOn(false); // datasheet says this will draw only 10ua
screen.setOn(false); // datasheet says this will draw only 10ua
// Put radio in sleep mode (will still draw power but only 0.2uA)
service.radio.rf95.sleep();
// Put radio in sleep mode (will still draw power but only 0.2uA)
service.radio.rf95.sleep();
nodeDB.saveToDisk();
nodeDB.saveToDisk();
#ifdef RESET_OLED
digitalWrite(RESET_OLED, 1); // put the display in reset before killing its power
digitalWrite(RESET_OLED, 1); // put the display in reset before killing its power
#endif
#ifdef VEXT_ENABLE
digitalWrite(VEXT_ENABLE, 1); // turn off the display power
digitalWrite(VEXT_ENABLE, 1); // turn off the display power
#endif
setLed(false);
setLed(false);
#ifdef T_BEAM_V10
if (axp192_found)
{
// No need to turn this off if the power draw in sleep mode really is just 0.2uA and turning it off would
// leave floating input for the IRQ line
if (axp192_found) {
// No need to turn this off if the power draw in sleep mode really is just 0.2uA and turning it off would
// leave floating input for the IRQ line
// If we want to leave the radio receving in would be 11.5mA current draw, but most of the time it is just waiting
// in its sequencer (true?) so the average power draw should be much lower even if we were listinging for packets
// all the time.
// If we want to leave the radio receving in would be 11.5mA current draw, but most of the time it is just waiting
// in its sequencer (true?) so the average power draw should be much lower even if we were listinging for packets
// all the time.
// axp.setPowerOutPut(AXP192_LDO2, AXP202_OFF); // LORA radio
// axp.setPowerOutPut(AXP192_LDO2, AXP202_OFF); // LORA radio
setGPSPower(false);
}
setGPSPower(false);
}
#endif
/*
Some ESP32 IOs have internal pullups or pulldowns, which are enabled by default.
If an external circuit drives this pin in deep sleep mode, current consumption may
increase due to current flowing through these pullups and pulldowns.
/*
Some ESP32 IOs have internal pullups or pulldowns, which are enabled by default.
If an external circuit drives this pin in deep sleep mode, current consumption may
increase due to current flowing through these pullups and pulldowns.
To isolate a pin, preventing extra current draw, call rtc_gpio_isolate() function.
For example, on ESP32-WROVER module, GPIO12 is pulled up externally.
GPIO12 also has an internal pulldown in the ESP32 chip. This means that in deep sleep,
some current will flow through these external and internal resistors, increasing deep
sleep current above the minimal possible value.
To isolate a pin, preventing extra current draw, call rtc_gpio_isolate() function.
For example, on ESP32-WROVER module, GPIO12 is pulled up externally.
GPIO12 also has an internal pulldown in the ESP32 chip. This means that in deep sleep,
some current will flow through these external and internal resistors, increasing deep
sleep current above the minimal possible value.
Note: we don't isolate pins that are used for the LORA, LED, i2c, spi or the wake button
*/
static const uint8_t rtcGpios[] = {/* 0, */ 2,
/* 4, */
Note: we don't isolate pins that are used for the LORA, LED, i2c, spi or the wake button
*/
static const uint8_t rtcGpios[] = {/* 0, */ 2,
/* 4, */
#ifndef USE_JTAG
12, 13, /* 14, */ /* 15, */
12,
13,
/* 14, */ /* 15, */
#endif
/* 25, */ 26, /* 27, */
32, 33, 34, 35, 36, 37, /* 38, */ 39};
/* 25, */ 26, /* 27, */
32,
33,
34,
35,
36,
37,
/* 38, */ 39};
for (int i = 0; i < sizeof(rtcGpios); i++)
rtc_gpio_isolate((gpio_num_t)rtcGpios[i]);
for (int i = 0; i < sizeof(rtcGpios); i++)
rtc_gpio_isolate((gpio_num_t)rtcGpios[i]);
// FIXME, disable internal rtc pullups/pulldowns on the non isolated pins. for inputs that we aren't using
// to detect wake and in normal operation the external part drives them hard.
// FIXME, disable internal rtc pullups/pulldowns on the non isolated pins. for inputs that we aren't using
// to detect wake and in normal operation the external part drives them hard.
// We want RTC peripherals to stay on
esp_sleep_pd_config(ESP_PD_DOMAIN_RTC_PERIPH, ESP_PD_OPTION_ON);
// We want RTC peripherals to stay on
esp_sleep_pd_config(ESP_PD_DOMAIN_RTC_PERIPH, ESP_PD_OPTION_ON);
#ifdef BUTTON_PIN
// Only GPIOs which are have RTC functionality can be used in this bit map: 0,2,4,12-15,25-27,32-39.
uint64_t gpioMask = (1ULL << BUTTON_PIN);
// Only GPIOs which are have RTC functionality can be used in this bit map: 0,2,4,12-15,25-27,32-39.
uint64_t gpioMask = (1ULL << BUTTON_PIN);
#ifdef BUTTON_NEED_PULLUP
gpio_pullup_en((gpio_num_t) BUTTON_PIN);
gpio_pullup_en((gpio_num_t)BUTTON_PIN);
#endif
// Not needed because both of the current boards have external pullups
// FIXME change polarity in hw so we can wake on ANY_HIGH instead - that would allow us to use all three buttons (instead of just the first)
// gpio_pullup_en((gpio_num_t)BUTTON_PIN);
// Not needed because both of the current boards have external pullups
// FIXME change polarity in hw so we can wake on ANY_HIGH instead - that would allow us to use all three buttons (instead of
// just the first) gpio_pullup_en((gpio_num_t)BUTTON_PIN);
esp_sleep_enable_ext1_wakeup(gpioMask, ESP_EXT1_WAKEUP_ALL_LOW);
esp_sleep_enable_ext1_wakeup(gpioMask, ESP_EXT1_WAKEUP_ALL_LOW);
#endif
esp_sleep_enable_timer_wakeup(msecToWake * 1000ULL); // call expects usecs
esp_deep_sleep_start(); // TBD mA sleep current (battery)
esp_sleep_enable_timer_wakeup(msecToWake * 1000ULL); // call expects usecs
esp_deep_sleep_start(); // TBD mA sleep current (battery)
}
/**
* enter light sleep (preserves ram but stops everything about CPU).
*
*
* Returns (after restoring hw state) when the user presses a button or we get a LoRa interrupt
*/
esp_sleep_wakeup_cause_t doLightSleep(uint64_t sleepMsec) // FIXME, use a more reasonable default
{
//DEBUG_MSG("Enter light sleep\n");
uint64_t sleepUsec = sleepMsec * 1000LL;
// DEBUG_MSG("Enter light sleep\n");
uint64_t sleepUsec = sleepMsec * 1000LL;
Serial.flush(); // send all our characters before we stop cpu clock
setBluetoothEnable(false); // has to be off before calling light sleep
Serial.flush(); // send all our characters before we stop cpu clock
setBluetoothEnable(false); // has to be off before calling light sleep
// NOTE! ESP docs say we must disable bluetooth and wifi before light sleep
// NOTE! ESP docs say we must disable bluetooth and wifi before light sleep
// We want RTC peripherals to stay on
esp_sleep_pd_config(ESP_PD_DOMAIN_RTC_PERIPH, ESP_PD_OPTION_ON);
// We want RTC peripherals to stay on
esp_sleep_pd_config(ESP_PD_DOMAIN_RTC_PERIPH, ESP_PD_OPTION_ON);
#ifdef BUTTON_NEED_PULLUP
gpio_pullup_en((gpio_num_t) BUTTON_PIN);
gpio_pullup_en((gpio_num_t)BUTTON_PIN);
#endif
gpio_wakeup_enable((gpio_num_t)BUTTON_PIN, GPIO_INTR_LOW_LEVEL); // when user presses, this button goes low
gpio_wakeup_enable((gpio_num_t)DIO0_GPIO, GPIO_INTR_HIGH_LEVEL); // RF95 interrupt, active high
gpio_wakeup_enable((gpio_num_t)BUTTON_PIN, GPIO_INTR_LOW_LEVEL); // when user presses, this button goes low
gpio_wakeup_enable((gpio_num_t)DIO0_GPIO, GPIO_INTR_HIGH_LEVEL); // RF95 interrupt, active high
#ifdef PMU_IRQ
// FIXME, disable wake due to PMU because it seems to fire all the time?
// gpio_wakeup_enable((gpio_num_t)PMU_IRQ, GPIO_INTR_HIGH_LEVEL); // pmu irq
// FIXME, disable wake due to PMU because it seems to fire all the time?
// gpio_wakeup_enable((gpio_num_t)PMU_IRQ, GPIO_INTR_HIGH_LEVEL); // pmu irq
#endif
assert(esp_sleep_enable_gpio_wakeup() == ESP_OK);
assert(esp_sleep_enable_timer_wakeup(sleepUsec) == ESP_OK);
assert(esp_light_sleep_start() == ESP_OK);
//DEBUG_MSG("Exit light sleep b=%d, rf95=%d, pmu=%d\n", digitalRead(BUTTON_PIN), digitalRead(DIO0_GPIO), digitalRead(PMU_IRQ));
return esp_sleep_get_wakeup_cause();
assert(esp_sleep_enable_gpio_wakeup() == ESP_OK);
assert(esp_sleep_enable_timer_wakeup(sleepUsec) == ESP_OK);
assert(esp_light_sleep_start() == ESP_OK);
// DEBUG_MSG("Exit light sleep b=%d, rf95=%d, pmu=%d\n", digitalRead(BUTTON_PIN), digitalRead(DIO0_GPIO),
// digitalRead(PMU_IRQ));
return esp_sleep_get_wakeup_cause();
}
#if 0

Wyświetl plik

@ -15,7 +15,7 @@ void setCPUFast(bool on);
void setLed(bool ledOn);
extern int bootCount;
extern esp_sleep_source_t wakeCause;
extern esp_sleep_source_t wakeCause;
// is bluetooth sw currently running?
extern bool bluetoothOn;