Kaynağa Gözat

Moved configuration values to dedicated files and documented them.

tags/v1.2.2
Bertrand Lemasle 6 yıl önce
ebeveyn
işleme
9b66b8b395
19 değiştirilmiş dosya ile 621 ekleme ve 511 silme
  1. +32
    -111
      src/Config.h
  2. +28
    -28
      src/Core.h
  3. +159
    -159
      src/Hardware.cpp
  4. +44
    -44
      src/MainUnit.cpp
  5. +25
    -25
      src/NetworkPositionsBackup.h
  6. +0
    -16
      src/NetworkPositionsConfig.h
  7. +0
    -13
      src/Pins.h
  8. +85
    -85
      src/Rtc.cpp
  9. +18
    -17
      src/SdCard.cpp
  10. +12
    -13
      src/SdCard.h
  11. +32
    -0
      src/config/Alerts.h
  12. +24
    -0
      src/config/BackupNetwork.h
  13. +1
    -0
      src/config/BackupSd.h
  14. +17
    -0
      src/config/Gps.h
  15. +28
    -0
      src/config/Main.h
  16. +10
    -0
      src/config/Network.h
  17. +16
    -0
      src/config/Pins.h
  18. +53
    -0
      src/config/Sleeps.h
  19. +37
    -0
      src/config/System.h

+ 32
- 111
src/Config.h Dosyayı Görüntüle

@@ -1,112 +1,33 @@
#pragma once

#include <Arduino.h>

#define BACKUP_ENABLE_SDCARD 0
#define BACKUP_ENABLE_NETWORK 1

#if BACKUP_ENABLE_NETWORK
#include "NetworkPositionsConfig.h"
#endif

#define SIM808_BAUDRATE 4800

#define CONFIG_ADDR 0
#define CONFIG_RESERVED_SIZE 128
#define CONFIG_SEED 14
#define VERSION "1.20"

#define SLEEP_TIMING_TIME(hours, minutes) hours * 60 + minutes

#pragma region Default configuration values

#define MENU_TIMEOUT 10000
/**
\def SLEEP_DEFAULT_TIME_SECONDS
Hard coded value for default sleep time between position acquisitions.
Exprimed in seconds
*/

#define CONFIG_DEFAULT_BATTERY_ALERT_LEVEL1 45
#define CONFIG_DEFAULT_BATTERY_ALERT_LEVEL2 38
#define CONFIG_DEFAULT_BATTERY_ALERT_CLEAR 60
#define CONFIG_DEFAULT_ACTIVE_ALERTS 0
#define CONFIG_DEFAULT_CONTACT_PHONE "+642568452"

#define SLEEP_DEFAULT_TIME_SECONDS 1800
#define SLEEP_DEFAULT_STOPPED_THRESHOLD 5
#define SLEEP_DEFAULT_PAUSING_TIME_SECONDS 270

#define SLEEP_TIMING_MIN SLEEP_TIMING_TIME(0, 0)
#define SLEEP_TIMING_MAX SLEEP_TIMING_TIME(23, 59)
#define SLEEP_TIMING_MIN_MOVING_VELOCITY 5

#define GPS_DEFAULT_INTERMEDIATE_TIMEOUT_MS 10000L
#define GPS_DEFAULT_TOTAL_TIMEOUT_MS 80000L
#define GPS_DEFAULT_MISSED_POSITION_GAP_KM 2

#define NETWORK_DEFAULT_INTERMEDIATE_TIMEOUT_MS 10000L
#define NETWORK_DEFAULT_TOTAL_TIMEOUT_MS 80000L
#define NETWORK_DEFAULT_NO_NETWORK_QUALITY_THRESHOLD 8
#define NETWORK_DEFAULT_NO_NETWORK_TRIES 5

#define ALERTS_ON_SERIAL_IF_AVAILABLE 1
/**
\def ALERTS_ON_SERIAL_IF_AVAILABLE
Display alerts on serial when connected rather than sending an SMS.
Useful for debugging purpose and avoid costs related to SMS sending.
*/
#define ALERT_SUSPICIOUS_RTC_TEMPERATURE 0

#pragma endregion

struct sleepTimings_t {
uint8_t speed;
uint16_t timeMin;
uint16_t timeMax;
uint16_t seconds;
};

struct config_t {
uint8_t seed; //sizeof = 1
char version[5]; //sizeof = 5
uint16_t firstEntry; //sizeof = 2
uint16_t lastEntry; //sizeof = 2
#if BACKUP_ENABLE_NETWORK
networkConfig_t network; //sizeof = 73
#else
char reserved[73];
#endif
uint8_t alertBatteryLevel1; //sizeof = 1
uint8_t alertBatteryLevel2; //sizeof = 1
uint8_t alertBatteryLevelClear; //sizeof = 1
uint8_t activeAlerts; //sizeof = 1
char contactPhone[15]; //sizeof = 15
}; //sizeof = 29 + 73 = 102

namespace config {

static const sleepTimings_t defaultSleepTimings[] PROGMEM = {
{ 0, SLEEP_TIMING_TIME(16, 00), SLEEP_TIMING_TIME(19, 59), 3600 },
{ 0, SLEEP_TIMING_TIME(20, 00), SLEEP_TIMING_MAX, SLEEP_DEFAULT_TIME_SECONDS },
{ 0, SLEEP_TIMING_MIN, SLEEP_TIMING_TIME(8, 29), SLEEP_DEFAULT_TIME_SECONDS },
{ 0, SLEEP_TIMING_TIME(8, 30), SLEEP_TIMING_TIME(15, 59), 10800 },

{ SLEEP_TIMING_MIN_MOVING_VELOCITY, SLEEP_TIMING_MIN, SLEEP_TIMING_MAX, 540 },
{ 10, SLEEP_TIMING_MIN, SLEEP_TIMING_MAX, 270 },
{ 20, SLEEP_TIMING_MIN, SLEEP_TIMING_MAX, 225 },
{ 30, SLEEP_TIMING_MIN, SLEEP_TIMING_MAX, 240 },
{ 45, SLEEP_TIMING_MIN, SLEEP_TIMING_MAX, 280 },
{ 65, SLEEP_TIMING_MIN, SLEEP_TIMING_MAX, 276 },
{ 85, SLEEP_TIMING_MIN, SLEEP_TIMING_MAX, 225 }
};

namespace main {
extern config_t value;

void setup();
void save();

void reset();
}
#pragma once
#include <Arduino.h>
#include "config/Main.h"
struct config_t {
uint8_t seed; //sizeof = 1
char version[5]; //sizeof = 5
uint16_t firstEntry; //sizeof = 2
uint16_t lastEntry; //sizeof = 2
#if BACKUP_ENABLE_NETWORK
networkConfig_t network; //sizeof = 73
#else
char reserved[73];
#endif
uint8_t alertBatteryLevel1; //sizeof = 1
uint8_t alertBatteryLevel2; //sizeof = 1
uint8_t alertBatteryLevelClear; //sizeof = 1
uint8_t activeAlerts; //sizeof = 1
char contactPhone[15]; //sizeof = 15
}; //sizeof = 29 + 73 = 102
namespace config {
namespace main {
extern config_t value;
void setup();
void save();
void reset();
}
}

+ 28
- 28
src/Core.h Dosyayı Görüntüle

@@ -1,29 +1,29 @@
#pragma once
#include <Arduino.h>
#include "Debug.h"
#include "Gps.h"
#include "MainUnit.h"
#include "Network.h"
#include "Rtc.h"
#include "Pins.h"
#include "Positions.h"
enum class TRACKER_MOVING_STATE : uint8_t {
MOVING = 0,
PAUSED = 1,
STOPPED = 2,
STATIC = 3
};
namespace core {
extern uint16_t sleepTime;
void main();
void updateRtcTime();
TRACKER_MOVING_STATE updateSleepTime();
uint16_t mapSleepTime(uint8_t velocity);
uint8_t notifyFailures(PositionEntryMetadata &metadata);
#pragma once
#include <Arduino.h>
#include "Debug.h"
#include "Gps.h"
#include "MainUnit.h"
#include "Network.h"
#include "Rtc.h"
#include "config/Pins.h"
#include "Positions.h"
enum class TRACKER_MOVING_STATE : uint8_t {
MOVING = 0,
PAUSED = 1,
STOPPED = 2,
STATIC = 3
};
namespace core {
extern uint16_t sleepTime;
void main();
void updateRtcTime();
TRACKER_MOVING_STATE updateSleepTime();
uint16_t mapSleepTime(uint8_t velocity);
uint8_t notifyFailures(PositionEntryMetadata &metadata);
}

+ 159
- 159
src/Hardware.cpp Dosyayı Görüntüle

@@ -1,159 +1,159 @@
#include "Config.h"
#include "Hardware.h"
#include "Pins.h"
#include "Debug.h"
#include <SoftwareSerial.h>
#include <SIM808.h>
#include <SIM808_Types.h>
#include <Wire.h>
#include <E24.h>
namespace hardware {
#define LOGGER_NAME "Hardware::sim808"
namespace sim808 {
SoftwareSerial simSerial = SoftwareSerial(SIM_TX, SIM_RX);
SIM808 device = SIM808(SIM_RST, SIM_PWR, SIM_STATUS);
uint8_t networkPoweredCount = 0;
uint8_t gpsPoweredCount = 0;
void powerOn() {
VERBOSE("powerOn");
bool poweredOn = device.powerOnOff(true);
if (!poweredOn) return;
device.init();
networkPoweredCount = gpsPoweredCount = 0;
}
void powerOff() {
VERBOSE("powerOff");
device.powerOnOff(false);
networkPoweredCount = gpsPoweredCount = 0;
}
void powerOffIfUnused() {
//does not rely on count for safety
//if there is a bug somewhere, the device will consume more battery,
//but will not fail due to an over aggressive battery saving strategy
bool gpsPowered = false;
if ((!device.getGpsPowerState(&gpsPowered) || !gpsPowered) &&
(device.getPhoneFunctionality() != SIM808_PHONE_FUNCTIONALITY::FULL)) {
powerOff();
}
}
void setup() {
NOTICE("setup");
simSerial.begin(SIM808_BAUDRATE);
device.begin(simSerial);
powerOff(); //ensure powerOff on start
}
void gpsPowerOn() {
if(gpsPoweredCount) {
gpsPoweredCount++;
return;
}
VERBOSE("gpsPowerOn");
powerOn();
if(!networkPoweredCount) {
//SIM808 turns phone on by default but we don't need it for gps only
device.setPhoneFunctionality(SIM808_PHONE_FUNCTIONALITY::MINIMUM);
}
device.enableGps();
}
void gpsPowerOff() {
if (!device.powered()) {
networkPoweredCount = gpsPoweredCount = 0; //just to be sure counts == 0
return;
}
if(gpsPoweredCount > 1) {
gpsPoweredCount--;
return;
}
VERBOSE("gpsPowerOff");
device.disableGps();
powerOffIfUnused();
}
void networkPowerOn() {
if(networkPoweredCount) {
networkPoweredCount++;
return;
}
VERBOSE("networkPowerOn");
powerOn();
device.setPhoneFunctionality(SIM808_PHONE_FUNCTIONALITY::FULL);
}
void networkPowerOff() {
if (!device.powered()) {
networkPoweredCount = gpsPoweredCount = 0; //just to be sure counts == 0
return;
}
if(networkPoweredCount > 1) {
networkPoweredCount--;
return;
}
VERBOSE("networkPowerOff");
device.disableGprs();
device.setPhoneFunctionality(SIM808_PHONE_FUNCTIONALITY::MINIMUM);
powerOffIfUnused();
}
}
#define LOGGER_NAME "Hardware::i2c"
namespace i2c {
E24 eeprom = E24(E24Size_t::E24_512K);
uint8_t poweredCount = 0;
void powerOn() {
if(poweredCount) {
poweredCount++;
return;
}
VERBOSE("powerOn");
digitalWrite(I2C_PWR, HIGH);
pinMode(I2C_PWR, OUTPUT);
Wire.begin();
poweredCount = 1;
}
void powerOff(bool forced = false) {
if(poweredCount > 1 && !forced) {
poweredCount--;
return;
}
VERBOSE("powerOff");
pinMode(I2C_PWR, INPUT);
digitalWrite(I2C_PWR, LOW);
//turn off i2c
TWCR &= ~(bit(TWEN) | bit(TWIE) | bit(TWEA));
//disable i2c internal pull ups
digitalWrite(A4, LOW);
digitalWrite(A5, LOW);
poweredCount = 0;
}
}
}
#include "Config.h"
#include "Hardware.h"
#include "config/Pins.h"
#include "Debug.h"
#include <SoftwareSerial.h>
#include <SIM808.h>
#include <SIM808_Types.h>
#include <Wire.h>
#include <E24.h>
namespace hardware {
#define LOGGER_NAME "Hardware::sim808"
namespace sim808 {
SoftwareSerial simSerial = SoftwareSerial(SIM_TX, SIM_RX);
SIM808 device = SIM808(SIM_RST, SIM_PWR, SIM_STATUS);
uint8_t networkPoweredCount = 0;
uint8_t gpsPoweredCount = 0;
void powerOn() {
VERBOSE("powerOn");
bool poweredOn = device.powerOnOff(true);
if (!poweredOn) return;
device.init();
networkPoweredCount = gpsPoweredCount = 0;
}
void powerOff() {
VERBOSE("powerOff");
device.powerOnOff(false);
networkPoweredCount = gpsPoweredCount = 0;
}
void powerOffIfUnused() {
//does not rely on count for safety
//if there is a bug somewhere, the device will consume more battery,
//but will not fail due to an over aggressive battery saving strategy
bool gpsPowered = false;
if ((!device.getGpsPowerState(&gpsPowered) || !gpsPowered) &&
(device.getPhoneFunctionality() != SIM808_PHONE_FUNCTIONALITY::FULL)) {
powerOff();
}
}
void setup() {
NOTICE("setup");
simSerial.begin(SIM808_BAUDRATE);
device.begin(simSerial);
powerOff(); //ensure powerOff on start
}
void gpsPowerOn() {
if(gpsPoweredCount) {
gpsPoweredCount++;
return;
}
VERBOSE("gpsPowerOn");
powerOn();
if(!networkPoweredCount) {
//SIM808 turns phone on by default but we don't need it for gps only
device.setPhoneFunctionality(SIM808_PHONE_FUNCTIONALITY::MINIMUM);
}
device.enableGps();
}
void gpsPowerOff() {
if (!device.powered()) {
networkPoweredCount = gpsPoweredCount = 0; //just to be sure counts == 0
return;
}
if(gpsPoweredCount > 1) {
gpsPoweredCount--;
return;
}
VERBOSE("gpsPowerOff");
device.disableGps();
powerOffIfUnused();
}
void networkPowerOn() {
if(networkPoweredCount) {
networkPoweredCount++;
return;
}
VERBOSE("networkPowerOn");
powerOn();
device.setPhoneFunctionality(SIM808_PHONE_FUNCTIONALITY::FULL);
}
void networkPowerOff() {
if (!device.powered()) {
networkPoweredCount = gpsPoweredCount = 0; //just to be sure counts == 0
return;
}
if(networkPoweredCount > 1) {
networkPoweredCount--;
return;
}
VERBOSE("networkPowerOff");
device.disableGprs();
device.setPhoneFunctionality(SIM808_PHONE_FUNCTIONALITY::MINIMUM);
powerOffIfUnused();
}
}
#define LOGGER_NAME "Hardware::i2c"
namespace i2c {
E24 eeprom = E24(E24Size_t::E24_512K);
uint8_t poweredCount = 0;
void powerOn() {
if(poweredCount) {
poweredCount++;
return;
}
VERBOSE("powerOn");
digitalWrite(I2C_PWR, HIGH);
pinMode(I2C_PWR, OUTPUT);
Wire.begin();
poweredCount = 1;
}
void powerOff(bool forced = false) {
if(poweredCount > 1 && !forced) {
poweredCount--;
return;
}
VERBOSE("powerOff");
pinMode(I2C_PWR, INPUT);
digitalWrite(I2C_PWR, LOW);
//turn off i2c
TWCR &= ~(bit(TWEN) | bit(TWIE) | bit(TWEA));
//disable i2c internal pull ups
digitalWrite(A4, LOW);
digitalWrite(A5, LOW);
poweredCount = 0;
}
}
}

+ 44
- 44
src/MainUnit.cpp Dosyayı Görüntüle

@@ -1,45 +1,45 @@
#include "MainUnit.h"
#include "Rtc.h"
#include "Pins.h"
#include "Debug.h"
#define LOGGER_NAME "MainUnit"
namespace mainunit {
namespace details {
void prepareSleep() {
hardware::sim808::simSerial.end(); //avoid woke up by SoftwareSerial interrupt
delay(5); //ensure log messages have been printed out
}
void wokeUp() {
tmElements_t wokeUpTime;
rtc::getTime(wokeUpTime);
VERBOSE_FORMAT("wokeUp", "%d:%d:%d", wokeUpTime.Hour, wokeUpTime.Minute, wokeUpTime.Second);
hardware::sim808::simSerial.listen();
}
}
void interrupt() {
detachInterrupt(digitalPinToInterrupt(RTC_WAKE));
}
void interruptIn(uint16_t seconds) {
rtc::setAlarm(seconds);
pinMode(RTC_WAKE, INPUT);
attachInterrupt(digitalPinToInterrupt(RTC_WAKE), interrupt, FALLING);
}
void deepSleep(uint16_t seconds) {
NOTICE_FORMAT("deepSleep", "%d seconds", seconds);
interruptIn(seconds);
details::prepareSleep();
LowPower.powerDown(SLEEP_FOREVER, ADC_OFF, BOD_OFF);
details::wokeUp();
}
#include "MainUnit.h"
#include "Rtc.h"
#include "config/Pins.h"
#include "Debug.h"
#define LOGGER_NAME "MainUnit"
namespace mainunit {
namespace details {
void prepareSleep() {
hardware::sim808::simSerial.end(); //avoid woke up by SoftwareSerial interrupt
delay(5); //ensure log messages have been printed out
}
void wokeUp() {
tmElements_t wokeUpTime;
rtc::getTime(wokeUpTime);
VERBOSE_FORMAT("wokeUp", "%d:%d:%d", wokeUpTime.Hour, wokeUpTime.Minute, wokeUpTime.Second);
hardware::sim808::simSerial.listen();
}
}
void interrupt() {
detachInterrupt(digitalPinToInterrupt(RTC_WAKE));
}
void interruptIn(uint16_t seconds) {
rtc::setAlarm(seconds);
pinMode(RTC_WAKE, INPUT);
attachInterrupt(digitalPinToInterrupt(RTC_WAKE), interrupt, FALLING);
}
void deepSleep(uint16_t seconds) {
NOTICE_FORMAT("deepSleep", "%d seconds", seconds);
interruptIn(seconds);
details::prepareSleep();
LowPower.powerDown(SLEEP_FOREVER, ADC_OFF, BOD_OFF);
details::wokeUp();
}
}

+ 25
- 25
src/NetworkPositionsBackup.h Dosyayı Görüntüle

@@ -1,26 +1,26 @@
#pragma once
#include "PositionsBackup.h"
#include "Time2.h"
#include "Positions.h"
namespace positions {
namespace backup {
namespace net {
class NetworkPositionsBackup : public PositionsBackup {
private:
bool isBackupNeeded(bool forPrepare);
bool appendPosition(PositionEntry &entry);
void appendPositions();
public:
void setup();
void prepare();
void backup(bool force);
};
}
}
#pragma once
#include "PositionsBackup.h"
#include "Time2.h"
#include "Positions.h"
namespace positions {
namespace backup {
namespace net {
class NetworkPositionsBackup : public PositionsBackup {
private:
bool isBackupNeeded(bool forPrepare);
bool appendPosition(PositionEntry &entry);
void appendPositions();
public:
void setup();
void prepare();
void backup(bool force);
};
}
}
}

+ 0
- 16
src/NetworkPositionsConfig.h Dosyayı Görüntüle

@@ -1,16 +0,0 @@
#pragma once


#define POSITIONS_CONFIG_NET_DEFAULT_SAVE_THRESHOLD 30
#define POSITIONS_CONFIG_NET_DEFAULT_APN "Vodafone"
#define POSITIONS_CONFIG_NET_DEFAULT_URL "https://yourserver.com/endpoint"
#define POSITIONS_CONFIG_NET_DEFAULT_EXPECTED_RESPONSE 201
#define POSITIONS_CONFIG_NET_DEFAULT_UNAVAILABLE_NETWORK_POSTPONE_THRESHOLD 5


struct networkConfig_t {
uint8_t saveThreshold; //sizeof = 1
uint16_t lastSavedEntry; //sizeof = 2
char apn[20]; //sizeof = 20
char url[50]; //sizeof = 50
}; //sizeof = 73

+ 0
- 13
src/Pins.h Dosyayı Görüntüle

@@ -1,13 +0,0 @@
#pragma once

#define SIM_RST 5
#define SIM_RX 6
#define SIM_TX 7
#define SIM_PWR 9
#define SIM_STATUS 8

#define I2C_PWR A0
#define SD_SS SS

#define SIM_RI 2
#define RTC_WAKE 3

+ 85
- 85
src/Rtc.cpp Dosyayı Görüntüle

@@ -1,86 +1,86 @@
#include "Debug.h"
#include "Rtc.h"
#include "Pins.h"
#include <Wire.h>
#include <uDS3231.h>
#define LOGGER_NAME "Rtc"
using namespace utils;
namespace rtc {
void setup() {
VERBOSE("setup");
hardware::i2c::powerOn();
RTC.control(DS3231_12H, DS3231_OFF); //24 hours clock
RTC.control(DS3231_A1_INT_ENABLE, DS3231_OFF); //Alarm 1 OFF
RTC.control(DS3231_INT_ENABLE, DS3231_ON); //INTCN ON
hardware::i2c::powerOff();
}
int16_t getTemperature() {
hardware::i2c::powerOn();
float temperature = RTC.readTempRegister();
hardware::i2c::powerOff();
return static_cast<int16_t>(temperature * 100);
}
bool isAccurate() {
hardware::i2c::powerOn();
bool accurate = RTC.status(DS3231_HALTED_FLAG) == DS3231_OFF;
hardware::i2c::powerOff();
return accurate;
}
timestamp_t getTime() {
tmElements_t time;
getTime(time);
return time::makeTimestamp(time);
}
void getTime(tmElements_t &time) {
hardware::i2c::powerOn();
RTC.readTime(time);
hardware::i2c::powerOff();
VERBOSE_FORMAT("getTime", "%d/%d/%d %d:%d:%d", tmYearToCalendar(time.Year), time.Month, time.Day, time.Hour, time.Minute, time.Second);
}
void setTime(const tmElements_t &time) {
VERBOSE_FORMAT("setTime", "%d/%d/%d %d:%d:%d", tmYearToCalendar(time.Year), time.Month, time.Day, time.Hour, time.Minute, time.Second);
hardware::i2c::powerOn();
RTC.writeTime(time);
RTC.control(DS3231_HALTED_FLAG, DS3231_OFF);
hardware::i2c::powerOff();
}
void setAlarm(uint16_t seconds) {
tmElements_t currentTime;
tmElements_t alarmTime;
getTime(currentTime);
time::breakTime(time::makeTimestamp(currentTime) + seconds, alarmTime);
setAlarm(alarmTime);
}
void setAlarm(const tmElements_t &time) {
hardware::i2c::powerOn();
RTC.writeAlarm1(DS3231_ALM_HMS, time);
RTC.control(DS3231_A1_FLAG, DS3231_OFF); //reset Alarm 1 flag
RTC.control(DS3231_A1_INT_ENABLE, DS3231_ON); //Alarm 1 ON
RTC.control(DS3231_INT_ENABLE, DS3231_ON); //INTCN ON
NOTICE_FORMAT("setAlarm", "Next alarm : %d:%d:%d", time.Hour, time.Minute, time.Second);
hardware::i2c::powerOff();
}
#include "Debug.h"
#include "Rtc.h"
#include "config/Pins.h"
#include <Wire.h>
#include <uDS3231.h>
#define LOGGER_NAME "Rtc"
using namespace utils;
namespace rtc {
void setup() {
VERBOSE("setup");
hardware::i2c::powerOn();
RTC.control(DS3231_12H, DS3231_OFF); //24 hours clock
RTC.control(DS3231_A1_INT_ENABLE, DS3231_OFF); //Alarm 1 OFF
RTC.control(DS3231_INT_ENABLE, DS3231_ON); //INTCN ON
hardware::i2c::powerOff();
}
int16_t getTemperature() {
hardware::i2c::powerOn();
float temperature = RTC.readTempRegister();
hardware::i2c::powerOff();
return static_cast<int16_t>(temperature * 100);
}
bool isAccurate() {
hardware::i2c::powerOn();
bool accurate = RTC.status(DS3231_HALTED_FLAG) == DS3231_OFF;
hardware::i2c::powerOff();
return accurate;
}
timestamp_t getTime() {
tmElements_t time;
getTime(time);
return time::makeTimestamp(time);
}
void getTime(tmElements_t &time) {
hardware::i2c::powerOn();
RTC.readTime(time);
hardware::i2c::powerOff();
VERBOSE_FORMAT("getTime", "%d/%d/%d %d:%d:%d", tmYearToCalendar(time.Year), time.Month, time.Day, time.Hour, time.Minute, time.Second);
}
void setTime(const tmElements_t &time) {
VERBOSE_FORMAT("setTime", "%d/%d/%d %d:%d:%d", tmYearToCalendar(time.Year), time.Month, time.Day, time.Hour, time.Minute, time.Second);
hardware::i2c::powerOn();
RTC.writeTime(time);
RTC.control(DS3231_HALTED_FLAG, DS3231_OFF);
hardware::i2c::powerOff();
}
void setAlarm(uint16_t seconds) {
tmElements_t currentTime;
tmElements_t alarmTime;
getTime(currentTime);
time::breakTime(time::makeTimestamp(currentTime) + seconds, alarmTime);
setAlarm(alarmTime);
}
void setAlarm(const tmElements_t &time) {
hardware::i2c::powerOn();
RTC.writeAlarm1(DS3231_ALM_HMS, time);
RTC.control(DS3231_A1_FLAG, DS3231_OFF); //reset Alarm 1 flag
RTC.control(DS3231_A1_INT_ENABLE, DS3231_ON); //Alarm 1 ON
RTC.control(DS3231_INT_ENABLE, DS3231_ON); //INTCN ON
NOTICE_FORMAT("setAlarm", "Next alarm : %d:%d:%d", time.Hour, time.Minute, time.Second);
hardware::i2c::powerOff();
}
}

+ 18
- 17
src/SdCard.cpp Dosyayı Görüntüle

@@ -1,18 +1,19 @@
#include "Config.h"

#if BACKUP_ENABLE_SDCARD
#include "SdCard.h"

namespace hardware {
namespace sdcard {

SdFat filesystem;
bool available = false;

void setup() {
available = filesystem.begin(SD_SS);
}

}
}
#include "Config.h"
#if BACKUP_ENABLE_SDCARD
#include "SdCard.h"
#include "config/Pins.h"
namespace hardware {
namespace sdcard {
SdFat filesystem;
bool available = false;
void setup() {
available = filesystem.begin(SD_SS);
}
}
}
#endif

+ 12
- 13
src/SdCard.h Dosyayı Görüntüle

@@ -1,14 +1,13 @@
#pragma once

#include <SdFat.h>
#include "Pins.h"

namespace hardware {
namespace sdcard {

extern SdFat filesystem;
extern bool available;

void setup();
}
#pragma once
#include <SdFat.h>
namespace hardware {
namespace sdcard {
extern SdFat filesystem;
extern bool available;
void setup();
}
}

+ 32
- 0
src/config/Alerts.h Dosyayı Görüntüle

@@ -0,0 +1,32 @@
#pragma once
/**
* Configure the values used for alerts triggering.
* Note that the battery level percentage are quite high,
* because the reading provided by the SIM808 module are
* not accurate and the device shuts itself off way before reaching 0%.
* The clearance level is also well above the first alert level, because
* the reading is so inaccurate that sometimes the battery can gain 5%
* between readings. Setting a clearance level much higher avoid
* clearing the levels and retriggering them the next time.
*/
#define CONFIG_DEFAULT_BATTERY_ALERT_LEVEL1 45 ///< Battery percentage at which to trigger the first low battery alert.
#define CONFIG_DEFAULT_BATTERY_ALERT_LEVEL2 38 ///< Battery percentage at which to trigger the final low battery alert.
#define CONFIG_DEFAULT_BATTERY_ALERT_CLEAR 60 ///< Battery percentage at which to clear all battery alerts.
#define CONFIG_DEFAULT_ACTIVE_ALERTS 0 ///< Default active alerts
#define CONFIG_DEFAULT_CONTACT_PHONE "+642568452" ///< Default phone number to send the alert SMS to.
/**
\def ALERTS_ON_SERIAL_IF_AVAILABLE
Display alerts on serial when connected rather than sending an SMS.
Useful for debugging purpose and avoid costs related to SMS sending.
*/
#define ALERTS_ON_SERIAL_IF_AVAILABLE 1
/**
\def ALERT_SUSPICIOUS_RTC_TEMPERATURE
Temperature at which to consider the RTC module as failling.
When the backup battery is dead or nearly dead, the reading
of the temperature fails and returns 0.
*/
#define ALERT_SUSPICIOUS_RTC_TEMPERATURE 0

+ 24
- 0
src/config/BackupNetwork.h Dosyayı Görüntüle

@@ -0,0 +1,24 @@
/**
* Configure how the positions are backuped with the network
*/
#pragma once
#define POSITIONS_CONFIG_NET_DEFAULT_SAVE_THRESHOLD 30 ///< Determines how many positions will be saved before a network backup is needed (only when not moving though).
#define POSITIONS_CONFIG_NET_DEFAULT_APN "Vodafone" ///< APN used for GPRS context
#define POSITIONS_CONFIG_NET_DEFAULT_URL "https://yourserver.com/endpoint" ///< URL to which positions data will be send through an HTTP POST request
#define POSITIONS_CONFIG_NET_DEFAULT_EXPECTED_RESPONSE 201 ///< Expected response code from the server that indicates that the positions has been successfully backuped.
/**
\def POSITIONS_CONFIG_NET_DEFAULT_UNAVAILABLE_NETWORK_POSTPONE_THRESHOLD
Determines how many times to deal with an unreliable network before postponing the backup.
In an area where cell reception isn't good, this avoid to try to backup the positions
every single time, which would rapidly consumes all the batty.
*/
#define POSITIONS_CONFIG_NET_DEFAULT_UNAVAILABLE_NETWORK_POSTPONE_THRESHOLD 5
struct networkConfig_t {
uint8_t saveThreshold; //sizeof = 1
uint16_t lastSavedEntry; //sizeof = 2
char apn[20]; //sizeof = 20
char url[50]; //sizeof = 50
}; //sizeof = 73

+ 1
- 0
src/config/BackupSd.h Dosyayı Görüntüle

@@ -0,0 +1 @@
#pragma once

+ 17
- 0
src/config/Gps.h Dosyayı Görüntüle

@@ -0,0 +1,17 @@
/**
* Configure how the system waits for the GPS signal.
*/
#pragma once
#define GPS_DEFAULT_INTERMEDIATE_TIMEOUT_MS 10000L ///< Time to sleeps between each GPS signal assessment.
#define GPS_DEFAULT_TOTAL_TIMEOUT_MS 80000L ///< Timeout after which to stop trying to get a GPS signal.
/**
\def GPS_DEFAULT_MISSED_POSITION_GAP_KM
Gap between the current and previous position above which to consider
that the tracker has moved. Even if stopped, this will trigger a whole
new "cycle" of positions acquisition, and will avoid missing positions
because while moving, the tracker woke up while stopped at a light traffic for instance.
*/
#define GPS_DEFAULT_MISSED_POSITION_GAP_KM 2

+ 28
- 0
src/config/Main.h Dosyayı Görüntüle

@@ -0,0 +1,28 @@
#pragma once
#include "System.h"
#include "Sleeps.h"
#include "Gps.h"
#include "Network.h"
#include "Alerts.h"
/**
\def BACKUP_ENABLE_SDCARD
Enable (1) or disable (0) the backup of positions using an sd card.
Note: This code has never been finished properly because of the lack of space
on the ATMega
*/
#define BACKUP_ENABLE_SDCARD 0
/**
\def BACKUP_ENABLE_NETWORK
Enable (1) or disable (0) the backup of positions using the network.
*/
#define BACKUP_ENABLE_NETWORK 1
#if BACKUP_ENABLE_SDCARD
#include "BackupSd.h"
#endif
#if BACKUP_ENABLE_NETWORK
#include "BackupNetwork.h"
#endif

+ 10
- 0
src/config/Network.h Dosyayı Görüntüle

@@ -0,0 +1,10 @@
/**
* Configure how the system waits for the network.
*/
#pragma onces
#define NETWORK_DEFAULT_NO_NETWORK_QUALITY_THRESHOLD 8 ///< Minimum signal quality to consider the cellphone reception as reliable.
#define NETWORK_DEFAULT_NO_NETWORK_TRIES 5 ///< Maximum tries before considering an unreliable cellphone reception as no reception at all.
#define NETWORK_DEFAULT_INTERMEDIATE_TIMEOUT_MS 10000L ///< Intermediate time to sleep between each cellphone reception assessment.
#define NETWORK_DEFAULT_TOTAL_TIMEOUT_MS 80000L ///< Timeout after which to stop trying to register to the network.

+ 16
- 0
src/config/Pins.h Dosyayı Görüntüle

@@ -0,0 +1,16 @@
/**
* Defines Arduino pins number connected to external systems.
*/
#pragma once
#define SIM_RST 5 ///< SIM808 RESET
#define SIM_RX 6 ///< SIM808 RXD
#define SIM_TX 7 ///< SIM808 TXD
#define SIM_PWR 9 ///< SIM808 PWRKEY
#define SIM_STATUS 8 ///< SIM808 STATUS
#define I2C_PWR A0 ///< Used to drive I2C power supply
#define SD_SS SS
#define SIM_RI 2 ///< Interrupt pin connected to SIM RI.
#define RTC_WAKE 3 ///< Interrupt pin connected to DS3231 !INT/SQW

+ 53
- 0
src/config/Sleeps.h Dosyayı Görüntüle

@@ -0,0 +1,53 @@
/**
* Controls how and when the device goes to sleep.
*/
#pragma once
#define SLEEP_TIMING_TIME(hours, minutes) hours * 60 + minutes
#define SLEEP_DEFAULT_TIME_SECONDS 1800 ///< Default sleep time
#define SLEEP_TIMING_MIN_MOVING_VELOCITY 5 ///< Speed under which to consider the tracker as not moving
#define SLEEP_DEFAULT_PAUSING_TIME_SECONDS 270 ///< Sleep time to use when not moving
#define SLEEP_DEFAULT_STOPPED_THRESHOLD 5 ///< Number of successive positions acquired as not moving before considering the tracker as stopped
#define SLEEP_TIMING_MIN SLEEP_TIMING_TIME(0, 0)
#define SLEEP_TIMING_MAX SLEEP_TIMING_TIME(23, 59)
/**
* Represents a single entry in a larger parametization
* of how long the tracker will go the sleep based on its speed
* and the time of the day.
*/
struct sleepTimings_t {
uint8_t speed; ///< Minimum speed (NOT maximum, the logic is reversed for code efficiency)
uint16_t timeMin; ///< Minimum time of the day (UTC)
uint16_t timeMax; ///< Maximum time of the day (UTC)
uint16_t seconds; ///< Sleep duration in seconds
};
namespace config {
/**
* Describes for how long the tracker should sleep before the next position
* acquisition based on the sleepTimings_t structure
*/
static const sleepTimings_t defaultSleepTimings[] PROGMEM = {
// Sleep timings when not moving
{ 0, SLEEP_TIMING_TIME(16, 00), SLEEP_TIMING_TIME(19, 59), 3600 }, ///< 1 hour between 16:00 and 20:00 UTC (04:00 to 08:00 UTC+12)
{ 0, SLEEP_TIMING_TIME(20, 00), SLEEP_TIMING_MAX, SLEEP_DEFAULT_TIME_SECONDS }, ///< default (30 minutes) between 20:00 and 00:00 UTC (08:00 to 12:00 UTC+12)
{ 0, SLEEP_TIMING_MIN, SLEEP_TIMING_TIME(8, 29), SLEEP_DEFAULT_TIME_SECONDS }, ///< default (30 minutes) between 00:00 and 8:30 UTC (12:00 to 20:30 UTC+12)
{ 0, SLEEP_TIMING_TIME(8, 30), SLEEP_TIMING_TIME(15, 59), 10800 }, ///< 3 hours between 20:30 and 16:00 UTC (20:30 to 04:00 UTC+12)
// Sleep timings while moving
{ SLEEP_TIMING_MIN_MOVING_VELOCITY, SLEEP_TIMING_MIN, SLEEP_TIMING_MAX, 540 }, ///< 540 seconds when speed > SLEEP_TIMING_MIN_MOVING_VELOCITY (5km/h)
{ 10, SLEEP_TIMING_MIN, SLEEP_TIMING_MAX, 270 }, ///< 270 seconds when speed > 10 km/h
{ 20, SLEEP_TIMING_MIN, SLEEP_TIMING_MAX, 225 }, ///< 225 seconds when speed > 20 km/h
{ 30, SLEEP_TIMING_MIN, SLEEP_TIMING_MAX, 240 }, ///< 240 seconds when speed > 30 km/h
{ 45, SLEEP_TIMING_MIN, SLEEP_TIMING_MAX, 280 }, ///< 280 seconds when speed > 45 km/h
{ 65, SLEEP_TIMING_MIN, SLEEP_TIMING_MAX, 276 }, ///< 276 seconds when speed > 65 km/h
{ 85, SLEEP_TIMING_MIN, SLEEP_TIMING_MAX, 225 } ///< 2225 seconds when speed > 85 km/h
};
}

+ 37
- 0
src/config/System.h Dosyayı Görüntüle

@@ -0,0 +1,37 @@
#pragma once
/**
\def SIM808_BAUDRATE
Control the baudrate use to communicate with the SIM808 module
*/
#define SIM808_BAUDRATE 4800
/**
\def CONFIG_ADDR
Address of the config block in the I2C EEPROM chip.
*/
#define CONFIG_ADDR 0
/**
\def CONFIG_RESERVED_SIZE
Reserved size for the config block in the I2C EEPROM chip.
*/
#define CONFIG_RESERVED_SIZE 128
/**
\def CONFIG_SEED
Seed use to detect invalid or outdate configuration data.
Changing this value will reset the configuration block.
*/
#define CONFIG_SEED 14
/**
\def VERSION
Version string, only used for indicative purpose
*/
#define VERSION "1.20"
/**
\def MENU_TIMEOUT
When hooked up on Serial port, determine how much milliseconds
to wait for a user input before proceeding.
*/
#define MENU_TIMEOUT 20000

Yükleniyor…
İptal
Kaydet