Merge branch 'dev' into gps-sleep-mode

# Conflicts:
#	docs/software/TODO.md
#	platformio.ini
This commit is contained in:
geeksville
2020-03-13 18:48:38 -07:00
64 changed files with 1345 additions and 635 deletions

View File

@@ -20,7 +20,8 @@ CustomRF95::CustomRF95(MemoryPool<MeshPacket> &_pool, PointerQueue<MeshPacket> &
bool CustomRF95::canSleep()
{
return (_mode == RHModeIdle || _mode == RHModeRx) && txQueue.isEmpty(); // FIXME - also check if we have started receiving
// We allow initializing mode, because sometimes while testing we don't ever call init() to turn on the hardware
return (_mode == RHModeInitialising || _mode == RHModeIdle || _mode == RHModeRx) && !_isReceiving && txQueue.isEmpty();
}
bool CustomRF95::sleep()
@@ -44,12 +45,10 @@ bool CustomRF95::init()
/// bluetooth comms code. If the txmit queue is empty it might return an error
ErrorCode CustomRF95::send(MeshPacket *p)
{
// FIXME - we currently just slam over into send mode if the RF95 is in RX mode. This is _probably_ safe given
// how quiet our network is, bu it would be better to wait _if_ we are partially though receiving a packet (rather than
// just merely waiting for one).
// This is doubly bad because not only do 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)
// 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,
// we almost certainly guarantee no one outside will like the packet we are sending.
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());
@@ -141,7 +140,10 @@ void CustomRF95::handleInterrupt()
portYIELD_FROM_ISR();
}
/// Return true if a higher pri task has woken
/** 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()
{
BaseType_t higherPriWoken = false;

View File

@@ -15,6 +15,8 @@
*/
class CustomRF95 : public RH_RF95
{
friend class MeshRadio; // for debugging we let that class touch pool
MemoryPool<MeshPacket> &pool;
PointerQueue<MeshPacket> &rxDest;
PointerQueue<MeshPacket> txQueue;

View File

@@ -10,18 +10,20 @@
#include "mesh-pb-constants.h"
#include "NodeDB.h"
#include "configuration.h"
#include "PowerFSM.h"
#include "CallbackCharacteristic.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
static uint8_t trBytes[_max(_max(_max(_max(ToRadio_size, RadioConfig_size), User_size), MyNodeInfo_size), FromRadio_size)];
class ProtobufCharacteristic : public BLECharacteristic, public BLECharacteristicCallbacks
class ProtobufCharacteristic : public CallbackCharacteristic
{
const pb_msgdesc_t *fields;
void *my_struct;
public:
ProtobufCharacteristic(const char *uuid, uint32_t btprops, const pb_msgdesc_t *_fields, void *_my_struct)
: BLECharacteristic(uuid, btprops),
: CallbackCharacteristic(uuid, btprops),
fields(_fields),
my_struct(_my_struct)
{
@@ -30,13 +32,15 @@ public:
void onRead(BLECharacteristic *c)
{
DEBUG_MSG("Got proto read\n");
BLEKeepAliveCallbacks::onRead(c);
size_t numbytes = pb_encode_to_bytes(trBytes, sizeof(trBytes), fields, my_struct);
DEBUG_MSG("pbread from %s returns %d bytes\n", c->getUUID().toString().c_str(), numbytes);
c->setValue(trBytes, numbytes);
}
void onWrite(BLECharacteristic *c)
{
BLEKeepAliveCallbacks::onWrite(c);
writeToDest(c, my_struct);
}
@@ -47,13 +51,13 @@ protected:
bool writeToDest(BLECharacteristic *c, void *dest)
{
// dumpCharacteristic(pCharacteristic);
DEBUG_MSG("Got on proto write\n");
std::string src = c->getValue();
DEBUG_MSG("pbwrite to %s of %d bytes\n", c->getUUID().toString().c_str(), src.length());
return pb_decode_from_bytes((const uint8_t *)src.c_str(), src.length(), fields, dest);
}
};
class NodeInfoCharacteristic : public BLECharacteristic, public BLECharacteristicCallbacks
class NodeInfoCharacteristic : public BLECharacteristic, public BLEKeepAliveCallbacks
{
public:
NodeInfoCharacteristic()
@@ -64,6 +68,8 @@ public:
void onRead(BLECharacteristic *c)
{
BLEKeepAliveCallbacks::onRead(c);
const NodeInfo *info = nodeDB.readNextInfo();
if (info)
@@ -81,8 +87,8 @@ public:
void onWrite(BLECharacteristic *c)
{
// dumpCharacteristic(pCharacteristic);
DEBUG_MSG("Got on nodeinfo write\n");
BLEKeepAliveCallbacks::onWrite(c);
DEBUG_MSG("Reset nodeinfo read pointer\n");
nodeDB.resetReadPointer();
}
};
@@ -114,6 +120,8 @@ public:
void onWrite(BLECharacteristic *c)
{
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))
{
@@ -141,167 +149,145 @@ public:
}
};
static BLECharacteristic
meshFromRadioCharacteristic("8ba2bcc2-ee02-4a55-a531-c525c5e454d5", BLECharacteristic::PROPERTY_READ),
meshToRadioCharacteristic("f75c76d2-129e-4dad-a1dd-7866124401e7", BLECharacteristic::PROPERTY_WRITE),
meshFromNumCharacteristic("ed9da18c-a800-4f66-a670-aa7547e34453", BLECharacteristic::PROPERTY_WRITE | BLECharacteristic::PROPERTY_READ | BLECharacteristic::PROPERTY_NOTIFY);
class ToRadioCharacteristic : public CallbackCharacteristic
{
public:
ToRadioCharacteristic()
: CallbackCharacteristic("f75c76d2-129e-4dad-a1dd-7866124401e7", BLECharacteristic::PROPERTY_WRITE)
{
}
static NodeInfoCharacteristic meshNodeInfoCharacteristic;
void onWrite(BLECharacteristic *c)
{
BLEKeepAliveCallbacks::onWrite(c);
DEBUG_MSG("Got on write\n");
static ProtobufCharacteristic
meshMyNodeCharacteristic("ea9f3f82-8dc4-4733-9452-1f6da28892a2", BLECharacteristic::PROPERTY_READ, MyNodeInfo_fields, &myNodeInfo);
service.handleToRadio(c->getValue());
}
};
static OwnerCharacteristic meshOwnerCharacteristic;
static RadioCharacteristic meshRadioCharacteristic;
class FromRadioCharacteristic : public CallbackCharacteristic
{
public:
FromRadioCharacteristic()
: CallbackCharacteristic("8ba2bcc2-ee02-4a55-a531-c525c5e454d5", BLECharacteristic::PROPERTY_READ)
{
}
void onRead(BLECharacteristic *c)
{
BLEKeepAliveCallbacks::onRead(c);
MeshPacket *mp = service.getForPhone();
// 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)
{
DEBUG_MSG("toPhone queue is empty\n");
c->setValue((uint8_t *)"", 0);
}
else
{
static FromRadio fRadio;
// Encapsulate as a FromRadio packet
memset(&fRadio, 0, sizeof(fRadio));
fRadio.which_variant = FromRadio_packet_tag;
fRadio.variant.packet = *mp;
size_t numbytes = pb_encode_to_bytes(trBytes, sizeof(trBytes), FromRadio_fields, &fRadio);
DEBUG_MSG("delivering toPhone packet to phone %d bytes\n", numbytes);
c->setValue(trBytes, numbytes);
service.releaseToPool(mp); // we just copied the bytes, so don't need this buffer anymore
}
}
};
class FromNumCharacteristic : public CallbackCharacteristic
{
public:
FromNumCharacteristic()
: CallbackCharacteristic("ed9da18c-a800-4f66-a670-aa7547e34453",
BLECharacteristic::PROPERTY_WRITE | BLECharacteristic::PROPERTY_READ | BLECharacteristic::PROPERTY_NOTIFY)
{
}
void onRead(BLECharacteristic *c)
{
BLEKeepAliveCallbacks::onRead(c);
DEBUG_MSG("FIXME implement fromnum read\n");
}
};
FromNumCharacteristic *meshFromNumCharacteristic;
/**
* Tell any bluetooth clients that the number of rx packets has changed
*/
void bluetoothNotifyFromNum(uint32_t newValue)
{
meshFromNumCharacteristic.setValue(newValue);
meshFromNumCharacteristic.notify();
if (meshFromNumCharacteristic)
{
// if bt not running ignore
meshFromNumCharacteristic->setValue(newValue);
meshFromNumCharacteristic->notify();
}
}
class BluetoothMeshCallbacks : public BLECharacteristicCallbacks
{
void onRead(BLECharacteristic *c)
{
DEBUG_MSG("Got on read\n");
if (c == &meshFromRadioCharacteristic)
{
MeshPacket *mp = service.getForPhone();
// 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)
{
DEBUG_MSG("toPhone queue is empty\n");
c->setValue((uint8_t *)"", 0);
}
else
{
DEBUG_MSG("delivering toPhone packet to phone\n");
static FromRadio fradio;
// Encapsulate as a ToRadio packet
memset(&fradio, 0, sizeof(fradio));
fradio.which_variant = FromRadio_packet_tag;
fradio.variant.packet = *mp;
service.releaseToPool(mp); // we just copied the bytes, so don't need this buffer anymore
size_t numbytes = pb_encode_to_bytes(trBytes, sizeof(trBytes), FromRadio_fields, &fradio);
c->setValue(trBytes, numbytes);
}
}
else
{
// we are uninterested in the other reads
}
}
void onWrite(BLECharacteristic *c)
{
// dumpCharacteristic(pCharacteristic);
DEBUG_MSG("Got on write\n");
if (c == &meshToRadioCharacteristic)
{
service.handleToRadio(c->getValue());
}
else
{
// we are uninterested in the other writes
}
}
};
static BluetoothMeshCallbacks btMeshCb;
BLEService *meshService;
/*
MeshBluetoothService UUID 6ba1b218-15a8-461f-9fa8-5dcae273eafd
FIXME - notify vs indication for fromradio output. Using notify for now, not sure if that is best
FIXME - in the esp32 mesh managment code, occasionally mirror the current net db to flash, so that if we reboot we still have a good guess of users who are out there.
FIXME - make sure this protocol is guaranteed robust and won't drop packets
"According to the BLE specification the notification length can be max ATT_MTU - 3. The 3 bytes subtracted is the 3-byte header(OP-code (operation, 1 byte) and the attribute handle (2 bytes)).
In BLE 4.1 the ATT_MTU is 23 bytes (20 bytes for payload), but in BLE 4.2 the ATT_MTU can be negotiated up to 247 bytes."
MAXPACKET is 256? look into what the lora lib uses. FIXME
Characteristics:
UUID
properties
description
8ba2bcc2-ee02-4a55-a531-c525c5e454d5
read
fromradio - contains a newly received packet destined towards the phone (up to MAXPACKET bytes? per packet).
After reading the esp32 will put the next packet in this mailbox. If the FIFO is empty it will put an empty packet in this
mailbox.
f75c76d2-129e-4dad-a1dd-7866124401e7
write
toradio - write ToRadio protobufs to this charstic to send them (up to MAXPACKET len)
ed9da18c-a800-4f66-a670-aa7547e34453
read|notify|write
fromnum - the current packet # in the message waiting inside fromradio, if the phone sees this notify it should read messages
until it catches up with this number.
The phone can write to this register to go backwards up to FIXME packets, to handle the rare case of a fromradio packet was dropped after the esp32
callback was called, but before it arrives at the phone. If the phone writes to this register the esp32 will discard older packets and put the next packet >= fromnum in fromradio.
When the esp32 advances fromnum, it will delay doing the notify by 100ms, in the hopes that the notify will never actally need to be sent if the phone is already pulling from fromradio.
Note: that if the phone ever sees this number decrease, it means the esp32 has rebooted.
meshMyNodeCharacteristic("ea9f3f82-8dc4-4733-9452-1f6da28892a2", BLECharacteristic::PROPERTY_READ)
mynode - read this to access a MyNodeInfo protobuf
meshNodeInfoCharacteristic("d31e02e0-c8ab-4d3f-9cc9-0b8466bdabe8", BLECharacteristic::PROPERTY_WRITE | BLECharacteristic::PROPERTY_READ),
nodeinfo - read this to get a series of node infos (ending with a null empty record), write to this to restart the read statemachine that returns all the node infos
meshRadioCharacteristic("b56786c8-839a-44a1-b98e-a1724c4a0262", BLECharacteristic::PROPERTY_WRITE | BLECharacteristic::PROPERTY_READ),
radio - read/write this to access a RadioConfig protobuf
meshOwnerCharacteristic("6ff1d8b6-e2de-41e3-8c0b-8fa384f64eb6", BLECharacteristic::PROPERTY_WRITE | BLECharacteristic::PROPERTY_READ)
owner - read/write this to access a User protobuf
Re: queue management
Not all messages are kept in the fromradio queue (filtered based on SubPacket):
* only the most recent Position and User messages for a particular node are kept
* all Data SubPackets are kept
* No WantNodeNum / DenyNodeNum messages are kept
A variable keepAllPackets, if set to true will suppress this behavior and instead keep everything for forwarding to the phone (for debugging)
See bluetooth-api.md for documentation.
*/
BLEService *createMeshBluetoothService(BLEServer *server)
{
// Create the BLE Service, we need more than the default of 15 handles
BLEService *service = server->createService(BLEUUID("6ba1b218-15a8-461f-9fa8-5dcae273eafd"), 25, 0);
addWithDesc(service, &meshFromRadioCharacteristic, "fromRadio");
addWithDesc(service, &meshToRadioCharacteristic, "toRadio");
addWithDesc(service, &meshFromNumCharacteristic, "fromNum");
assert(!meshFromNumCharacteristic);
meshFromNumCharacteristic = new FromNumCharacteristic;
meshFromRadioCharacteristic.setCallbacks(&btMeshCb);
meshToRadioCharacteristic.setCallbacks(&btMeshCb);
meshFromNumCharacteristic.setCallbacks(&btMeshCb);
addWithDesc(service, meshFromNumCharacteristic, "fromRadio");
addWithDesc(service, new ToRadioCharacteristic, "toRadio");
addWithDesc(service, new FromRadioCharacteristic, "fromNum");
addWithDesc(service, &meshMyNodeCharacteristic, "myNode");
addWithDesc(service, &meshRadioCharacteristic, "radio");
addWithDesc(service, &meshOwnerCharacteristic, "owner");
addWithDesc(service, &meshNodeInfoCharacteristic, "nodeinfo");
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");
meshFromNumCharacteristic.addDescriptor(new BLE2902()); // Needed so clients can request notification
meshFromNumCharacteristic->addDescriptor(addBLEDescriptor(new BLE2902())); // Needed so clients can request notification
service->start();
server->getAdvertising()->addServiceUUID(service->getUUID());
// We only add to advertisting once, because the ESP32 arduino code is dumb and that object never dies
static bool firstTime = true;
if (firstTime)
{
firstTime = false;
server->getAdvertising()->addServiceUUID(service->getUUID());
}
DEBUG_MSG("*** Mesh service:\n");
service->dump();
meshService = service;
return service;
}
void stopMeshBluetoothService()
{
assert(meshService);
meshService->stop();
}
void destroyMeshBluetoothService()
{
assert(meshService);
delete meshService;
meshFromNumCharacteristic = NULL;
}

View File

@@ -5,8 +5,11 @@
#include <Arduino.h>
BLEService *createMeshBluetoothService(BLEServer* server);
void destroyMeshBluetoothService();
/**
* Tell any bluetooth clients that the number of rx packets has changed
*/
void bluetoothNotifyFromNum(uint32_t newValue);
void stopMeshBluetoothService();

View File

@@ -25,6 +25,9 @@ The band is from 902 to 928 MHz. It mentions channel number and its respective c
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)
@@ -45,6 +48,9 @@ MeshRadio::MeshRadio(MemoryPool<MeshPacket> &_pool, PointerQueue<MeshPacket> &_r
bool MeshRadio::init()
{
if (!useHardware)
return true;
DEBUG_MSG("Starting meshradio init...\n");
#ifdef RESET_GPIO
@@ -109,14 +115,17 @@ void MeshRadio::reloadConfig()
rf95.setModeRx();
}
ErrorCode MeshRadio::send(MeshPacket *p)
{
return rf95.send(p);
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

View File

@@ -13,17 +13,22 @@
#define CH_SPACING_US 2.16f // MHz
#define NUM_CHANNELS_US 13
// EU channel settings
#define CH0_EU 865.2f // MHz
#define CH_SPACING_EU 0.3f // MHz
#define NUM_CHANNELS_EU 10
// EU433 channel settings
#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 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 NUM_CHANNELS_CN 20
// CN channel settings
// 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 NUM_CHANNELS_JP 10
@@ -33,10 +38,14 @@
#define CH0 CH0_US
#define CH_SPACING CH_SPACING_US
#define NUM_CHANNELS NUM_CHANNELS_US
#elif defined(HW_VERSION_EU)
#define CH0 CH0_EU
#define CH_SPACING CH_SPACING_EU
#define NUM_CHANNELS NUM_CHANNELS_EU
#elif defined(HW_VERSION_EU433)
#define CH0 CH0_EU433
#define CH_SPACING CH_SPACING_EU433
#define NUM_CHANNELS NUM_CHANNELS_EU433
#elif defined(HW_VERSION_EU865)
#define CH0 CH0_EU865
#define CH_SPACING CH_SPACING_EU865
#define NUM_CHANNELS NUM_CHANNELS_EU865
#elif defined(HW_VERSION_CN)
#define CH0 CH0_CN
#define CH_SPACING CH_SPACING_CN

View File

@@ -9,6 +9,7 @@
#include "GPS.h"
#include "screen.h"
#include "Periodic.h"
#include "PowerFSM.h"
/*
receivedPacketQueue - this is a queue of messages we've received from the mesh, which we are keeping to deliver to the phone.
@@ -123,10 +124,35 @@ MeshPacket *MeshService::handleFromRadioUser(MeshPacket *mp)
return mp;
}
void MeshService::handleIncomingPosition(MeshPacket *mp)
{
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)
{
struct timeval tv;
uint32_t secs = mp->payload.variant.position.time;
tv.tv_sec = secs;
tv.tv_usec = 0;
gps.perhapsSetRTC(&tv);
}
}
}
void MeshService::handleFromRadio(MeshPacket *mp)
{
powerFSM.trigger(EVENT_RECEIVED_PACKET); // Possibly keep the node from sleeping
mp->rx_time = gps.getValidTime(); // store the arrival timestamp for the phone
// If it is a position packet, perhaps set our clock (if we don't have a GPS of our own, otherwise wait for that to work)
if (!myNodeInfo.has_gps)
handleIncomingPosition(mp);
if (mp->has_payload && mp->payload.which_variant == SubPacket_user_tag)
{
mp = handleFromRadioUser(mp);
@@ -208,17 +234,7 @@ void MeshService::handleToRadio(std::string s)
case ToRadio_packet_tag:
{
// If our phone is sending a position, see if we can use it to set our RTC
if (r.variant.packet.has_payload && r.variant.packet.payload.which_variant == SubPacket_position_tag && r.variant.packet.payload.variant.position.time)
{
struct timeval tv;
uint32_t secs = r.variant.packet.payload.variant.position.time;
// FIXME, this is a shit not right version of the standard def of unix time!!!
tv.tv_sec = secs;
tv.tv_usec = 0;
gps.perhapsSetRTC(&tv);
}
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)
@@ -246,8 +262,14 @@ 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)
p->payload.variant.position.time = 0;
{
if (!myNodeInfo.has_gps)
p->payload.variant.position.time = 0;
else
DEBUG_MSG("Providing time to mesh %u\n", p->payload.variant.position.time);
}
// If the phone sent a packet just to us, don't send it out into the network
if (p->to == nodeDB.getNodeNum())
@@ -294,8 +316,7 @@ void MeshService::sendOurPosition(NodeNum dest)
p->to = dest;
p->payload.which_variant = SubPacket_position_tag;
p->payload.variant.position = node->position;
// FIXME - for now we are leaving this in the sent packets (for debugging)
//p->payload.variant.position.time = 0; // No need to send time, other node won't trust it anyways
p->payload.variant.position.time = gps.getValidTime(); // This nodedb timestamp might be stale, so update it if our clock is valid.
sendToMesh(p);
}

View File

@@ -86,6 +86,9 @@ private:
/// handle a user packet that just arrived on the radio, return NULL if we should not process this packet at all
MeshPacket *handleFromRadioUser(MeshPacket *mp);
/// look at inbound packets and if they contain a position with time, possibly set our clock
void handleIncomingPosition(MeshPacket *mp);
};
extern MeshService service;

View File

@@ -21,6 +21,14 @@ MyNodeInfo &myNodeInfo = devicestate.my_node;
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
#define here.
*/
#define DEVICESTATE_CUR_VER 2
#define DEVICESTATE_MIN_VER DEVICESTATE_CUR_VER
#define FS SPIFFS
/**
@@ -52,11 +60,11 @@ void NodeDB::init()
radioConfig.preferences.send_owner_interval = 4; // per sw-design.md
radioConfig.preferences.position_broadcast_secs = 15 * 60;
radioConfig.preferences.wait_bluetooth_secs = 30;
radioConfig.preferences.wait_bluetooth_secs = 120;
radioConfig.preferences.screen_on_secs = 30;
radioConfig.preferences.mesh_sds_timeout_secs = 60 * 60;
radioConfig.preferences.phone_sds_timeout_sec = 60 * 60;
radioConfig.preferences.sds_secs = 60 * 60;
radioConfig.preferences.mesh_sds_timeout_secs = 2 * 60 * 60;
radioConfig.preferences.phone_sds_timeout_sec = 2 * 60 * 60;
radioConfig.preferences.sds_secs = 365 * 24 * 60 * 60; // one year
radioConfig.preferences.ls_secs = 60 * 60;
radioConfig.preferences.phone_timeout_secs = 15 * 60;
@@ -64,6 +72,9 @@ void NodeDB::init()
// some hardware defaults to have a built in GPS
myNodeInfo.has_gps = true;
#endif
strncpy(myNodeInfo.region, xstr(HW_VERSION), sizeof(myNodeInfo.region));
strncpy(myNodeInfo.firmware_version, xstr(APP_VERSION), sizeof(myNodeInfo.firmware_version));
strncpy(myNodeInfo.hw_model, HW_VENDOR, sizeof(myNodeInfo.hw_model));
// Init our blank owner info to reasonable defaults
esp_efuse_mac_get_default(ourMacAddr);
@@ -144,7 +155,7 @@ void NodeDB::loadFromDisk()
}
else
{
if (scratch.version < DeviceState_Version_Minimum)
if (scratch.version < DEVICESTATE_MIN_VER)
DEBUG_MSG("Warn: devicestate is old, discarding\n");
else
{
@@ -173,7 +184,7 @@ void NodeDB::saveToDisk()
//DEBUG_MSG("Presave channel name=%s\n", channelSettings.name);
devicestate.version = DeviceState_Version_Current;
devicestate.version = DEVICESTATE_CUR_VER;
if (!pb_encode(&stream, DeviceState_fields, &devicestate))
{
DEBUG_MSG("Error: can't write protobuf %s\n", PB_GET_ERROR(&stream));
@@ -275,7 +286,7 @@ void NodeDB::updateFrom(const MeshPacket &mp)
devicestate.rx_text_message = mp;
devicestate.has_rx_text_message = true;
updateTextMessage = true;
powerFSM.trigger(EVENT_NODEDB_UPDATED);
powerFSM.trigger(EVENT_RECEIVED_TEXT_MSG);
}
}
break;

View File

@@ -6,6 +6,7 @@
#include "screen.h"
#include "PowerFSM.h"
#include "GPS.h"
#include "main.h"
static void sdsEnter()
{
@@ -24,29 +25,24 @@ static void sdsEnter()
static void lsEnter()
{
/*
// while we have bluetooth on, we can't do light sleep, but once off stay in light_sleep all the time
// we will wake from light sleep on button press or interrupt from the RF95 radio
if (!bluetoothOn && !is_screen_on() && service.radio.rf95.canSleep() && gps.canSleep())
doLightSleep(radioConfig.preferences.ls_secs);
else
{
delay(msecstosleep);
} */
screen.setOn(false);
while (!service.radio.rf95.canSleep())
delay(10); // Kinda yucky - wait until radio says say we can shutdown (finished in process sends/receives)
gps.prepareSleep(); // abandon in-process parsing
setGPSPower(false); // kill GPS power
if (!isUSBPowered) // FIXME - temp hack until we can put gps in sleep mode, if we have AC when we go to sleep then leave GPS on
setGPSPower(false); // kill GPS power
}
static void lsIdle()
{
uint32_t secsSlept = 0;
esp_sleep_source_t wakeCause = ESP_SLEEP_WAKEUP_UNDEFINED;
bool reached_ls_secs = false;
while (secsSlept < radioConfig.preferences.ls_secs)
while (!reached_ls_secs)
{
// Briefly come out of sleep long enough to blink the led once every few seconds
uint32_t sleepTime = 5;
@@ -62,11 +58,20 @@ static void lsIdle()
break;
secsSlept += sleepTime;
reached_ls_secs = secsSlept >= radioConfig.preferences.ls_secs;
}
setLed(false);
// Regardless of why we woke (for now) just transition to NB (and that state will handle stuff like IRQs etc)
powerFSM.trigger(EVENT_WAKE_TIMER);
if (reached_ls_secs)
{
// stay in LS mode but let loop check whatever it wants
DEBUG_MSG("reached ls_secs, servicing loop()\n");
}
else
{
// Regardless of why we woke just transition to NB (and that state will handle stuff like IRQs etc)
powerFSM.trigger(EVENT_WAKE_TIMER);
}
}
static void lsExit()
@@ -77,6 +82,7 @@ static void lsExit()
static void nbEnter()
{
screen.setOn(false);
setBluetoothEnable(false);
// FIXME - check if we already have packets for phone and immediately trigger EVENT_PACKETS_FOR_PHONE
@@ -93,10 +99,7 @@ static void onEnter()
setBluetoothEnable(true);
}
static void onExit()
{
screen.setOn(false);
}
static void wakeForPing()
{
}
@@ -110,7 +113,7 @@ 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 stateON(onEnter, NULL, onExit, "ON");
State stateON(onEnter, NULL, NULL, "ON");
Fsm powerFSM(&stateDARK);
void PowerFSM_setup()
@@ -130,8 +133,8 @@ void PowerFSM_setup()
powerFSM.add_transition(&stateDARK, &stateON, EVENT_PRESS, NULL, "Press");
powerFSM.add_transition(&stateON, &stateON, EVENT_PRESS, screenPress, "Press"); // reenter On to restart our timers
powerFSM.add_transition(&stateNB, &stateON, EVENT_PRESS, NULL, "Bluetooth pairing");
powerFSM.add_transition(&stateON, &stateON, EVENT_PRESS, NULL, "Bluetooth pairing");
powerFSM.add_transition(&stateDARK, &stateON, EVENT_BLUETOOTH_PAIR, NULL, "Bluetooth pairing");
powerFSM.add_transition(&stateON, &stateON, EVENT_BLUETOOTH_PAIR, NULL, "Bluetooth pairing");
powerFSM.add_transition(&stateNB, &stateON, EVENT_NODEDB_UPDATED, NULL, "NodeDB update");
powerFSM.add_transition(&stateDARK, &stateON, EVENT_NODEDB_UPDATED, NULL, "NodeDB update");
@@ -140,6 +143,9 @@ void PowerFSM_setup()
powerFSM.add_transition(&stateLS, &stateON, EVENT_RECEIVED_TEXT_MSG, NULL, "Received text");
powerFSM.add_transition(&stateNB, &stateON, EVENT_RECEIVED_TEXT_MSG, NULL, "Received text");
powerFSM.add_transition(&stateDARK, &stateON, EVENT_RECEIVED_TEXT_MSG, NULL, "Received text");
powerFSM.add_transition(&stateON, &stateON, EVENT_RECEIVED_TEXT_MSG, NULL, "Received text"); // restarts the sleep timer
powerFSM.add_transition(&stateDARK, &stateDARK, EVENT_CONTACT_FROM_PHONE, NULL, "Contact from phone");
powerFSM.add_transition(&stateNB, &stateDARK, EVENT_PACKET_FOR_PHONE, NULL, "Packet for phone");
@@ -151,5 +157,9 @@ void PowerFSM_setup()
powerFSM.add_timed_transition(&stateDARK, &stateLS, radioConfig.preferences.wait_bluetooth_secs * 1000, NULL, "Bluetooth timeout");
powerFSM.add_timed_transition(&stateLS, &stateSDS, radioConfig.preferences.mesh_sds_timeout_secs * 1000, NULL, "mesh timeout");
// removing for now, because some users don't even have phones
// powerFSM.add_timed_transition(&stateLS, &stateSDS, radioConfig.preferences.phone_sds_timeout_sec * 1000, NULL, "phone timeout");
powerFSM.run_machine(); // run one interation of the state machine, so we run our on enter tasks for the initial DARK state
}

View File

@@ -1,6 +1,6 @@
#pragma once
#include "Fsm.h"
#include <Fsm.h>
// See sw-design.md for documentation
@@ -12,7 +12,8 @@
#define EVENT_BOOT 6
#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_CONTACT_FROM_PHONE 9 // the phone just talked to us over bluetooth
extern Fsm powerFSM;
void PowerFSM_setup();
void PowerFSM_setup();

View File

@@ -29,22 +29,20 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
// Version
// -----------------------------------------------------------------------------
#define APP_NAME "Meshtastic"
// If app version is not specified we assume we are not being invoked by the build script
#ifndef APP_VERSION
#define APP_VERSION "0.0.0" // this def normally comes from build-all.sh
#define APP_VERSION 0.0.0 // this def normally comes from build-all.sh
#define HW_VERSION 1.0 - US // normally comes from build-all.sh and contains the region code
#endif
// -----------------------------------------------------------------------------
// Configuration
// -----------------------------------------------------------------------------
// 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
#endif
@@ -55,18 +53,20 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
//#define USE_JTAG
#endif
#define DEBUG_PORT Serial // Serial debug port
#define SERIAL_BAUD 115200 // Serial debug baud rate
#define DEBUG_PORT Serial // Serial debug port
#define SERIAL_BAUD 115200 // Serial debug baud rate
#define REQUIRE_RADIO true // If true, we will fail to start if the radio is not found
#define REQUIRE_RADIO true // If true, we will fail to start if the radio is not found
#define xstr(s) str(s)
#define str(s) #s
// -----------------------------------------------------------------------------
// DEBUG
// -----------------------------------------------------------------------------
#ifdef DEBUG_PORT
#define DEBUG_MSG(...) DEBUG_PORT.printf( __VA_ARGS__ )
#define DEBUG_MSG(...) DEBUG_PORT.printf(__VA_ARGS__)
#else
#define DEBUG_MSG(...)
#endif
@@ -81,15 +81,15 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
// GPS
// -----------------------------------------------------------------------------
#define GPS_SERIAL_NUM 1
#define GPS_BAUDRATE 9600
#define GPS_SERIAL_NUM 1
#define GPS_BAUDRATE 9600
#if defined(T_BEAM_V10)
#define GPS_RX_PIN 34
#define GPS_RX_PIN 34
#ifdef USE_JTAG
#define GPS_TX_PIN -1
#define GPS_TX_PIN -1
#else
#define GPS_TX_PIN 12
#define GPS_TX_PIN 12
#endif
#endif
@@ -97,59 +97,59 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
// LoRa SPI
// -----------------------------------------------------------------------------
#define SCK_GPIO 5
#define MISO_GPIO 19
#define MOSI_GPIO 27
#define NSS_GPIO 18
#define SCK_GPIO 5
#define MISO_GPIO 19
#define MOSI_GPIO 27
#define NSS_GPIO 18
#if defined(T_BEAM_V10)
#define HW_VENDOR "TTGO"
// This string must exactly match the case used in release file names or the android updater won't work
#define HW_VENDOR "TBEAM"
#define BICOLOR_DISPLAY // we have yellow at the top 16 lines
#define I2C_SDA 21
#define I2C_SCL 22
#define I2C_SDA 21
#define I2C_SCL 22
#define BUTTON_PIN 38
#define BUTTON_PIN 38
#ifndef USE_JTAG
#define RESET_GPIO 14
#define RESET_GPIO 14
#endif
#define DIO0_GPIO 26
#define DIO1_GPIO 33 // Note: not really used on this board
#define DIO2_GPIO 32 // Note: not really used on this board
#define DIO0_GPIO 26
#define DIO1_GPIO 33 // Note: not really used on this board
#define DIO2_GPIO 32 // Note: not really used on this board
// Leave undefined to disable our PMU IRQ handler
#define PMU_IRQ 35
// Leave undefined to disable our PMU IRQ handler
#define PMU_IRQ 35
#elif defined(HELTEC_LORA32)
#define HW_VENDOR "Heltec"
// This string must exactly match the case used in release file names or the android updater won't work
#define HW_VENDOR "HELTEC"
#ifndef USE_JTAG // gpio15 is TDO for JTAG, so no I2C on this board while doing jtag
#define I2C_SDA 4
#define I2C_SCL 15
#define I2C_SDA 4
#define I2C_SCL 15
#endif
#define RESET_OLED 16
#define RESET_OLED 16
#define VEXT_ENABLE 21 // active low, powers the oled display and the lora antenna boost
#define LED_PIN 25
#define BUTTON_PIN 0
#define VEXT_ENABLE 21 // active low, powers the oled display and the lora antenna boost
#define LED_PIN 25
#define BUTTON_PIN 0
#ifndef USE_JTAG
#define RESET_GPIO 14
#define RESET_GPIO 14
#endif
#define DIO0_GPIO 26
#define DIO1_GPIO 35
#define DIO2_GPIO 34
#define DIO0_GPIO 26
#define DIO1_GPIO 35
#define DIO2_GPIO 34
#endif
// -----------------------------------------------------------------------------
// AXP192 (Rev1-specific options)
// -----------------------------------------------------------------------------
// #define AXP192_SLAVE_ADDRESS 0x34 // Now defined in axp20x.h
#define GPS_POWER_CTRL_CH 3
#define LORA_POWER_CTRL_CH 2
#define GPS_POWER_CTRL_CH 3
#define LORA_POWER_CTRL_CH 2

View File

@@ -44,14 +44,15 @@
AXP20X_Class axp;
bool pmu_irq = false;
#endif
bool isCharging = false;
bool isUSBPowered = false;
bool ssd1306_found = false;
bool axp192_found = false;
// these flags are all in bss so they default false
bool isCharging;
bool isUSBPowered;
#define xstr(s) str(s)
#define str(s) #s
bool ssd1306_found;
bool axp192_found;
bool bluetoothOn;
// -----------------------------------------------------------------------------
// Application
@@ -171,8 +172,8 @@ void axp192Init()
axp.clearIRQ();
#endif
isCharging = axp.isChargeing();
isUSBPowered = axp.isVBUSPlug();
isCharging = axp.isChargeing() ? 1 : 0;
isUSBPowered = axp.isVBUSPlug() ? 1 : 0;
}
else
{
@@ -234,7 +235,7 @@ void setup()
#endif
// Hello
DEBUG_MSG("%s %s\n", xstr(APP_NAME), str(APP_VERSION));
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)
@@ -250,24 +251,53 @@ void setup()
service.init();
bool useBluetooth = true;
if (useBluetooth)
{
DEBUG_MSG("Starting bluetooth\n");
BLEServer *serve = initBLE(getDeviceName(), HW_VENDOR, str(APP_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();
}
setBluetoothEnable(false);
// setBluetoothEnable(false); we now don't start bluetooth until we enter the proper state
setCPUFast(false); // 80MHz is fine for our slow peripherals
PowerFSM_setup();
powerFSM.trigger(EVENT_BOOT); // transition to ON, FIXME, only do this for cold boots, not waking from SDS
}
void initBluetooth()
{
DEBUG_MSG("Starting bluetooth\n");
// FIXME - we are leaking like crazy
// AllocatorScope scope(btPool);
BLEServer *serve = initBLE(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();
}
void setBluetoothEnable(bool 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();
}
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;
@@ -322,11 +352,15 @@ void loop()
DEBUG_MSG("pmu irq!\n");
isCharging = axp.isChargeing();
isUSBPowered = axp.isVBUSPlug();
isCharging = axp.isChargeing() ? 1 : 0;
isUSBPowered = axp.isVBUSPlug() ? 1 : 0;
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;
#endif
}
#endif
@@ -337,7 +371,7 @@ void loop()
static uint32_t minPressMs; // what tick should we call this press long enough
static uint32_t lastPingMs;
if (!digitalRead(BUTTON_PIN))
if (!digitalRead(BUTTON_PIN))
{
if (!wasPressed)
{ // just started a new press
@@ -371,7 +405,7 @@ void loop()
// ESP.restart();
}
}
#endif
#endif
// 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.

View File

@@ -1,4 +1,6 @@
#pragma once
extern bool axp192_found;
extern bool ssd1306_found;
extern bool ssd1306_found;
extern bool isCharging;
extern bool isUSBPowered;

View File

@@ -49,7 +49,6 @@ PB_BIND(ToRadio, ToRadio, 2)
#ifndef PB_CONVERT_DOUBLE_FLOAT
/* On some platforms (such as AVR), double is really float.
* To be able to encode/decode double on these platforms, you need.

View File

@@ -31,12 +31,6 @@ typedef enum _ChannelSettings_ModemConfig {
ChannelSettings_ModemConfig_Bw125Cr48Sf4096 = 3
} ChannelSettings_ModemConfig;
typedef enum _DeviceState_Version {
DeviceState_Version_Unset = 0,
DeviceState_Version_Minimum = 16,
DeviceState_Version_Current = 16
} DeviceState_Version;
/* Struct definitions */
typedef struct _ChannelSettings {
int32_t tx_power;
@@ -56,6 +50,9 @@ typedef struct _MyNodeInfo {
int32_t my_node_num;
bool has_gps;
int32_t num_channels;
char region[12];
char hw_model[12];
char firmware_version[12];
} MyNodeInfo;
typedef struct _Position {
@@ -63,7 +60,6 @@ typedef struct _Position {
double longitude;
int32_t altitude;
int32_t battery_level;
bool from_hardware;
uint32_t time;
} Position;
@@ -136,9 +132,9 @@ typedef struct _DeviceState {
NodeInfo node_db[32];
pb_size_t receive_queue_count;
MeshPacket receive_queue[32];
DeviceState_Version version;
bool has_rx_text_message;
MeshPacket rx_text_message;
uint32_t version;
} DeviceState;
typedef struct _FromRadio {
@@ -170,13 +166,9 @@ typedef struct _ToRadio {
#define _ChannelSettings_ModemConfig_MAX ChannelSettings_ModemConfig_Bw125Cr48Sf4096
#define _ChannelSettings_ModemConfig_ARRAYSIZE ((ChannelSettings_ModemConfig)(ChannelSettings_ModemConfig_Bw125Cr48Sf4096+1))
#define _DeviceState_Version_MIN DeviceState_Version_Unset
#define _DeviceState_Version_MAX DeviceState_Version_Current
#define _DeviceState_Version_ARRAYSIZE ((DeviceState_Version)(DeviceState_Version_Current+1))
/* Initializer values for message structs */
#define Position_init_default {0, 0, 0, 0, 0, 0}
#define Position_init_default {0, 0, 0, 0, 0}
#define Data_init_default {_Data_Type_MIN, {0, {0}}}
#define User_init_default {"", "", "", {0}}
#define SubPacket_init_default {0, {Position_init_default}, 0}
@@ -185,11 +177,11 @@ typedef struct _ToRadio {
#define RadioConfig_init_default {false, RadioConfig_UserPreferences_init_default, false, ChannelSettings_init_default}
#define RadioConfig_UserPreferences_init_default {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
#define NodeInfo_init_default {0, false, User_init_default, false, Position_init_default, 0, 0}
#define MyNodeInfo_init_default {0, 0, 0}
#define DeviceState_init_default {false, RadioConfig_init_default, false, MyNodeInfo_init_default, false, User_init_default, 0, {NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default}, 0, {MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default}, _DeviceState_Version_MIN, false, MeshPacket_init_default}
#define MyNodeInfo_init_default {0, 0, 0, "", "", ""}
#define DeviceState_init_default {false, RadioConfig_init_default, false, MyNodeInfo_init_default, false, User_init_default, 0, {NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default, NodeInfo_init_default}, 0, {MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default, MeshPacket_init_default}, false, MeshPacket_init_default, 0}
#define FromRadio_init_default {0, 0, {MeshPacket_init_default}}
#define ToRadio_init_default {0, {MeshPacket_init_default}}
#define Position_init_zero {0, 0, 0, 0, 0, 0}
#define Position_init_zero {0, 0, 0, 0, 0}
#define Data_init_zero {_Data_Type_MIN, {0, {0}}}
#define User_init_zero {"", "", "", {0}}
#define SubPacket_init_zero {0, {Position_init_zero}, 0}
@@ -198,8 +190,8 @@ typedef struct _ToRadio {
#define RadioConfig_init_zero {false, RadioConfig_UserPreferences_init_zero, false, ChannelSettings_init_zero}
#define RadioConfig_UserPreferences_init_zero {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
#define NodeInfo_init_zero {0, false, User_init_zero, false, Position_init_zero, 0, 0}
#define MyNodeInfo_init_zero {0, 0, 0}
#define DeviceState_init_zero {false, RadioConfig_init_zero, false, MyNodeInfo_init_zero, false, User_init_zero, 0, {NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero}, 0, {MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero}, _DeviceState_Version_MIN, false, MeshPacket_init_zero}
#define MyNodeInfo_init_zero {0, 0, 0, "", "", ""}
#define DeviceState_init_zero {false, RadioConfig_init_zero, false, MyNodeInfo_init_zero, false, User_init_zero, 0, {NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero, NodeInfo_init_zero}, 0, {MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero, MeshPacket_init_zero}, false, MeshPacket_init_zero, 0}
#define FromRadio_init_zero {0, 0, {MeshPacket_init_zero}}
#define ToRadio_init_zero {0, {MeshPacket_init_zero}}
@@ -214,11 +206,13 @@ typedef struct _ToRadio {
#define MyNodeInfo_my_node_num_tag 1
#define MyNodeInfo_has_gps_tag 2
#define MyNodeInfo_num_channels_tag 3
#define MyNodeInfo_region_tag 4
#define MyNodeInfo_hw_model_tag 5
#define MyNodeInfo_firmware_version_tag 6
#define Position_latitude_tag 1
#define Position_longitude_tag 2
#define Position_altitude_tag 3
#define Position_battery_level_tag 4
#define Position_from_hardware_tag 5
#define Position_time_tag 6
#define RadioConfig_UserPreferences_position_broadcast_secs_tag 1
#define RadioConfig_UserPreferences_send_owner_interval_tag 2
@@ -257,7 +251,7 @@ typedef struct _ToRadio {
#define DeviceState_owner_tag 3
#define DeviceState_node_db_tag 4
#define DeviceState_receive_queue_tag 5
#define DeviceState_version_tag 6
#define DeviceState_version_tag 8
#define DeviceState_rx_text_message_tag 7
#define FromRadio_packet_tag 2
#define FromRadio_num_tag 1
@@ -269,7 +263,6 @@ X(a, STATIC, SINGULAR, DOUBLE, latitude, 1) \
X(a, STATIC, SINGULAR, DOUBLE, longitude, 2) \
X(a, STATIC, SINGULAR, INT32, altitude, 3) \
X(a, STATIC, SINGULAR, INT32, battery_level, 4) \
X(a, STATIC, SINGULAR, BOOL, from_hardware, 5) \
X(a, STATIC, SINGULAR, UINT32, time, 6)
#define Position_CALLBACK NULL
#define Position_DEFAULT NULL
@@ -356,7 +349,10 @@ X(a, STATIC, SINGULAR, INT32, frequency_error, 6)
#define MyNodeInfo_FIELDLIST(X, a) \
X(a, STATIC, SINGULAR, INT32, my_node_num, 1) \
X(a, STATIC, SINGULAR, BOOL, has_gps, 2) \
X(a, STATIC, SINGULAR, INT32, num_channels, 3)
X(a, STATIC, SINGULAR, INT32, num_channels, 3) \
X(a, STATIC, SINGULAR, STRING, region, 4) \
X(a, STATIC, SINGULAR, STRING, hw_model, 5) \
X(a, STATIC, SINGULAR, STRING, firmware_version, 6)
#define MyNodeInfo_CALLBACK NULL
#define MyNodeInfo_DEFAULT NULL
@@ -366,8 +362,8 @@ X(a, STATIC, OPTIONAL, MESSAGE, my_node, 2) \
X(a, STATIC, OPTIONAL, MESSAGE, owner, 3) \
X(a, STATIC, REPEATED, MESSAGE, node_db, 4) \
X(a, STATIC, REPEATED, MESSAGE, receive_queue, 5) \
X(a, STATIC, SINGULAR, UENUM, version, 6) \
X(a, STATIC, OPTIONAL, MESSAGE, rx_text_message, 7)
X(a, STATIC, OPTIONAL, MESSAGE, rx_text_message, 7) \
X(a, STATIC, SINGULAR, UINT32, version, 8)
#define DeviceState_CALLBACK NULL
#define DeviceState_DEFAULT NULL
#define DeviceState_radio_MSGTYPE RadioConfig
@@ -420,7 +416,7 @@ extern const pb_msgdesc_t ToRadio_msg;
#define ToRadio_fields &ToRadio_msg
/* Maximum encoded size of messages (where known) */
#define Position_size 48
#define Position_size 46
#define Data_size 256
#define User_size 72
#define SubPacket_size 261
@@ -428,9 +424,9 @@ extern const pb_msgdesc_t ToRadio_msg;
#define ChannelSettings_size 50
#define RadioConfig_size 126
#define RadioConfig_UserPreferences_size 72
#define NodeInfo_size 157
#define MyNodeInfo_size 24
#define DeviceState_size 15085
#define NodeInfo_size 155
#define MyNodeInfo_size 63
#define DeviceState_size 15064
#define FromRadio_size 301
#define ToRadio_size 295

View File

@@ -30,6 +30,7 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
#include "screen.h"
#include "mesh-pb-constants.h"
#include "NodeDB.h"
#include "main.h"
#define FONT_HEIGHT 14 // actually 13 for "ariel 10" but want a little extra space
#define FONT_HEIGHT_16 (ArialMT_Plain_16[1] + 1)
@@ -139,6 +140,7 @@ void drawTextMessageFrame(OLEDDisplay *display, OLEDDisplayUiState *state, int16
{
MeshPacket &mp = devicestate.rx_text_message;
NodeInfo *node = nodeDB.getNode(mp.from);
// DEBUG_MSG("drawing text message from 0x%x: %s\n", mp.from, mp.payload.variant.data.payload.bytes);
// Demo for drawStringMaxWidth:
// with the third parameter you can define the width after which words will be wrapped.
@@ -442,9 +444,19 @@ void drawDebugInfo(OLEDDisplay *display, OLEDDisplayUiState *state, int16_t x, i
static char channelStr[20];
snprintf(channelStr, sizeof(channelStr), "%s", channelSettings.name);
// We don't show battery levels yet - for now just lie and show debug info
static char batStr[20];
snprintf(batStr, sizeof(batStr), "Batt %x%%", (isCharging << 1) + isUSBPowered);
static char gpsStr[20];
if (myNodeInfo.has_gps)
snprintf(gpsStr, sizeof(gpsStr), "GPS %d%%", 75); // FIXME, use something based on hdop
else
gpsStr[0] = '\0'; // Just show emptystring
const char *fields[] = {
"Batt 89%",
"GPS 75%",
batStr,
gpsStr,
usersStr,
channelStr,
NULL};
@@ -495,17 +507,21 @@ void Screen::setOn(bool on)
if (on != screenOn)
{
if (on) {
if (on)
{
DEBUG_MSG("Turning on screen\n");
dispdev.displayOn();
setPeriod(1); // redraw ASAP
}
else
else {
DEBUG_MSG("Turning off screen\n");
dispdev.displayOff();
}
screenOn = on;
}
}
static void screen_print(const char *text, uint8_t x, uint8_t y, uint8_t alignment)
void screen_print(const char *text, uint8_t x, uint8_t y, uint8_t alignment)
{
DEBUG_MSG(text);
@@ -608,7 +624,6 @@ void Screen::doTask()
targetFramerate = IDLE_FRAMERATE;
ui.setTargetFPS(targetFramerate);
}
ui.update();
// While showing the bluetooth pair screen all of our standard screen switching is stopped
if (!showingBluetooth)
@@ -619,7 +634,7 @@ void Screen::doTask()
if (millis() > 3 * 1000) // we show the boot screen for a few seconds only
{
showingBootScreen = false;
screen_set_frames();
setFrames();
}
}
else // standard screen loop handling ehre
@@ -627,13 +642,16 @@ void Screen::doTask()
// If the # nodes changes, we need to regen our list of screens
if (nodeDB.updateGUI || nodeDB.updateTextMessage)
{
screen_set_frames();
setFrames();
nodeDB.updateGUI = false;
nodeDB.updateTextMessage = false;
}
}
}
// This must be after we possibly do screen_set_frames() to ensure we draw the new data
ui.update();
// DEBUG_MSG("want fps %d, fixed=%d\n", targetFramerate, ui.getUiState()->frameState);
// If we are scrolling we need to be called soon, otherwise just 1 fps (to save CPU)
// We also ask to be called twice as fast as we really need so that any rounding errors still result
@@ -660,7 +678,7 @@ void screen_start_bluetooth(uint32_t pin)
}
// restore our regular frame list
void screen_set_frames()
void Screen::setFrames()
{
DEBUG_MSG("showing standard frames\n");
@@ -704,4 +722,4 @@ void Screen::onPress()
targetFramerate = TRANSITION_FRAMERATE;
ui.setTargetFPS(targetFramerate);
}
}
}

View File

@@ -3,6 +3,7 @@
#include "PeriodicTask.h"
void screen_print(const char * text);
void screen_print(const char * text, uint8_t x, uint8_t y, uint8_t alignment);
// Show the bluetooth PIN screen
@@ -34,6 +35,10 @@ public:
/// Handle a button press
void onPress();
/// Rebuilt our list of screens
void setFrames();
private:
};
extern Screen screen;
extern Screen screen;

View File

@@ -14,11 +14,12 @@
#include "esp_pm.h"
#include "MeshRadio.h"
#include "main.h"
#include "sleep.h"
#ifdef T_BEAM_V10
#include "axp20x.h"
extern AXP20X_Class axp;
#endif
#endif
// deep sleep support
RTC_DATA_ATTR int bootCount = 0;
@@ -27,11 +28,6 @@ esp_sleep_source_t wakeCause; // the reason we booted this time
#define xstr(s) str(s)
#define str(s) #s
#include "esp_bt_main.h"
bool bluetoothOn = true; // we turn it on during setup() so default on
// -----------------------------------------------------------------------------
// Application
// -----------------------------------------------------------------------------
@@ -65,7 +61,7 @@ void setLed(bool ledOn)
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)
@@ -86,9 +82,24 @@ void initDeepSleep()
wakeButtons = ((uint64_t)1) << buttons.gpios[0];
*/
DEBUG_MSG("booted, wake cause %d (boot count %d)\n", wakeCause, bootCount);
}
// 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 == TG0WDT_SYS_RESET)
reason = "taskWatchdog";
if (hwReason == TG1WDT_SYS_RESET)
reason = "intWatchdog";
if (wakeCause == ESP_SLEEP_WAKEUP_TIMER)
reason = "timeout";
DEBUG_MSG("booted, wake cause %d (boot count %d), reset_reason=%s\n", wakeCause, bootCount, reason);
}
void doDeepSleep(uint64_t msecToWake)
{
@@ -177,31 +188,6 @@ void doDeepSleep(uint64_t msecToWake)
esp_deep_sleep_start(); // TBD mA sleep current (battery)
}
void setBluetoothEnable(bool on)
{
if (on != bluetoothOn)
{
DEBUG_MSG("Setting bluetooth enable=%d\n", on);
bluetoothOn = on;
if (on)
{
if (esp_bt_controller_enable(ESP_BT_MODE_BTDM) != ESP_OK)
DEBUG_MSG("error reenabling bt controller\n");
if (esp_bluedroid_enable() != ESP_OK)
DEBUG_MSG("error reenabling bluedroid\n");
}
else
{
if (esp_bluedroid_disable() != ESP_OK)
DEBUG_MSG("error disabling bluedroid\n");
if (esp_bt_controller_disable() != ESP_OK)
DEBUG_MSG("error disabling bt controller\n");
}
}
}
/**
* enter light sleep (preserves ram but stops everything about CPU).
*
@@ -212,7 +198,7 @@ esp_sleep_wakeup_cause_t doLightSleep(uint64_t sleepMsec) // FIXME, use a more r
//DEBUG_MSG("Enter light sleep\n");
uint64_t sleepUsec = sleepMsec * 1000LL;
Serial.flush(); // send all our characters before we stop cpu clock
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