Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Enhance and fix data logging #147

Open
wants to merge 16 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 3 additions & 2 deletions firmware_v5/telelogger/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -16,14 +16,15 @@ Data Transmissions
------------------

Data transmission over UDP and HTTP protocols are implemented with following hardware.

* WiFi (ESP32 built-in)
* WiFi Mesh (ESP-MDF for ESP32)
* 3G WCDMA (SIM5360)
* 4G LTE CAT-4 (SIM7600)
* 4G LTE CAT-M1 (SIM7070)

UDP mode implements a client for [Freematics Hub](https://freematics.com/hub/). HTTP mode implements a client for [Traccar](https://www.traccar.org) under [OsmAnd](https://www.traccar.org/osmand/) protocol.
There two ways of sending data:
1. UDP mode implements a `freematics` protocol client for [Freematics Hub](https://freematics.com/hub/) or [Traccar](https://www.traccar.org) (sends more data, [protocol's API](https://freematics.com/pages/hub/api/), uses 5170 port).
2. HTTP/HTTPS mode implements a `osmand` protocol client for Traccar (sends only location data, [protocol's API](https://www.traccar.org/osmand/), uses 5055 port)

Data Storage
------------
Expand Down
3 changes: 2 additions & 1 deletion firmware_v5/telelogger/config.h
Original file line number Diff line number Diff line change
Expand Up @@ -132,7 +132,8 @@
// motion threshold for waking up
#define MOTION_THRESHOLD 0.4f /* moving vehicle motion threshold in G */
// engine jumpstart voltage
#define JUMPSTART_VOLTAGE 14 /* V */
#define JUMPSTART_VOLTAGE 13.5f /* V */
#define LOW_BATTERY_VOLTAGE 11.6f /* V */

/**************************************
* Additional features
Expand Down
8 changes: 7 additions & 1 deletion firmware_v5/telelogger/dashboard/dashboard.js
100644 → 100755
Original file line number Diff line number Diff line change
Expand Up @@ -79,8 +79,14 @@ function processInput(data)
if (ret = checkData(con, "HTTPD:")) {
document.getElementById("wifi").innerHTML = ret.indexOf("NO") >= 0 ? imgCross : imgTick;
}
if (ret = checkData(con, "Joining")) {
document.getElementById("wifi").innerText = ret;
}
if (ret = checkData(con, "WiFi IP:")) {
document.getElementById("wifi").innerHTML = imgTick + " IP:" + ret;
document.getElementById("wifi").innerHTML += " " + imgTick + " IP:" + ret;
}
if (ret = checkData(con, "No WiFi")) {
document.getElementById("wifi").innerHTML = imgCross;
}
if (ret = checkData(con, "IMEI:")) {
document.getElementById("sim_card").innerHTML = imgTick;
Expand Down
21 changes: 16 additions & 5 deletions firmware_v5/telelogger/teleclient.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -160,11 +160,14 @@ bool TeleClientUDP::notify(byte event, const char* payload)
netbuf.init(128);
netbuf.header(devid);
netbuf.dispatch(buf, sprintf(buf, "EV=%X", (unsigned int)event));
// ticker time in milliseconds
netbuf.dispatch(buf, sprintf(buf, "TS=%lu", millis()));
// local device time in seconds
struct timeval timeval1;
gettimeofday(&timeval1, NULL);
uint32_t timestampSec = timeval1.tv_sec;
netbuf.dispatch(buf, sprintf(buf, "TM=%lu", timestampSec));
netbuf.dispatch(buf, sprintf(buf, "ID=%s", devid));
if (rssi) {
netbuf.dispatch(buf, sprintf(buf, "SSI=%d", (int)rssi));
}
if (vin[0]) {
netbuf.dispatch(buf, sprintf(buf, "VIN=%s", vin));
}
Expand Down Expand Up @@ -209,10 +212,18 @@ bool TeleClientUDP::notify(byte event, const char* payload)
if (event == EVENT_LOGIN) {
// extract info from server response
char *p = strstr(data, "TM=");
unsigned long t_seconds = 0;
unsigned long t_microseconds = 0;
if (p) {
t_seconds = atol(p + 3);
}
p = strstr(data, "TN=");
if (p) {
t_microseconds = atol(p + 3);
}
if (t_seconds > 0) {
// set local time from server
unsigned long tm = atol(p + 3);
struct timeval tv = { .tv_sec = (time_t)tm, .tv_usec = 0 };
struct timeval tv = { .tv_sec = (time_t)t_seconds, .tv_usec = (time_t)t_microseconds };
settimeofday(&tv, NULL);
}
p = strstr(data, "SN=");
Expand Down
3 changes: 2 additions & 1 deletion firmware_v5/telelogger/teleclient.h
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
#define EVENT_COMMAND 5
#define EVENT_ACK 6
#define EVENT_PING 7
#define EVENT_LOW_BATTERY 8

#define BUFFER_STATE_EMPTY 0
#define BUFFER_STATE_FILLING 1
Expand Down Expand Up @@ -183,4 +184,4 @@ class TeleClientHTTP : public TeleClient
#endif
private:
bool started = false;
};
};
2 changes: 1 addition & 1 deletion firmware_v5/telelogger/telelogger.h
Original file line number Diff line number Diff line change
Expand Up @@ -102,7 +102,7 @@ class CStorageRAM: public CStorage {
void tailer()
{
//if (m_cache[m_cacheBytes - 1] == ',') m_cacheBytes--;
m_cacheBytes += sprintf(m_cache + m_cacheBytes, "*%X", (unsigned int)checksum(m_cache, m_cacheBytes));
m_cacheBytes += sprintf(m_cache + m_cacheBytes, "*%02X", (unsigned int)checksum(m_cache, m_cacheBytes));
}
void untailer()
{
Expand Down
105 changes: 75 additions & 30 deletions firmware_v5/telelogger/telelogger.ino
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,7 @@ PID_POLLING_INFO obdData[]= {
{PID_RPM, 1},
{PID_THROTTLE, 1},
{PID_ENGINE_LOAD, 1},
{PID_FUEL_LEVEL, 1},
{PID_FUEL_PRESSURE, 2},
{PID_TIMING_ADVANCE, 2},
{PID_COOLANT_TEMP, 3},
Expand All @@ -74,6 +75,7 @@ float deviceTemp = 0;
int16_t rssi = 0;
char vin[18] = {0};
uint16_t dtc[6] = {0};
// value 1440 means, that voltage is 14.4V
int16_t batteryVoltage = 0;
GPS_DATA* gd = 0;

Expand Down Expand Up @@ -181,6 +183,20 @@ void processExtInputs(CBuffer* buffer)
}
#endif

CStorageRAM latestLocationStore;

void prepareData(CStorageRAM* store, CBuffer* buffer) {
// here we use CStorageRAM to serialize data correctly
store->purge();
#if SERVER_PROTOCOL == PROTOCOL_UDP
store->header(devid);
#endif

store->timestamp(buffer->timestamp);
buffer->serialize(*store);
store->tailer();
}

/*******************************************************************************
HTTP API
*******************************************************************************/
Expand Down Expand Up @@ -397,10 +413,8 @@ void processMEMS(CBuffer* buffer)
value[2] = ori.roll;
buffer->add(PID_ORIENTATION, value);
#endif
if (temp != deviceTemp) {
deviceTemp = temp;
buffer->add(PID_DEVICE_TEMP, (int)temp);
}
deviceTemp = temp;
buffer->add(PID_MEMS_TEMP, (int) (temp * 10));
#if 0
// calculate motion
float motion = 0;
Expand Down Expand Up @@ -749,7 +763,7 @@ bool waitMotion(long timeout)
/*******************************************************************************
Collecting and processing data
*******************************************************************************/
void process()
void process(bool isInStandby)
{
uint32_t startTime = millis();

Expand Down Expand Up @@ -787,24 +801,51 @@ void process()
}
if (batteryVoltage) {
buffer->add(PID_BATTERY_VOLTAGE, (int)batteryVoltage);
if (batteryVoltage > JUMPSTART_VOLTAGE * 100) {
buffer->add(PID_IGNITION, (int) 1);
} else {
buffer->add(PID_IGNITION, (int) 0);
}
}
#endif

#if LOG_EXT_SENSORS
processExtInputs(buffer);
#endif

#if NET_DEVICE >= SIM800
rssi = teleClient.net.getSignal();
if (rssi) {
buffer->add(PID_CELL_RSSI, rssi);
}
#endif

#if NET_DEVICE == NET_SIM7600
if (teleClient.net.cellTower->mcc != 0) {
buffer->add(PID_CELL_MCC, teleClient.net.cellTower->mcc);
buffer->add(PID_CELL_MNC, teleClient.net.cellTower->mnc);
buffer->add(PID_CELL_LAC, (uint32_t) teleClient.net.cellTower->lac);
buffer->add(PID_CELL_CID, (uint32_t) teleClient.net.cellTower->cellid);
}
#endif

#if ENABLE_MEMS
processMEMS(buffer);
#endif

processGPS(buffer);
bool receivedGPS = processGPS(buffer);

float cpuTemp = readChipTemperature();
buffer->add(PID_CPU_TEMP, (int) (cpuTemp * 10));
if (!state.check(STATE_MEMS_READY)) {
deviceTemp = readChipTemperature();
buffer->add(PID_DEVICE_TEMP, deviceTemp);
deviceTemp = cpuTemp;
}

// format device time
struct timeval timeval1;
gettimeofday(&timeval1, NULL);
buffer->add(PID_DEVICE_TIME_SEC, (uint32_t) timeval1.tv_sec);
buffer->add(PID_DEVICE_TIME_MCS, (uint32_t) timeval1.tv_usec);
buffer->timestamp = millis();
buffer->state = BUFFER_STATE_FILLED;

Expand All @@ -814,9 +855,10 @@ void process()
lastStatsTime = startTime;
}

prepareData(&latestLocationStore, buffer);
#if STORAGE != STORAGE_NONE
if (state.check(STATE_STORAGE_READY)) {
buffer->serialize(logger);
logger.dispatch(latestLocationStore.buffer(), latestLocationStore.length());
uint16_t sizeKB = (uint16_t)(logger.size() >> 10);
if (sizeKB != lastSizeKB) {
logger.flush();
Expand All @@ -828,6 +870,7 @@ void process()
}
#endif

if (!isInStandby) {
const int dataIntervals[] = DATA_INTERVAL_TABLE;
#if ENABLE_OBD || ENABLE_MEMS
// motion adaptive data interval control
Expand All @@ -842,7 +885,7 @@ void process()
}
}
if (stationary) {
// stationery timeout
// stationary timeout
Serial.print("Stationary for ");
Serial.print(motionless);
Serial.println(" secs");
Expand All @@ -855,7 +898,7 @@ void process()
#endif
long t = dataInterval - (millis() - startTime);
if (t > 0 && t < dataInterval) delay(t);
}
}}

bool initNetwork()
{
Expand All @@ -872,7 +915,7 @@ bool initNetwork()
String ip = teleClient.net.getIP();
if (ip.length()) {
state.set(STATE_NET_CONNECTED);
Serial.print("IP:");
Serial.print("WiFi IP:");
Serial.println(ip);
#if ENABLE_OLED
oled.println(ip);
Expand Down Expand Up @@ -1006,8 +1049,6 @@ void telemetry(void* inst)
delay(1000);
} while (state.check(STATE_STANDBY) && millis() - t < 1000L * PING_BACK_INTERVAL);
if (state.check(STATE_STANDBY)) {
// start ping
#if 0
#if GNSS == GNSS_EXTERNAL || GNSS == GNSS_INTERNAL
#if GNSS == GNSS_EXTERNAL
if (sys.gpsBegin())
Expand All @@ -1016,18 +1057,28 @@ void telemetry(void* inst)
#endif
{
state.set(STATE_GPS_READY);
for (uint32_t t = millis(); millis() - t < 60000; ) {
if (sys.gpsGetData(&gd)) {
break;
}
}
}
#endif
#endif

process(true);

// start ping
if (initNetwork()) {
Serial.print("Ping...");
bool success = teleClient.ping();
Serial.println(success ? "OK" : "NO");

Serial.print("Data upload...");
bool successData = teleClient.transmit(latestLocationStore.buffer(), latestLocationStore.length());
Serial.println(successData ? "OK" : "NO");
#if ENABLE_OBD
float bV = obd.getVoltage();
if (bV < LOW_BATTERY_VOLTAGE) {
if (teleClient.notify(EVENT_LOW_BATTERY, "")) {
Serial.println("EVENT_LOW_BATTERY sent");
}
}
#endif
}
teleClient.shutdown();
state.clear(STATE_NET_READY | STATE_NET_CONNECTED);
Expand Down Expand Up @@ -1056,17 +1107,12 @@ void telemetry(void* inst)
}

buffer->state = BUFFER_STATE_LOCKED;
#if SERVER_PROTOCOL == PROTOCOL_UDP
store.header(devid);
#endif
store.timestamp(buffer->timestamp);
buffer->serialize(store);
prepareData(&store, buffer);
buffer->purge();
store.tailer();
//Serial.println(store.buffer());

// start transmission
if (ledMode == 0) digitalWrite(PIN_LED, HIGH);

if (teleClient.transmit(store.buffer(), store.length())) {
// successfully sent
connErrors = 0;
Expand All @@ -1078,8 +1124,6 @@ void telemetry(void* inst)
}
if (ledMode == 0) digitalWrite(PIN_LED, LOW);

store.purge();

teleClient.inbound();
if (syncInterval > 10000 && millis() - teleClient.lastSyncTime > syncInterval) {
Serial.println("Instable connection");
Expand Down Expand Up @@ -1355,6 +1399,7 @@ void setup()
Serial.println("HTTPD:NO");
}
#endif
latestLocationStore.init(SERIALIZE_BUFFER_SIZE);

#if ENABLE_BLE
// init BLE
Expand Down Expand Up @@ -1382,7 +1427,7 @@ void loop()
}

// collect and log data
process();
process(false);

// check serial input for command
while (Serial.available()) {
Expand Down
17 changes: 15 additions & 2 deletions libraries/FreematicsPlus/FreematicsBase.h
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,11 @@

#include <Arduino.h>

// time values
#define PID_TICKER 0x0
#define PID_DEVICE_TIME_SEC 0x1
#define PID_DEVICE_TIME_MCS 0x2

// non-OBD/custom PIDs (no mode number)
#define PID_GPS_LATITUDE 0xA
#define PID_GPS_LONGITUDE 0xB
Expand All @@ -23,17 +28,25 @@
#define PID_ACC 0x20
#define PID_GYRO 0x21
#define PID_COMPASS 0x22
#define PID_MEMS_TEMP 0x23
#define PID_BATTERY_VOLTAGE 0x24
#define PID_ORIENTATION 0x25

// cell tower info
#define PID_CELL_RSSI 0x40 // dBm
#define PID_CELL_MCC 0x41
#define PID_CELL_MNC 0x42
#define PID_CELL_LAC 0x43
#define PID_CELL_CID 0x44

// custom PIDs for calculated data
#define PID_TRIP_DISTANCE 0x30
#define PID_DATA_SIZE 0x80
#define PID_CSQ 0x81
#define PID_DEVICE_TEMP 0x82
#define PID_CPU_TEMP 0x82
#define PID_DEVICE_HALL 0x83
#define PID_EXT_SENSOR1 0x90
#define PID_EXT_SENSOR2 0x91
#define PID_IGNITION 0x92

typedef struct {
float pitch;
Expand Down
Loading