bobbycar/controller_teensy/include/logging.h

385 lines
12 KiB
C

#ifndef _LOGGING_H_
#define _LOGGING_H_
// SD Card Logging
#include <SPI.h>
#include <SD.h> //Format sd cart with FAT or FAT16. FAT32 for >1GB Cards on Teensy4.1
//#define SDCHIPSELECT 14
boolean datalogging=true;
String datalogging_filename="UNKNOWN.txt";
bool serialCommandEcho_Enabled=true;
bool initLogging();
void loggingLoop(unsigned long loopmillis,ESCSerialComm& escFront, ESCSerialComm& escRear);
void writeLogComment(unsigned long time, String msg);
void printFileListing();
void printDirectory(File dir, int numTabs,String parent);
void printFile(String filename);
void removeFile(String filename);
void serialCommandLoop();
bool initLogging() {
Serial.print("Initializing SD card...");
// see if the card is present and can be initialized:
if (!SD.begin(BUILTIN_SDCARD)) {
Serial.println("Card failed, or not present");
display.println(F("SD Init Fail!")); display.display();
datalogging=false; //disable logging
delay(1000);
return false;
}else{
Serial.println("Card initialized.");
display.print(F("LOG=")); display.display();
if (datalogging){
int filenumber=0;
char buffer[6];
sprintf(buffer, "%04d", filenumber);
datalogging_filename="LOG_"+String(buffer)+".TXT";
while(SD.exists(datalogging_filename.c_str()) && filenumber<10000) {
//Serial.print(datalogging_filename); Serial.println(" exists");
filenumber++;
sprintf(buffer, "%04d", filenumber);
datalogging_filename="LOG_"+String(buffer)+".TXT";
}
Serial.print(datalogging_filename); Serial.println(" is free");
display.print(datalogging_filename); display.println(); display.display();
}
}
return true;
}
void loggingLoop(unsigned long loopmillis,ESCSerialComm& escFront, ESCSerialComm& escRear) {
static unsigned long last_datalogging_write=0;
static boolean logging_headerWritten=false;
if (datalogging) {
#define LOGGINGINTERVAL 100
if (loopmillis-last_datalogging_write>LOGGINGINTERVAL)
{
last_datalogging_write=loopmillis;
File dataFile = SD.open(datalogging_filename.c_str(), FILE_WRITE);
if (dataFile) { // if the file is available, write to it
if (!logging_headerWritten) {
dataFile.print("time,cmd_FrontL,cmd_FrontR,cmd_RearL,cmd_RearR,");
dataFile.print("current_FrontL,current_FrontR,current_RearL,current_RearR,");
dataFile.print("rpm_FrontL,rpm_FrontR,rpm_RearL,rpm_RearR,");
dataFile.print("temp_Front,temp_Rear,vbat_Front,vbat_Rear,");
dataFile.print("currentAll,throttle,brake,speed,trip_Front,trip_Rear,trip,currentConsumed_Front,currentConsumed_Rear,currentConsumed,watthoursConsumed,");
dataFile.println("temp_ESCFront,temp_ESCRear,temp_Air,looptime_duration");
dataFile.print("#TIMESTAMP:"); dataFile.println(now());
logging_headerWritten=true;
}
dataFile.print(loopmillis/1000.0,3); dataFile.print(",");
dataFile.print(escFront.getCmdL()); dataFile.print(",");
dataFile.print(escFront.getCmdR()); dataFile.print(",");
dataFile.print(escRear.getCmdL()); dataFile.print(",");
dataFile.print(escRear.getCmdR()); dataFile.print(",");
dataFile.print(escFront.getFiltered_curL(),3); dataFile.print(",");
dataFile.print(escFront.getFiltered_curR(),3); dataFile.print(",");
dataFile.print(escRear.getFiltered_curL(),3); dataFile.print(",");
dataFile.print(escRear.getFiltered_curR(),3); dataFile.print(",");
dataFile.print(escFront.getFeedback_speedL_meas()); dataFile.print(","); //+ //Todo: check if speed for R wheels needs to be negated
dataFile.print(escFront.getFeedback_speedR_meas()); dataFile.print(","); //-
dataFile.print(escRear.getFeedback_speedL_meas()); dataFile.print(","); //+
dataFile.print(escRear.getFeedback_speedR_meas()); dataFile.print(","); //-
dataFile.print(escFront.getFeedback_boardTemp()); dataFile.print(",");
dataFile.print(escRear.getFeedback_boardTemp()); dataFile.print(",");
dataFile.print(escFront.getFeedback_batVoltage()); dataFile.print(",");
dataFile.print(escRear.getFeedback_batVoltage()); dataFile.print(",");
dataFile.print(filtered_currentAll,3); dataFile.print(",");
dataFile.print(throttle_pos); dataFile.print(",");
dataFile.print(brake_pos); dataFile.print(",");
dataFile.print((escFront.getMeanSpeed()+escRear.getMeanSpeed())/2.0); dataFile.print(",");
dataFile.print(escFront.getTrip()); dataFile.print(",");
dataFile.print(escRear.getTrip()); dataFile.print(",");
dataFile.print(trip); dataFile.print(",");
dataFile.print(escFront.getCurrentConsumed(),3); dataFile.print(",");
dataFile.print(escRear.getCurrentConsumed(),3); dataFile.print(",");
dataFile.print(currentConsumed,3); dataFile.print(",");
dataFile.print(watthoursConsumed,3); dataFile.print(",");
dataFile.print(temp_ESCFront,2); dataFile.print(",");
dataFile.print(temp_ESCRear,2); dataFile.print(",");
dataFile.print(temp_Air,2); dataFile.print(",");
dataFile.print(looptime_duration); //dataFile.print(",");
looptime_duration=0; //reset
dataFile.println("");
dataFile.close();
}else{ //dataFile not available
error_sdfile_unavailable=true;
}
}
}
}
void writeLogComment(unsigned long time, String msg) {
//SerialRef.print("#"); SerialRef.print(time/1000.0,3); SerialRef.print(","); SerialRef.print(msg); SerialRef.println();
if (datalogging) {
File dataFile = SD.open(datalogging_filename.c_str(), FILE_WRITE);
if (dataFile) { // if the file is available, write to it
dataFile.print("#");
dataFile.print(time/1000.0,3);
dataFile.print(",");
dataFile.print(msg);
dataFile.println();
dataFile.close();
}
}
}
String getLogFilename() {
return datalogging_filename;
}
bool loadTripSD()
{
//stats.txt containt lines with driven distance or consume current.
//the lowest line is the latest data
//data is usually written rather slowly
File myFile = SD.open("stats.txt", FILE_WRITE);
if (myFile) {
myFile.print("ini=");
myFile.println(now());
myFile.flush();
delay(100);
myFile.close();
Serial.println("TripSD: time written");
}else{
return false;
}
myFile = SD.open("stats.txt");
if (myFile) {
while (myFile.available()) {
String line=myFile.readStringUntil('\n');
Serial.print("TripSD Read Line:");
Serial.println(line);
if (line.substring(0,4)=="trp="){
overallTrip=(line.substring(4)).toFloat();
}else if (line.substring(0,4)=="occ="){
overallCurrentConsumed=(line.substring(4)).toFloat();
}else if (line.substring(0,4)=="owh="){
overallWatthoursConsumed=(line.substring(4)).toFloat();
}else if (line.substring(0,4)=="vlt="){
lastTripVoltage=(line.substring(4)).toFloat();
}
}
Serial.print("TripSD trip:");
Serial.println(overallTrip);
display.print(F("TripSD=")); display.println(overallTrip);
Serial.print("TripSD current:");
Serial.println(overallCurrentConsumed);
Serial.print("TripSD watthours:");
Serial.println(overallWatthoursConsumed);
display.print(F("Cur. SD=")); display.println(overallCurrentConsumed); display.display();
Serial.print("TripSD voltage:");
Serial.println(lastTripVoltage);
display.print(F("Volt. SD=")); display.println(lastTripVoltage); display.display();
myFile.flush();
delay(10);
myFile.close();
}else{
return false;
}
return true;
}
void writeTrip(unsigned long loopmillis,ESCSerialComm& escFront, ESCSerialComm& escRear) {
if (datalogging) {
File myFile = SD.open("stats.txt", FILE_WRITE);
if (myFile) {
myFile.print("trp=");
myFile.println(overallTrip);
myFile.print("occ=");
myFile.println(overallCurrentConsumed);
myFile.print("owh=");
myFile.println(overallWatthoursConsumed);
myFile.print("vlt=");
float _voltage=(escFront.getFeedback_batVoltage()+escRear.getFeedback_batVoltage())/2.0;
myFile.println(_voltage,2);
myFile.close();
}
}
}
void resetTrip() {
if (datalogging) {
File myFile = SD.open("stats.txt", FILE_WRITE);
if (myFile) {
myFile.print("trp=");
myFile.println(0);
myFile.print("occ=");
myFile.println(0);
myFile.print("owh=");
myFile.println(0);
myFile.print("vlt=");
myFile.println(0);
myFile.flush();
delay(10);
myFile.close();
}
}
}
void serialCommandLoop() {
#define MAX_MESSAGE_LENGTH 80
uint8_t timeoutcounter=MAX_MESSAGE_LENGTH;
while (Serial.available() > 0 && timeoutcounter>0)
{
timeoutcounter--;
static char message[MAX_MESSAGE_LENGTH];
static unsigned int message_pos = 0;
char inByte = Serial.read();
if (inByte == '\r') {
break; //ignore CR
}
if ( inByte != '\n' && (message_pos < MAX_MESSAGE_LENGTH - 1) )
{
message[message_pos] = inByte;
message_pos++;
}
else
{
message[message_pos] = '\0';
String smessage=String(message);
if(smessage.equals("echo off")) {
serialCommandEcho_Enabled=false;
}else if(smessage.equals("echo on")) {
serialCommandEcho_Enabled=true;
}
if (serialCommandEcho_Enabled) { //Echo Command
Serial.print("$"); Serial.println(message);
}
//Handle Commands
if(smessage.equals("test")) {
Serial.println("OK");
}else if(smessage.equals("ls")) {
printFileListing();
}else if(smessage.startsWith("cat")) {
printFile(smessage.substring(4));
}else if(smessage.startsWith("rm")) {
removeFile(smessage.substring(3));
}else if(smessage.equals("log off")) {
datalogging=false;
Serial.print("Log disabled: "); Serial.println(datalogging_filename);
}else if(smessage.equals("log on")) {
datalogging=true;
Serial.print("Log enabled: "); Serial.println(datalogging_filename);
}
message_pos = 0;
}
}
}
void printFileListing() {
File root;
root = SD.open("/");
printDirectory(root, 0,"");
}
void printDirectory(File dir, int numTabs,String parent) {
bool printSize=false;
bool printFullDirectoryNames=true;
while (true) {
File entry = dir.openNextFile();
if (! entry) {
// no more files
break;
}
if (!printFullDirectoryNames) {
for (uint8_t i = 0; i < numTabs; i++) {
Serial.print('\t');
}
}
if (!entry.isDirectory() || !printFullDirectoryNames) {
Serial.print(parent+entry.name());
}
if (entry.isDirectory()) {
if (!printFullDirectoryNames) {
Serial.println("/");
}
printDirectory(entry, numTabs + 1,parent+entry.name()+"/");
} else {
if (printSize) {
// files have sizes, directories do not
Serial.print("\t\t");
Serial.print(entry.size(), DEC);
}
Serial.println();
}
entry.close();
}
}
void printFile(String filename) {
File dataFile = SD.open(filename.c_str(), FILE_READ);
// if the file is available, write to it:
if (dataFile) {
while (dataFile.available()) {
Serial.write(dataFile.read());
}
dataFile.close();
}
// if the file isn't open, pop up an error:
else {
Serial.print("error opening "); Serial.println(filename);
}
}
void removeFile(String filename) {
SD.remove(filename.c_str());
if (SD.exists(filename.c_str())) {
Serial.println("File still exists");
} else {
Serial.println("OK");
}
}
#endif