Extensively refactor to reduce resource usage.

Looks like LMIC is still an issue though :-/
This commit is contained in:
Starbeamrainbowlabs 2019-06-26 15:46:07 +01:00
parent 130697395b
commit bdf9d4dd16
13 changed files with 101 additions and 104 deletions

3
.gitmodules vendored
View file

@ -10,3 +10,6 @@
[submodule "iot/libraries/arduino-lmic"]
path = iot/libraries/arduino-lmic
url = https://github.com/matthijskooijman/arduino-lmic.git
[submodule "iot/libraries/Arduino-MemoryFree"]
path = iot/libraries/Arduino-MemoryFree
url = https://github.com/mpflaga/Arduino-MemoryFree.git

@ -0,0 +1 @@
Subproject commit aed5cc5e28f8f01afc41a625151c184a8e94e32e

View file

@ -1,33 +1,35 @@
#include "gps.h"
#include "settings.h"
// The GPS message decoder
TinyGPSPlus gps;
// The serial connection to the GPS device
SoftwareSerial serial_gps(PIN_GPS_RX, PIN_GPS_TX);
SoftwareSerial* serial_gps;
void gps_begin() {
serial_gps = new SoftwareSerial(PIN_GPS_RX, PIN_GPS_TX);
// Initialise the software-based serial connection to the GPS device
serial_gps.begin(BAUD_GPS);
serial_gps->begin(BAUD_GPS);
}
void gps_fetch() {
Serial.print(F("[gps] Getting location: "));
GPSLocation gps_fetch() {
// The GPS message decoder
TinyGPSPlus gps;
GPSLocation result;
Serial.print(F("[gps] Working: "));
uint32_t ms_last_update = millis();
// We WILL discover our location - if it's the last thing we do!
while(true) {
if(millis() > 5000 && gps.charsProcessed() < 10) {
Serial.println(F("\n[error] Failed to initialise GPS device."));
Serial.println(F("\n[error] GPS device init failed"));
while(true) { delay(1); }
}
// Make sure there's something to read
if(serial_gps.available() <= 0) {
if(serial_gps->available() <= 0)
continue;
}
// If it failed, go around again
if(!gps.encode(serial_gps.read()))
if(!gps.encode(serial_gps->read()))
continue;
// If we haven't acquired a lock yet, go around again
@ -41,14 +43,26 @@ void gps_fetch() {
// Hooray!
Serial.println(F("ok"));
return;
}
}
TinyGPSPlus gps_info() {
return gps;
result.lat = gps.location.lat();
result.lng = gps.location.lng();
#ifdef SD_DEBUG_ENABLED
snprintf(result.time, 19, "%04d-%02d-%02d %02d:%02d:%02d",
gps.date.year(),
gps.date.month(),
gps.date.day(),
gps.time.hour(),
gps.time.minute(),
gps.time.second()
);
#endif
return result;
}
}
void gps_end() {
Serial.println(F("[warning] Putting the GPS device to sleep isn't implemented yet."));
serial_gps->end();
delete serial_gps;
//delete gps;
// Serial.println(F("[warning] Putting the GPS device to sleep isn't implemented yet."));
}

View file

@ -6,6 +6,16 @@
#include "settings.h"
// A lightweight struct to hold location information.
// TinyGPS++ actually uses a *ton* of RAM so we can't keep the instance around as a global variable
struct GPSLocation {
float lat;
float lng;
#ifdef SD_DEBUG_ENABLED
char time[20];
#endif
};
/**
* Initialises the connection to the GPS device.
*/
@ -15,14 +25,7 @@ void gps_begin();
* Fetches new data from the GPS module.
* May take a moment, as the GPS device needs time to acquire a satellite fix.
*/
void gps_fetch();
/**
* Fetches the latest information from the GPS device.
* Call gps_fetch() first.
* @return TinyGPSLocation The current location.
*/
TinyGPSPlus gps_info();
GPSLocation gps_fetch();
/**
* Ends the connection to the GPS device and puts it to sleep in order to save

View file

@ -2,6 +2,7 @@
#include <Arduino.h>
#include <TinyGPS++.h>
#include <SD.h>
#include <MemoryFree.h>
#include "random.h"
// BAD PRACTICE: For some extremely strange reason, the Arduino IDE doesn't pick up random.cpp like it does our other source files - so we've got to explicitly include it here. If we had control over the build process (which we don't), we've use a Makefile here that handled this better.
@ -15,43 +16,41 @@
void setup() {
Serial.begin(BAUD_PC);
Serial.println(F("[main] Beginning collection sequence."));
Serial.println(F("[main] Starting"));
random_begin();
Serial.println(freeMemory(), DEC); // 1
peripheral_register(PIN_SPI_CS_RFM95);
peripheral_register(PIN_SPI_CS_SD);
Serial.println(freeMemory(), DEC); // 2
gps_begin();
TinyGPSPlus gps_data = gps_info();
Serial.println(freeMemory(), DEC); // 3
GPSLocation gps_data = gps_fetch();
Serial.println(freeMemory(), DEC); // 4
gps_end();
Serial.println(freeMemory(), DEC); // 5
Serial.print(F("[main] Location: (")); Serial.print(gps_data.location.lat()); Serial.print(F(", ")); Serial.print(gps_data.location.lng()); Serial.println(F(")"));
Serial.print(F("[main] Location ")); Serial.print(gps_data.lat); Serial.print(F(", ")); Serial.println(gps_data.lng);
uint32_t id = random_get();
Serial.print(F("[main] id: "));
Serial.print(F("[main] Id "));
Serial.println(id);
// Activate microSD card breakout board on the SPI bus
peripheral_unsilence(PIN_SPI_CS_SD);
store_init();
store_reading(id, gps_data.location);
char debug_message[64];
int chars = snprintf(debug_message, 64, "%d-%d-%d %d:%d:%d | %f %f",
gps_data.date.year(),
gps_data.date.month(),
gps_data.date.day(),
gps_data.time.hour(),
gps_data.time.minute(),
gps_data.time.second(),
gps_data.location.lat(),
gps_data.location.lng()
);
store_debug(debug_message, chars);
Serial.println(freeMemory(), DEC); // 6
store_reading(id, gps_data);
#ifdef SD_DEBUG_ENABLED
store_debug(gps_data.time, 19);
#endif
store_close();
Serial.println(freeMemory(), DEC); // 7
// ------------------------------------------------------------------------
@ -60,8 +59,8 @@ void setup() {
uint8_t message[] = "testing";
transmit_init();
transmit_send(message, 7);
// transmit_init();
// transmit_send(message, 7);
power_off(); // Doesn't return

View file

@ -1,20 +1,20 @@
#include <Arduino.h>
void peripheral_register(int pin_number) {
void peripheral_register(uint8_t pin_number) {
pinMode(OUTPUT, pin_number);
// Disable the device by default to avoid issues
digitalWrite(pin_number, HIGH);
}
void peripheral_unsilence(int pin_number) {
void peripheral_unsilence(uint8_t pin_number) {
digitalWrite(pin_number, LOW);
}
void peripheral_silence(int pin_number) {
void peripheral_silence(uint8_t pin_number) {
digitalWrite(pin_number, HIGH);
}
void peripheral_switch(int pin_number_old, int pin_number_new) {
void peripheral_switch(uint8_t pin_number_old, uint8_t pin_number_new) {
digitalWrite(pin_number_old, HIGH);
digitalWrite(pin_number_new, LOW);
}

View file

@ -4,21 +4,21 @@
* Register a new SPI peripheral.
* @param pin_number The pin number of the device's chip select pin.
*/
void peripheral_register(int pin_number);
void peripheral_register(uint8_t pin_number);
/**
* Allows the device with the given chip select pin to talk on the SPI bus.
* @param pin_number The pin number of the chip select pin of the device to allow to talk.
*/
void peripheral_unsilence(int pin_number);
void peripheral_unsilence(uint8_t pin_number);
/**
* Stops the device with the given chip select pin from talking on the SPI bus.
* @param pin_number The chip-select pin number of the device to stop.
*/
void peripheral_silence(int pin_number);
void peripheral_silence(uint8_t pin_number);
/**
* Switches the active device from one to another on the SPI bus.
* @param pin_number_old The chip-select pin number of the old device to switch out from.
* @param pin_number_new The chip-select pin number of the new device to switch in to.
*/
void peripheral_switch(int pin_number_old, int pin_number_new);
void peripheral_switch(uint8_t pin_number_old, uint8_t pin_number_new);

View file

@ -2,16 +2,6 @@
#include "settings.h"
/*
void power_gps_wakeup() {
Serial.println(F("Warn: GPS wakeup isn't implemented yet."));
}
void power_gps_standby() {
Serial.println(F("Warn: GPS standby isn't implemented yet."));
}
*/
void power_off() {
Serial.println(F("[power] Shutting down"));
// Serial.println(F("[power] Switching GPS module to standby"));

View file

@ -1,13 +1,4 @@
/**
* Wakes the GPS module up from standby.
*/
// void power_gps_wakeup();
/**
* Puts the GPS module into standby.
*/
// void power_gps_standby();
/**
* Signals that our work is complete and that we can turn off now to the
* TPL5111.

View file

@ -31,6 +31,9 @@
/// RFM95 ///
/////////////
// Whether to actually enable LMIC-based transmission or not.
#define ENABLE_RADIO
// The SPI chip-select pin for the RFM 95
#define PIN_SPI_CS_RFM95 10
@ -63,7 +66,10 @@
#define PIN_SPI_CS_SD 3
// The filename on the microSD card to store data in.
#define SD_FILENAME "data.tsv"
#define SD_FILENAME F("data.tsv")
// Whether to write debug information to the filename below. This could compromise privacy, so it should be commented out for production.
#define SD_DEBUG_ENABLED
// The filename on the microSD card to store debug information in
#define SD_FILENAME_DEBUG "debug.log"
#define SD_FILENAME_DEBUG F("debug.log")

View file

@ -3,29 +3,28 @@
#include <TinyGPS++.h>
#include "settings.h"
File _debug_handle;
#include "gps.h"
void store_init() {
// NOTE: If this doesn't work, then we need to use pinMode() & specify the data pin here instead.
if(!SD.begin(PIN_SPI_CS_SD)) {
Serial.println(F("Error: Failed to initialise connection to microSD card"));
Serial.println(F("Error: MicroSD card init failed"));
while(true) { delay(1); } // Pseudo-halt, but uses delay() to ensure we keep passing back control to allow easy re-programming
}
}
void store_reading(uint32_t id, TinyGPSLocation location) {
void store_reading(uint32_t id, GPSLocation location) {
// Open the file to write the data to. If it doesn't exist it will be created.
// Unlike elsewhere, FILE_WRITE opens the file with the cursor starting at the end, so it's basically actually equivalent to FILE_APPEND that we use in other environments. Confusing, I know.
File handle = SD.open(SD_FILENAME, FILE_WRITE);
handle.print(id);
handle.print("\t");
handle.print(F("\t"));
handle.print(location.lat());
handle.print("\t");
handle.print(location.lat);
handle.print(F("\t"));
handle.print(location.lng());
handle.print(location.lng);
handle.println();
handle.close();
@ -33,7 +32,9 @@ void store_reading(uint32_t id, TinyGPSLocation location) {
void store_debug(char* buffer, int size) {
File handle = SD.open(SD_FILENAME_DEBUG, FILE_WRITE);
handle.write(buffer, size);
handle.println();
handle.close();
}
void store_close() {

View file

@ -7,7 +7,7 @@
void store_init();
void store_reading(uint32_t id, TinyGPSLocation location);
void store_reading(uint32_t id, GPSLocation location);
void store_debug(char* buffer, int size);

View file

@ -5,13 +5,10 @@
#include "settings.h"
// Global static variable that's used to detect when LMIC has finished doing it's thing
static bool is_sending_complete = false;
static osjob_t sendjob;
bool is_sending_complete = false;
void transmit_init() {
Serial.println(F("Initialising LMIC"));
Serial.println(F("[LMIC] Init"));
// LMIC init
os_init();
// Reset the MAC state. Session and pending data transfers will be discarded.
@ -70,7 +67,7 @@ void transmit_init() {
bool transmit_send(uint8_t* data, int length) {
// Check if there is not a current TX/RX job running
if (LMIC.opmode & OP_TXRXPEND) {
Serial.println(F("OP_TXRXPEND: There's already a job running, not sending"));
Serial.println(F("OP_TXRXPEND: Job running, can't send"));
return false;
}
// Prepare upstream data transmission at the next possible time.
@ -88,16 +85,9 @@ bool transmit_send(uint8_t* data, int length) {
return true;
}
// These callbacks are only used in over-the-air activation, so they are
// left empty here (we cannot leave them out completely unless
// DISABLE_JOIN is set in config.h, otherwise the linker will complain).
void os_getArtEui (u1_t* buf) { }
void os_getDevEui (u1_t* buf) { }
void os_getDevKey (u1_t* buf) { }
void onEvent (ev_t ev) {
Serial.print(os_getTime());
Serial.print(": ");
Serial.print(millis());
Serial.print(" ");
switch(ev) {
case EV_SCAN_TIMEOUT:
Serial.println(F("EV_SCAN_TIMEOUT"));
@ -111,27 +101,26 @@ void onEvent (ev_t ev) {
case EV_BEACON_TRACKED:
Serial.println(F("EV_BEACON_TRACKED"));
break;
case EV_JOINING:
/*case EV_JOINING:
Serial.println(F("EV_JOINING"));
break;
case EV_JOINED:
Serial.println(F("EV_JOINED"));
break;
break;*/
case EV_RFU1:
Serial.println(F("EV_RFU1"));
break;
case EV_JOIN_FAILED:
/*case EV_JOIN_FAILED:
Serial.println(F("EV_JOIN_FAILED"));
break;
case EV_REJOIN_FAILED:
Serial.println(F("EV_REJOIN_FAILED"));
break;
break;
break;*/
case EV_TXCOMPLETE:
Serial.println(F("EV_TXCOMPLETE (includes waiting for RX windows)"));
Serial.println(F("EV_TXCOMPLETE (incl. RX window wait)"));
if(LMIC.dataLen) {
// data received in rx slot after tx
Serial.print(F("Data Received: "));
Serial.print(F("Received: "));
Serial.write(LMIC.frame+LMIC.dataBeg, LMIC.dataLen);
Serial.println();
}