add ds18b20 temperature sensors
This commit is contained in:
parent
73fc09154f
commit
07ac01b993
File diff suppressed because it is too large
Load Diff
|
@ -181,8 +181,11 @@ void display_standingDisplay(ESCSerialComm& escFront, ESCSerialComm& escRear) {
|
|||
display.print(" V");
|
||||
display.println();
|
||||
|
||||
display.print(F("Temp:")); display.print(escFront.getFeedback_boardTemp());
|
||||
display.print(F("/")); display.print(escRear.getFeedback_boardTemp());
|
||||
//display.print(F("Temp:")); display.print(escFront.getFeedback_boardTemp());
|
||||
//display.print(F("/")); display.print(escRear.getFeedback_boardTemp());
|
||||
display.print(F("T:")); display.print(temp_ESCFront,0);
|
||||
display.print(F("/")); display.print(temp_ESCRear,0);
|
||||
display.print(F("/")); display.print(temp_Air,0);
|
||||
display.print(" C");
|
||||
display.println();
|
||||
|
||||
|
|
|
@ -65,7 +65,8 @@ void loggingLoop(unsigned long loopmillis,ESCSerialComm& escFront, ESCSerialComm
|
|||
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.println("currentAll,throttle,brake,speed,trip_Front,trip_Rear,currentConsumed_Front,currentConsumed_Rear");
|
||||
dataFile.print("currentAll,throttle,brake,speed,trip_Front,trip_Rear,currentConsumed_Front,currentConsumed_Rear");
|
||||
dataFile.println("temp_ESCFront,temp_ESCRear,temp_Air");
|
||||
dataFile.print("#TIMESTAMP:"); dataFile.println(now());
|
||||
logging_headerWritten=true;
|
||||
}
|
||||
|
@ -94,6 +95,9 @@ void loggingLoop(unsigned long loopmillis,ESCSerialComm& escFront, ESCSerialComm
|
|||
dataFile.print(escRear.getTrip()); dataFile.print(";");
|
||||
dataFile.print(escFront.getCurrentConsumed(),3); dataFile.print(";");
|
||||
dataFile.print(escRear.getCurrentConsumed(),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.println("");
|
||||
dataFile.close();
|
||||
}
|
||||
|
|
|
@ -0,0 +1,105 @@
|
|||
#ifndef _TEMPERATURE_H_
|
||||
#define _TEMPERATURE_H_
|
||||
|
||||
#include <OneWire.h>
|
||||
#include <DallasTemperature.h>
|
||||
|
||||
DeviceAddress thermometerESCFront={0x28,0xFF,0x64,0x0E,0x77,0xB0,0xAB,0x4B}; //IC with one marking 28FF640E77B0AB4B
|
||||
float temp_ESCFront;
|
||||
DeviceAddress thermometerESCRear={0x28,0xFF,0x64,0x0E,0x76,0x5D,0x86,0xC2}; //IC with two markings
|
||||
float temp_ESCRear;
|
||||
DeviceAddress thermometerAir={0x28,0xFF,0x64,0x0E,0x74,0x7E,0xFE,0x23}; //IC with three markings 28FF640E747EFE23
|
||||
float temp_Air;
|
||||
|
||||
#define ONE_WIRE_BUS A2 //GPIO pin
|
||||
#define TEMPERATURE_PRECISION 12 //max is 12
|
||||
#define READINTERVAL_DS18B20 5000 //ms
|
||||
|
||||
// Setup a oneWire instance to communicate with any OneWire devices (not just Maxim/Dallas temperature ICs)
|
||||
OneWire oneWire(ONE_WIRE_BUS);
|
||||
|
||||
// Pass our oneWire reference to Dallas Temperature.
|
||||
DallasTemperature sensors(&oneWire);
|
||||
|
||||
void initTemperature();
|
||||
void temperatureLoop();
|
||||
void printAddress(DeviceAddress deviceAddress);
|
||||
|
||||
void initTemperature() {
|
||||
|
||||
sensors.begin();
|
||||
delay(1000);
|
||||
|
||||
|
||||
Serial.print("Locating devices...");
|
||||
Serial.print("Found ");
|
||||
Serial.print(sensors.getDeviceCount(), DEC);
|
||||
Serial.println(" devices.");
|
||||
|
||||
delay(1000);
|
||||
|
||||
delay(1000);
|
||||
|
||||
|
||||
//Just search for devices. Only needed when connecting a new sensor to find the address
|
||||
oneWire.reset_search();
|
||||
|
||||
for (uint8_t i=0;i<sensors.getDeviceCount();i++){
|
||||
DeviceAddress _addr;
|
||||
if (!oneWire.search(_addr)) {
|
||||
Serial.print("Error: Device not found");
|
||||
}else{
|
||||
Serial.print("Found device. Address:");
|
||||
printAddress(_addr);
|
||||
}
|
||||
Serial.println();
|
||||
|
||||
}
|
||||
|
||||
delay(1000);
|
||||
|
||||
//sensors.setResolution(thermometerReservoir, TEMPERATURE_PRECISION);
|
||||
|
||||
}
|
||||
|
||||
void temperatureLoop(unsigned long loopmillis) {
|
||||
static unsigned long last_read_ds18b20;
|
||||
static bool flag_requestTemperatures=false;
|
||||
if (loopmillis>last_read_ds18b20+READINTERVAL_DS18B20) {
|
||||
if (loopmillis>last_read_ds18b20+READINTERVAL_DS18B20*10) { //timeout
|
||||
Serial.println("Warn: Request Temperatures Timeout!");
|
||||
flag_requestTemperatures=false;
|
||||
}
|
||||
if (!flag_requestTemperatures) {
|
||||
unsigned long _start=millis();
|
||||
sensors.requestTemperatures(); //this takes ~34ms
|
||||
Serial.print("DS Request took ms:"); Serial.println(millis()-_start);
|
||||
flag_requestTemperatures=true;
|
||||
}
|
||||
if (sensors.isConversionComplete()) {
|
||||
flag_requestTemperatures=false;
|
||||
last_read_ds18b20=loopmillis;
|
||||
temp_ESCFront= sensors.getTempC(thermometerESCFront); //This takes ~12.5ms
|
||||
temp_ESCRear= sensors.getTempC(thermometerESCRear);
|
||||
temp_Air= sensors.getTempC(thermometerAir);
|
||||
/*
|
||||
Serial.print("temp_ESCFront: "); Serial.println(temp_ESCFront);
|
||||
Serial.print("temp_ESCRear: "); Serial.println(temp_ESCRear);
|
||||
Serial.print("temp_Air: "); Serial.println(temp_Air);
|
||||
*/
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
void printAddress(DeviceAddress deviceAddress)
|
||||
{
|
||||
for (uint8_t i = 0; i < 8; i++)
|
||||
{
|
||||
// zero pad the address if necessary
|
||||
if (deviceAddress[i] < 16) Serial.print("0");
|
||||
Serial.print(deviceAddress[i], HEX);
|
||||
}
|
||||
}
|
||||
#endif
|
|
@ -24,4 +24,5 @@ lib_deps =
|
|||
robtillaart/ADS1X15@^0.3.9
|
||||
adafruit/Adafruit SSD1306@^2.5.7
|
||||
arduino-libraries/SD@^1.2.4
|
||||
https://github.com/adafruit/Adafruit_NeoPixel
|
||||
https://github.com/adafruit/Adafruit_NeoPixel
|
||||
https://github.com/milesburton/Arduino-Temperature-Control-Library/
|
|
@ -8,7 +8,7 @@
|
|||
#include "helpfunctions.h"
|
||||
#include "hoverboard-esc-serial-comm.h"
|
||||
#include "led.h"
|
||||
|
||||
#include "temperature.h"
|
||||
|
||||
//#include "comms.h"
|
||||
String getLogFilename();
|
||||
|
@ -21,6 +21,8 @@ String getLogFilename();
|
|||
|
||||
|
||||
|
||||
|
||||
|
||||
ESCSerialComm escFront(Serial2);
|
||||
ESCSerialComm escRear(Serial3);
|
||||
//Serial1 = TX1=1, RX1=0
|
||||
|
@ -116,6 +118,7 @@ void setup()
|
|||
led_simpeProgress(5,true);
|
||||
|
||||
//init ADS1115
|
||||
|
||||
if (!ADS.begin()) {
|
||||
Serial.println("Error:"); delay(2000); Serial.println("ADS1115 Init Error!");
|
||||
led_simpeProgress(6,false);
|
||||
|
@ -142,6 +145,9 @@ void setup()
|
|||
Serial.println("RTC has set the system time");
|
||||
led_simpeProgress(7,true);
|
||||
}
|
||||
|
||||
initTemperature();
|
||||
led_simpeProgress(8,true);
|
||||
|
||||
|
||||
|
||||
|
@ -198,10 +204,10 @@ void loop() {
|
|||
*/
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
if (loopmillis - last_adsread > ADSREADPERIOD) { //read teensy adc and filter
|
||||
if (ADS.isConnected() && (loopmillis - last_adsread > ADSREADPERIOD) ) { //read teensy adc and filter
|
||||
last_adsread=loopmillis;
|
||||
if (ADS.isBusy() == false) //reads a register on ads
|
||||
{
|
||||
|
@ -277,6 +283,9 @@ void loop() {
|
|||
display_update(escFront,escRear);
|
||||
}
|
||||
|
||||
//Temperature
|
||||
temperatureLoop(loopmillis);
|
||||
|
||||
//Fan
|
||||
static unsigned long last_fan_update=0;
|
||||
#define FANUPDATEPERIOD 5000
|
||||
|
@ -285,7 +294,8 @@ void loop() {
|
|||
if (loopmillis - last_fan_update > FANUPDATEPERIOD) {
|
||||
last_fan_update=loopmillis;
|
||||
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);
|
||||
if (!escFront.getControllerConnected() || !escRear.getControllerConnected()) { //boards are not powered on
|
||||
digitalWrite(PIN_FAN,HIGH); //force fan on
|
||||
}else{ //if both controllers are on, use temperature regulation
|
||||
|
|
Loading…
Reference in New Issue