refactor temperature sensor variable
This commit is contained in:
parent
8a3fdaa574
commit
2e557af21f
|
@ -18,6 +18,7 @@ Adafruit_SSD1306 display(SCREEN_WIDTH, SCREEN_HEIGHT, &Wire, OLED_RESET);
|
||||||
uint8_t standingDisplayScreen=0;
|
uint8_t standingDisplayScreen=0;
|
||||||
#define NUM_STANDINGDISPLAYSCREEN 3
|
#define NUM_STANDINGDISPLAYSCREEN 3
|
||||||
|
|
||||||
|
#define DISPLAYSTANDSTILLTIME 5000
|
||||||
|
|
||||||
bool display_init();
|
bool display_init();
|
||||||
void display_update(ESCSerialComm& escFront, ESCSerialComm& escRear);
|
void display_update(ESCSerialComm& escFront, ESCSerialComm& escRear);
|
||||||
|
@ -86,7 +87,7 @@ void display_update(ESCSerialComm& escFront, ESCSerialComm& escRear){
|
||||||
//Normal Display Routines here
|
//Normal Display Routines here
|
||||||
|
|
||||||
if (armed) {
|
if (armed) {
|
||||||
if (loopmillis-last_notidle>5000) {
|
if (loopmillis-last_notidle>DISPLAYSTANDSTILLTIME) {
|
||||||
display_standingDisplay(escFront,escRear);
|
display_standingDisplay(escFront,escRear);
|
||||||
}else{
|
}else{
|
||||||
display_drivingDisplay(escFront,escRear);
|
display_drivingDisplay(escFront,escRear);
|
||||||
|
@ -256,8 +257,8 @@ void display_standingDisplay(ESCSerialComm& escFront, ESCSerialComm& escRear) {
|
||||||
//Row 2
|
//Row 2
|
||||||
//display.print(F("Temp:")); display.print(escFront.getFeedback_boardTemp());
|
//display.print(F("Temp:")); display.print(escFront.getFeedback_boardTemp());
|
||||||
//display.print(F("/")); display.print(escRear.getFeedback_boardTemp());
|
//display.print(F("/")); display.print(escRear.getFeedback_boardTemp());
|
||||||
display.print(F("T:")); display.print(temp_ESCFront,0);
|
display.print(F("T:")); display.print(temp_Front,0);
|
||||||
display.print(F("/")); display.print(temp_ESCRear,0);
|
display.print(F("/")); display.print(temp_Rear,0);
|
||||||
display.print(F("/")); display.print(temp_Air,0);
|
display.print(F("/")); display.print(temp_Air,0);
|
||||||
display.print(" C");
|
display.print(" C");
|
||||||
display.println();
|
display.println();
|
||||||
|
|
|
@ -13,7 +13,10 @@ String datalogging_filename="UNKNOWN.txt";
|
||||||
|
|
||||||
uint16_t chunksize=128; //for bulk data transmission
|
uint16_t chunksize=128; //for bulk data transmission
|
||||||
|
|
||||||
#define LOGGINGINTERVAL 100
|
#define LOGGINGINTERVAL 100 //logging interval when driving
|
||||||
|
#define LOGGINGSTANDSTILLTIME 30000 //after which time of standstill logging interval should change
|
||||||
|
#define LOGGINGINTERVALSTANDSTILL 500 //logging interval when standing still
|
||||||
|
#define LOGGINGINTERVALDISARMED 1000 //logging interval when disarmed
|
||||||
|
|
||||||
bool serialCommandEcho_Enabled=true;
|
bool serialCommandEcho_Enabled=true;
|
||||||
|
|
||||||
|
@ -81,7 +84,17 @@ void loggingLoop(unsigned long loopmillis,ESCSerialComm& escFront, ESCSerialComm
|
||||||
static unsigned long last_datalogging_write=0;
|
static unsigned long last_datalogging_write=0;
|
||||||
static boolean logging_headerWritten=false;
|
static boolean logging_headerWritten=false;
|
||||||
|
|
||||||
if (loopmillis-last_datalogging_write>LOGGINGINTERVAL)
|
unsigned long logginginterval=LOGGINGINTERVAL;
|
||||||
|
if (armed) { //Change Logginginterval when less is happening
|
||||||
|
if (loopmillis-last_notidle>LOGGINGSTANDSTILLTIME) {
|
||||||
|
logginginterval=LOGGINGINTERVALSTANDSTILL;
|
||||||
|
}
|
||||||
|
}else{ //disamred
|
||||||
|
logginginterval=LOGGINGINTERVALDISARMED;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
if (loopmillis-last_datalogging_write>logginginterval)
|
||||||
{
|
{
|
||||||
last_datalogging_write=loopmillis;
|
last_datalogging_write=loopmillis;
|
||||||
|
|
||||||
|
@ -128,8 +141,8 @@ void loggingLoop(unsigned long loopmillis,ESCSerialComm& escFront, ESCSerialComm
|
||||||
dataFile.print(escRear.getCurrentConsumed(),3); dataFile.print(",");
|
dataFile.print(escRear.getCurrentConsumed(),3); dataFile.print(",");
|
||||||
dataFile.print(currentConsumed,3); dataFile.print(",");
|
dataFile.print(currentConsumed,3); dataFile.print(",");
|
||||||
dataFile.print(watthoursConsumed,3); dataFile.print(",");
|
dataFile.print(watthoursConsumed,3); dataFile.print(",");
|
||||||
dataFile.print(temp_ESCFront,2); dataFile.print(",");
|
dataFile.print(temp_Front,2); dataFile.print(",");
|
||||||
dataFile.print(temp_ESCRear,2); dataFile.print(",");
|
dataFile.print(temp_Rear,2); dataFile.print(",");
|
||||||
dataFile.print(temp_Air,2); dataFile.print(",");
|
dataFile.print(temp_Air,2); dataFile.print(",");
|
||||||
dataFile.print(looptime_duration_min); dataFile.print(",");
|
dataFile.print(looptime_duration_min); dataFile.print(",");
|
||||||
dataFile.print(looptime_duration_max); //dataFile.print(",");
|
dataFile.print(looptime_duration_max); //dataFile.print(",");
|
||||||
|
@ -375,8 +388,8 @@ void serialCommandLoop(unsigned long loopmillis,ESCSerialComm& escFront, ESCSeri
|
||||||
Serial.print("currentConsumed_Rear\t"); Serial.println(escRear.getCurrentConsumed(),3);
|
Serial.print("currentConsumed_Rear\t"); Serial.println(escRear.getCurrentConsumed(),3);
|
||||||
Serial.print("currentConsumed\t"); Serial.println(currentConsumed,3);
|
Serial.print("currentConsumed\t"); Serial.println(currentConsumed,3);
|
||||||
Serial.print("watthoursConsumed\t"); Serial.println(watthoursConsumed,3);
|
Serial.print("watthoursConsumed\t"); Serial.println(watthoursConsumed,3);
|
||||||
Serial.print("temp_Front\t"); Serial.println(temp_ESCFront,3);
|
Serial.print("temp_Front\t"); Serial.println(temp_Front,3);
|
||||||
Serial.print("temp_Rear\t"); Serial.println(temp_ESCRear,3);
|
Serial.print("temp_Rear\t"); Serial.println(temp_Rear,3);
|
||||||
Serial.print("temp_Air\t"); Serial.println(temp_Air,3);
|
Serial.print("temp_Air\t"); Serial.println(temp_Air,3);
|
||||||
Serial.print("looptime_duration_min\t"); Serial.println(looptime_duration_min);
|
Serial.print("looptime_duration_min\t"); Serial.println(looptime_duration_min);
|
||||||
Serial.print("looptime_duration_max\t"); Serial.println(looptime_duration_max);
|
Serial.print("looptime_duration_max\t"); Serial.println(looptime_duration_max);
|
||||||
|
|
|
@ -7,10 +7,10 @@
|
||||||
//#define SEARCH_DEVICES
|
//#define SEARCH_DEVICES
|
||||||
|
|
||||||
|
|
||||||
DeviceAddress thermometerESCFront={0x28,0xFF,0x64,0x0E,0x77,0xB0,0xAB,0x4B}; //IC with one marking 28FF640E77B0AB4B
|
DeviceAddress thermometerFront={0x28,0xFF,0x64,0x0E,0x77,0xB0,0xAB,0x4B}; //IC with one marking 28FF640E77B0AB4B
|
||||||
float temp_ESCFront;
|
float temp_Front;
|
||||||
DeviceAddress thermometerESCRear={0x28,0xFF,0x64,0x0E,0x76,0x5D,0x86,0xC2}; //IC with two markings
|
DeviceAddress thermometerRear={0x28,0xFF,0x64,0x0E,0x76,0x5D,0x86,0xC2}; //IC with two markings
|
||||||
float temp_ESCRear;
|
float temp_Rear;
|
||||||
DeviceAddress thermometerAir={0x28,0xFF,0x64,0x0E,0x74,0x7E,0xFE,0x23}; //IC with three markings 28FF640E747EFE23
|
DeviceAddress thermometerAir={0x28,0xFF,0x64,0x0E,0x74,0x7E,0xFE,0x23}; //IC with three markings 28FF640E747EFE23
|
||||||
float temp_Air;
|
float temp_Air;
|
||||||
|
|
||||||
|
@ -84,8 +84,8 @@ bool temperatureLoop(unsigned long loopmillis) {
|
||||||
if (sensors.isConversionComplete()) {
|
if (sensors.isConversionComplete()) {
|
||||||
flag_requestTemperatures=false;
|
flag_requestTemperatures=false;
|
||||||
last_read_ds18b20=loopmillis;
|
last_read_ds18b20=loopmillis;
|
||||||
temp_ESCFront= sensors.getTempC(thermometerESCFront); //This takes ~12.5ms
|
temp_Front= sensors.getTempC(thermometerFront); //This takes ~12.5ms
|
||||||
temp_ESCRear= sensors.getTempC(thermometerESCRear);
|
temp_Rear= sensors.getTempC(thermometerRear);
|
||||||
temp_Air= sensors.getTempC(thermometerAir);
|
temp_Air= sensors.getTempC(thermometerAir);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -49,7 +49,7 @@ void readADC();
|
||||||
void failChecks();
|
void failChecks();
|
||||||
//void sendCMD();
|
//void sendCMD();
|
||||||
void calculateSetSpeed(unsigned long timediff);
|
void calculateSetSpeed(unsigned long timediff);
|
||||||
void checkLog();
|
|
||||||
|
|
||||||
void leds();
|
void leds();
|
||||||
|
|
||||||
|
@ -254,24 +254,8 @@ void loop() {
|
||||||
last_statsupdate=loopmillis;
|
last_statsupdate=loopmillis;
|
||||||
}
|
}
|
||||||
|
|
||||||
/* TODO: remove this if, because everything contained in esc.update()
|
|
||||||
if (loopmillis - last_send > SENDPERIOD) { //Calculate motor stuff and send to motor controllers
|
|
||||||
last_send=loopmillis;
|
|
||||||
//sendCMD();
|
|
||||||
|
|
||||||
|
|
||||||
//Update speed and trip
|
|
||||||
float _meanRPM=(FeedbackFront.speedL_meas-FeedbackFront.speedR_meas+FeedbackRear.speedL_meas-FeedbackRear.speedR_meas)/4.0;
|
|
||||||
meanSpeedms=_meanRPM*wheelcircumference/60.0; // Units: 1/min * m / 60s
|
|
||||||
trip+=abs(meanSpeedms)* (SENDPERIOD/1000.0);
|
|
||||||
|
|
||||||
//mah consumed
|
|
||||||
currentConsumed += (motorparamsFront.filtered_curL+motorparamsFront.filtered_curR+motorparamsRear.filtered_curL+motorparamsRear.filtered_curR)* (SENDPERIOD/1000.0)/3600.0; //amp hours
|
|
||||||
}
|
|
||||||
*/
|
|
||||||
|
|
||||||
//If needed write log to serial port
|
|
||||||
//checkLog(); //TODO remove
|
|
||||||
loggingLoop(loopmillis,escFront,escRear);
|
loggingLoop(loopmillis,escFront,escRear);
|
||||||
if (!armed && !statswritten) { //write stats only once when disarmed
|
if (!armed && !statswritten) { //write stats only once when disarmed
|
||||||
statswritten=true;
|
statswritten=true;
|
||||||
|
@ -306,11 +290,11 @@ void loop() {
|
||||||
last_fan_update=loopmillis;
|
last_fan_update=loopmillis;
|
||||||
boolean fanstatus=digitalRead(PIN_FAN);
|
boolean fanstatus=digitalRead(PIN_FAN);
|
||||||
//float temp=max(escFront.getFeedback_boardTemp(),escRear.getFeedback_boardTemp());
|
//float temp=max(escFront.getFeedback_boardTemp(),escRear.getFeedback_boardTemp());
|
||||||
float temp=max(temp_ESCFront,temp_ESCRear);
|
float temp=max(temp_Front,temp_Rear);
|
||||||
if (temp_ESCFront==DEVICE_DISCONNECTED_C || temp_ESCRear==DEVICE_DISCONNECTED_C ) { //temperature error
|
if (temp_Front==DEVICE_DISCONNECTED_C || temp_Rear==DEVICE_DISCONNECTED_C ) { //temperature error
|
||||||
digitalWrite(PIN_FAN,HIGH); //force fan on
|
digitalWrite(PIN_FAN,HIGH); //force fan on
|
||||||
|
|
||||||
}else{ //normal temperature control
|
}else{ //normal temperature control_currentIncrease
|
||||||
|
|
||||||
if (!fanstatus) { //fan is off
|
if (!fanstatus) { //fan is off
|
||||||
if (temp>=fan_turn_on_temp){
|
if (temp>=fan_turn_on_temp){
|
||||||
|
|
Loading…
Reference in New Issue