make temperature request async
This commit is contained in:
parent
959ec20490
commit
6dd18ff375
|
@ -1,162 +0,0 @@
|
|||
#ifndef _COMMS_H_
|
||||
#define _COMMS_H_
|
||||
|
||||
|
||||
#include "definitions.h"
|
||||
#include "structs.h"
|
||||
|
||||
void SendSerial(SerialCommand &scom, int16_t uSpeedLeft, int16_t uSpeedRight, HardwareSerial &SerialRef);
|
||||
bool ReceiveSerial(SerialRead &sread, SerialFeedback &Feedback,SerialFeedback &NewFeedback, HardwareSerial &SerialRef);
|
||||
|
||||
void updateMotorparams( MotorParameter &mp, SerialFeedback &fb,unsigned long _loopmillis);
|
||||
|
||||
void writeLogInfo(HardwareSerial &SerialRef);
|
||||
void writeLogHeader(HardwareSerial &SerialRef);
|
||||
void writeLog(HardwareSerial &SerialRef, unsigned long time, MotorParameter &mpfront, MotorParameter &mprear, SerialFeedback &fbfront, SerialFeedback &fbrear, float currentAll, int16_t throttle, int16_t brake);
|
||||
void writeLogComment(HardwareSerial &SerialRef, unsigned long time, String msg);
|
||||
|
||||
|
||||
void SendSerial(SerialCommand &scom, int16_t uSpeedLeft, int16_t uSpeedRight, HardwareSerial &SerialRef)
|
||||
{
|
||||
// Create command
|
||||
scom.start = (uint16_t)START_FRAME;
|
||||
scom.speedLeft = (int16_t)uSpeedLeft;
|
||||
scom.speedRight = (int16_t)uSpeedRight;
|
||||
scom.checksum = (uint16_t)(scom.start ^ scom.speedLeft ^ scom.speedRight);
|
||||
|
||||
SerialRef.write((uint8_t *) &scom, sizeof(scom));
|
||||
|
||||
}
|
||||
|
||||
bool ReceiveSerial(SerialRead &sread, SerialFeedback &Feedback,SerialFeedback &NewFeedback, HardwareSerial &SerialRef)
|
||||
{
|
||||
bool _result=false; //return true if new full data frame received
|
||||
// Check for new data availability in the Serial buffer
|
||||
if ( SerialRef.available() ) {
|
||||
sread.incomingByte = SerialRef.read(); // Read the incoming byte
|
||||
sread.bufStartFrame = ((uint16_t)(sread.incomingByte) << 8) | sread.incomingBytePrev; // Construct the start frame
|
||||
}
|
||||
else {
|
||||
return false; //nothing new
|
||||
}
|
||||
|
||||
// If DEBUG_RX is defined print all incoming bytes
|
||||
#ifdef DEBUG_RX
|
||||
Serial.print(sread.incomingByte);
|
||||
#endif
|
||||
|
||||
// Copy received data
|
||||
if (sread.bufStartFrame == START_FRAME) { // Initialize if new data is detected
|
||||
sread.p = (byte *)&NewFeedback;
|
||||
*sread.p++ = sread.incomingBytePrev;
|
||||
*sread.p++ = sread.incomingByte;
|
||||
sread.idx = 2;
|
||||
} else if (sread.idx >= 2 && sread.idx < sizeof(SerialFeedback)) { // Save the new received data
|
||||
*sread.p++ = sread.incomingByte;
|
||||
sread.idx++;
|
||||
}
|
||||
|
||||
// Check if we reached the end of the package
|
||||
if (sread.idx == sizeof(SerialFeedback)) {
|
||||
uint16_t checksum;
|
||||
|
||||
checksum = (uint16_t)(NewFeedback.start ^ NewFeedback.cmd1 ^ NewFeedback.cmd2
|
||||
^ NewFeedback.speedR_meas ^ NewFeedback.speedL_meas ^ NewFeedback.batVoltage ^ NewFeedback.boardTemp ^ NewFeedback.curL_DC ^ NewFeedback.curR_DC ^ NewFeedback.cmdLed);
|
||||
|
||||
// Check validity of the new data
|
||||
if (NewFeedback.start == START_FRAME && checksum == NewFeedback.checksum) {
|
||||
// Copy the new data
|
||||
memcpy(&Feedback, &NewFeedback, sizeof(SerialFeedback));
|
||||
sread.lastValidDataSerial_time = millis();
|
||||
_result=true;
|
||||
} else {
|
||||
_result=false;
|
||||
}
|
||||
sread.idx = 0; // Reset the index (it prevents to enter in this if condition in the next cycle)
|
||||
}
|
||||
/*
|
||||
// Print data to built-in Serial
|
||||
Serial.print("1: "); Serial.print(Feedback.cmd1);
|
||||
Serial.print(" 2: "); Serial.print(Feedback.cmd2);
|
||||
Serial.print(" 3: "); Serial.print(Feedback.speedR);
|
||||
Serial.print(" 4: "); Serial.print(Feedback.speedL);
|
||||
Serial.print(" 5: "); Serial.print(Feedback.speedR_meas);
|
||||
Serial.print(" 6: "); Serial.print(Feedback.speedL_meas);
|
||||
Serial.print(" 7: "); Serial.print(Feedback.batVoltage);
|
||||
Serial.print(" 8: "); Serial.println(Feedback.boardTemp);
|
||||
} else {
|
||||
Serial.println("Non-valid data skipped");
|
||||
}*/
|
||||
|
||||
// Update previous states
|
||||
sread.incomingBytePrev = sread.incomingByte;
|
||||
|
||||
return _result; //new data was available
|
||||
}
|
||||
|
||||
|
||||
|
||||
void updateMotorparams( MotorParameter &mp, SerialFeedback &fb,unsigned long _loopmillis) {
|
||||
mp.cur_pos++;
|
||||
mp.cur_pos%=CURRENT_FILTER_SIZE;
|
||||
mp.curL_DC[mp.cur_pos] = -fb.curL_DC; //invert so positive current is consumed current. negative then means regenerated
|
||||
mp.curR_DC[mp.cur_pos] = -fb.curR_DC;
|
||||
mp.millis=_loopmillis;
|
||||
log_update=true;
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
void writeLogInfo(HardwareSerial &SerialRef) { //first line of file
|
||||
SerialRef.print("#TIMESTAMP:");
|
||||
SerialRef.println(now());
|
||||
}
|
||||
|
||||
void writeLogHeader(HardwareSerial &SerialRef) {
|
||||
SerialRef.print("time,cmd_FrontL,cmd_FrontR,cmd_RearL,cmd_RearR,");
|
||||
SerialRef.print("current_FrontL,current_FrontR,current_RearL,current_RearR,");
|
||||
SerialRef.print("rpm_FrontL,rpm_FrontR,rpm_RearL,rpm_RearR,");
|
||||
SerialRef.print("temp_Front,temp_Rear,vbat_Front,vbat_Rear,");
|
||||
SerialRef.println("currentAll,throttle,brake,speed,trip,currentConsumed");
|
||||
}
|
||||
|
||||
void writeLog(HardwareSerial &SerialRef, unsigned long time, MotorParameter &mpfront, MotorParameter &mprear, SerialFeedback &fbfront, SerialFeedback &fbrear, float currentAll, int16_t throttle, int16_t brake)
|
||||
{
|
||||
SerialRef.print(time/1000.0,3); SerialRef.print(","); //time in seconds
|
||||
SerialRef.print(mpfront.cmdL); SerialRef.print(",");
|
||||
SerialRef.print(mpfront.cmdR); SerialRef.print(",");
|
||||
SerialRef.print(mprear.cmdL); SerialRef.print(",");
|
||||
SerialRef.print(mprear.cmdR); SerialRef.print(",");
|
||||
|
||||
SerialRef.print(mpfront.filtered_curL,3); SerialRef.print(",");
|
||||
SerialRef.print(mpfront.filtered_curR,3); SerialRef.print(",");
|
||||
SerialRef.print(mprear.filtered_curL,3); SerialRef.print(",");
|
||||
SerialRef.print(mprear.filtered_curR,3); SerialRef.print(",");
|
||||
|
||||
SerialRef.print(fbfront.speedL_meas); SerialRef.print(","); //invert speed, because left wheels are negated
|
||||
SerialRef.print(-fbfront.speedR_meas); SerialRef.print(",");
|
||||
SerialRef.print(fbrear.speedL_meas); SerialRef.print(","); //invert speed, because left wheels are negated
|
||||
SerialRef.print(-fbrear.speedR_meas); SerialRef.print(",");
|
||||
|
||||
SerialRef.print(fbfront.boardTemp/10.0,1); SerialRef.print(","); //in degC
|
||||
SerialRef.print(fbrear.boardTemp/10.0,1); SerialRef.print(","); //in degC
|
||||
SerialRef.print(fbfront.batVoltage/100.0); SerialRef.print(","); //in V
|
||||
SerialRef.print(fbrear.batVoltage/100.0); SerialRef.print(","); //in V
|
||||
|
||||
SerialRef.print(currentAll,3); SerialRef.print(",");
|
||||
SerialRef.print(throttle); SerialRef.print(",");
|
||||
SerialRef.print(brake); SerialRef.print(",");
|
||||
SerialRef.print(meanSpeedms); SerialRef.print(","); // m/s
|
||||
SerialRef.print(trip); SerialRef.print(","); //in m
|
||||
SerialRef.print(currentConsumed,3); SerialRef.println(); //in Ah (Amphours)
|
||||
|
||||
}
|
||||
|
||||
void writeLogComment(HardwareSerial &SerialRef, unsigned long time, String msg)
|
||||
{
|
||||
SerialRef.print("#"); SerialRef.print(time/1000.0,3); SerialRef.print(","); SerialRef.print(msg); SerialRef.println();
|
||||
}
|
||||
*/
|
||||
|
||||
|
||||
#endif
|
|
@ -15,6 +15,8 @@
|
|||
#define SCREEN_ADDRESS 0x3C ///< See datasheet for Address; 0x3D for 128x64, 0x3C for 128x32
|
||||
Adafruit_SSD1306 display(SCREEN_WIDTH, SCREEN_HEIGHT, &Wire, OLED_RESET);
|
||||
|
||||
|
||||
|
||||
bool display_init();
|
||||
void display_update(ESCSerialComm& escFront, ESCSerialComm& escRear);
|
||||
void display_drivingDisplay(ESCSerialComm& escFront, ESCSerialComm& escRear);
|
||||
|
|
|
@ -4,6 +4,7 @@
|
|||
#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
|
||||
|
@ -22,7 +23,7 @@ OneWire oneWire(ONE_WIRE_BUS);
|
|||
DallasTemperature sensors(&oneWire);
|
||||
|
||||
void initTemperature();
|
||||
void temperatureLoop();
|
||||
bool temperatureLoop();
|
||||
void printAddress(DeviceAddress deviceAddress);
|
||||
|
||||
void initTemperature() {
|
||||
|
@ -60,18 +61,26 @@ void initTemperature() {
|
|||
|
||||
//sensors.setResolution(thermometerReservoir, TEMPERATURE_PRECISION);
|
||||
|
||||
|
||||
}
|
||||
|
||||
void temperatureLoop(unsigned long loopmillis) {
|
||||
bool 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
|
||||
if (loopmillis>last_read_ds18b20+READINTERVAL_DS18B20*4) { //timeout
|
||||
Serial.println("Warn: Request Temperatures Timeout!");
|
||||
flag_requestTemperatures=false;
|
||||
last_read_ds18b20=loopmillis; //set time to lastread to wait for another timeout
|
||||
return 0;
|
||||
}
|
||||
if (!flag_requestTemperatures) {
|
||||
sensors.requestTemperatures(); //this takes ~34ms
|
||||
//in synchronous mode requestTemperatures takes ~34ms if sensors are available. if sensors not available it takes about 729ms
|
||||
sensors.setWaitForConversion(false); //make async
|
||||
//in asynchronous mode it takes ~2ms if sensors are available. if not it takes ~1ms
|
||||
sensors.requestTemperatures();
|
||||
sensors.setWaitForConversion(true);
|
||||
|
||||
flag_requestTemperatures=true;
|
||||
}
|
||||
if (sensors.isConversionComplete()) {
|
||||
|
@ -80,13 +89,9 @@ void temperatureLoop(unsigned long 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);
|
||||
*/
|
||||
}
|
||||
}
|
||||
return 1;
|
||||
}
|
||||
|
||||
|
||||
|
|
|
@ -174,6 +174,7 @@ void loop() {
|
|||
loopmillis=millis(); //read millis for this cycle
|
||||
|
||||
|
||||
|
||||
/*
|
||||
// ____ Debugging pending serial byted for feedback
|
||||
static int s2availmax=0;
|
||||
|
@ -323,8 +324,12 @@ void loop() {
|
|||
display_update(escFront,escRear);
|
||||
}
|
||||
|
||||
|
||||
//Temperature
|
||||
temperatureLoop(loopmillis);
|
||||
if (!temperatureLoop(loopmillis)){
|
||||
writeLogComment(loopmillis, "Request Temperatures Timeout!");
|
||||
}
|
||||
|
||||
|
||||
//Fan
|
||||
static unsigned long last_fan_update=0;
|
||||
|
@ -390,7 +395,6 @@ void readADS() { //sequentially read ads and write to variable
|
|||
break;
|
||||
case 3: //Buttons
|
||||
ads_control_raw=ads_val;
|
||||
Serial.print("ADS="); Serial.print(ads_throttle_A_raw); Serial.print(" \t"); Serial.print(ads_throttle_B_raw); Serial.print(" \t"); Serial.print(ads_brake_raw); Serial.print(" \t"); Serial.println(ads_control_raw);
|
||||
break;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue