rx path to phone is written

1.2-legacy
geeksville 2020-02-02 18:33:46 -08:00
rodzic 74adc06f89
commit b799004f0d
6 zmienionych plików z 60 dodań i 31 usunięć

Wyświetl plik

@ -37,6 +37,7 @@ until the phone pulls those packets. Ever so often power on bluetooth just so w
* pick channel center frequency based on name? "dolphin" would hash to 900Mhz, "cat" to 905MHz etc? Or is that too opaque?
* scan to find channels with low background noise?
* share channel settings over Signal (or qr code) by embedding an an URL which is handled by the MeshUtil app.
* make jtag debugger id stable: https://askubuntu.com/questions/49910/how-to-distinguish-between-identical-usb-to-serial-adapters
# Low priority

Wyświetl plik

@ -20,13 +20,21 @@ framework = arduino
board_build.partitions = partition-table.csv
; note: we add src to our include search path so that lmic_project_config can override
build_flags = -Wall -Wextra -Wno-missing-field-initializers -O3 -Wl,-Map,.pio/build/esp32/output.map
build_flags = -Wall -Wextra -Wno-missing-field-initializers -O3 -Wl,-Map,.pio/build/esp32/output.map -DAXP_DEBUG_PORT=Serial
; -DLOG_LOCAL_LEVEL=ESP_LOG_DEBUG -DCORE_DEBUG_LEVEL=ARDUHAL_LOG_LEVEL_DEBUG
upload_speed = 921600
; upload_port = /dev/ttyUSB0
; the default is esptool
; upload_protocol = esp-prog
; monitor_port = /dev/ttyUSB0
monitor_speed = 115200
debug_tool = esp-prog
# debug_port = /dev/ttyUSB0
lib_deps =
RadioHead
TinyGPSPlus

Wyświetl plik

@ -10,7 +10,6 @@
#include "mesh.pb.h"
#include "MeshService.h"
static BLECharacteristic meshFromRadioCharacteristic("8ba2bcc2-ee02-4a55-a531-c525c5e454d5", BLECharacteristic::PROPERTY_READ);
static BLECharacteristic meshToRadioCharacteristic("f75c76d2-129e-4dad-a1dd-7866124401e7", BLECharacteristic::PROPERTY_WRITE);
static BLECharacteristic meshFromNumCharacteristic("ed9da18c-a800-4f66-a670-aa7547e34453", BLECharacteristic::PROPERTY_WRITE | BLECharacteristic::PROPERTY_READ | BLECharacteristic::PROPERTY_NOTIFY);
@ -23,9 +22,41 @@ class BluetoothMeshCallbacks : public BLECharacteristicCallbacks
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
// c->setValue(byteptr, len);
if (!mp)
{
c->setValue((uint8_t *)"", 0);
}
else
{
static FromRadio fradio;
// Encapsulate as a ToRadio packet
memset(&fradio, 0, sizeof(fradio));
fradio.which_variant = FromRadio_packet_tag;
memcpy(&fradio.variant.packet, mp, sizeof(*mp));
service.releaseToPool(mp); // we just copied the bytes, so don't need this buffer anymore
static uint8_t trBytes[ToRadio_size];
pb_ostream_t stream = pb_ostream_from_buffer(trBytes, sizeof(trBytes));
if (!pb_encode(&stream, FromRadio_fields, &fradio))
{
Serial.printf("Error: can't encode FromRadio %s\n", PB_GET_ERROR(&stream));
}
else
{
c->setValue(trBytes, stream.bytes_written);
}
}
}
else
{
assert(0); // fixme not yet implemented
}
}
@ -111,7 +142,3 @@ BLEService *createMeshBluetoothService(BLEServer *server)
return service;
}

Wyświetl plik

@ -36,27 +36,12 @@ public:
/// Do idle processing (mostly processing messages which have been queued from the radio)
void loop();
#if 0
/**
* handle an incoming MeshPacket from the radio, update DB state and queue it for the phone
*/
void handleFromRadio(NodeNum from, NodeNum to, const uint8_t *buf, size_t len) {
MeshPacket *p = packetPool.allocZeroed();
assert(p);
/// Return the next packet destined to the phone. FIXME, somehow use fromNum to allow the phone to retry the
/// last few packets if needs to.
MeshPacket *getForPhone() { return toPhoneQueue.dequeuePtr(0); }
pb_istream_t stream = pb_istream_from_buffer(buf, len);
if (!pb_decode(&stream, MeshPacket_fields, p) || !p->has_payload)
{
Serial.printf("Error: can't decode MeshPacket %s\n", PB_GET_ERROR(&stream));
}
else
{
// FIXME - update DB state based on payload and show recevied texts
toPhoneQueue.enqueue(p);
}
}
#endif
/// Allows the bluetooth handler to free packets after they have been sent
void releaseToPool(MeshPacket *p) { packetPool.release(p); }
/// Given a ToRadio buffer (from bluetooth) parse it and properly handle it (setup radio, owner or send packet into the mesh)
void handleToRadio(std::string s);

Wyświetl plik

@ -37,18 +37,22 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
// -----------------------------------------------------------------------------
// Select which T-Beam board is being used. Only uncomment one.
#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 DEBUG_PORT Serial // Serial debug port
#define SERIAL_BAUD 115200 // Serial debug baud rate
#define SLEEP_MSECS (30 * 24 * 60 * 60 * 1000LL) // Sleep for these many millis (or a button press or a lora msg?)
#define MESSAGE_TO_SLEEP_DELAY 5000 // Time after message before going to sleep
#define LOGO_DELAY 5000 // Time to show logo on first boot
#define LOGO_DELAY 2000 // Time to show logo on first boot
#define REQUIRE_RADIO true // If true, we will fail to start if the radio is not found
// If not defined, we will wait for lock forever
#define MINWAKE_MSECS (30 * 1000) // Wait after every boot for GPS lock (may need longer than 5s because we turned the gps off during deep sleep)
#define MINWAKE_MSECS (30 * 60 * 1000) // stay awake a long time (30 mins) for debugging
// #define MINWAKE_MSECS (30 * 1000) // Wait after every boot for GPS lock (may need longer than 5s because we turned the gps off during deep sleep)
// -----------------------------------------------------------------------------
// DEBUG

Wyświetl plik

@ -251,6 +251,8 @@ void axp192Init()
Serial.printf("DCDC3: %s\n", axp.isDCDC3Enable() ? "ENABLE" : "DISABLE");
Serial.printf("Exten: %s\n", axp.isExtenEnable() ? "ENABLE" : "DISABLE");
axp.debugCharging();
pinMode(PMU_IRQ, INPUT_PULLUP);
attachInterrupt(PMU_IRQ, [] {
pmu_irq = true;
@ -378,10 +380,12 @@ void loop()
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);
}
#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)