Compare commits
5 Commits
main
...
ioexpander
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
1b8ba88b05 | ||
| 5aa5aaa07a | |||
| 1b7a531d54 | |||
| 8171cab9cb | |||
|
|
899c8cffbc |
@@ -74,21 +74,21 @@ void ADS1256::InitializeADC()
|
|||||||
writeRegister(STATUS_REG, _STATUS);
|
writeRegister(STATUS_REG, _STATUS);
|
||||||
delay(200);
|
delay(200);
|
||||||
|
|
||||||
_MUX = 0b00000001; //MUX AIN0+AIN1
|
_MUX = DIFF_0_1; //MUX AIN0+AIN1
|
||||||
writeRegister(MUX_REG, _MUX);
|
writeRegister(MUX_REG, _MUX);
|
||||||
delay(200);
|
delay(200);
|
||||||
|
|
||||||
_ADCON = 0b00000000; //ADCON - CLK: OFF, SDCS: OFF, PGA = 0 (+/- 5 V)
|
_ADCON = WAKEUP; //ADCON - CLK: OFF, SDCS: OFF, PGA = 0 (+/- 5 V)
|
||||||
writeRegister(ADCON_REG, _ADCON);
|
writeRegister(ADCON_REG, _ADCON);
|
||||||
delay(200);
|
delay(200);
|
||||||
|
|
||||||
updateConversionParameter();
|
updateConversionParameter();
|
||||||
|
|
||||||
_DRATE = 0b10000010; //100SPS
|
_DRATE = DRATE_100SPS; //100SPS
|
||||||
writeRegister(DRATE_REG, _DRATE);
|
writeRegister(DRATE_REG, _DRATE);
|
||||||
delay(200);
|
delay(200);
|
||||||
|
|
||||||
sendDirectCommand(0b11110000); //Offset and self-gain calibration
|
sendDirectCommand(SELFCAL); //Offset and self-gain calibration
|
||||||
delay(200);
|
delay(200);
|
||||||
|
|
||||||
_isAcquisitionRunning = false; //MCU will be waiting to start a continuous acquisition
|
_isAcquisitionRunning = false; //MCU will be waiting to start a continuous acquisition
|
||||||
@@ -109,7 +109,7 @@ void ADS1256::waitForHighDRDY()
|
|||||||
void ADS1256::stopConversion() //Sending SDATAC to stop the continuous conversion
|
void ADS1256::stopConversion() //Sending SDATAC to stop the continuous conversion
|
||||||
{
|
{
|
||||||
waitForLowDRDY(); //SDATAC should be called after DRDY goes LOW (p35. Figure 33)
|
waitForLowDRDY(); //SDATAC should be called after DRDY goes LOW (p35. Figure 33)
|
||||||
_spi->transfer(0b00001111); //Send SDATAC to the ADC
|
_spi->transfer(SDATAC); //Send SDATAC to the ADC
|
||||||
CS_HIGH(); //We finished the command sequence, so we switch it back to HIGH
|
CS_HIGH(); //We finished the command sequence, so we switch it back to HIGH
|
||||||
_spi->endTransaction();
|
_spi->endTransaction();
|
||||||
|
|
||||||
@@ -120,14 +120,14 @@ void ADS1256::setDRATE(uint8_t drate) //Setting DRATE (sampling frequency)
|
|||||||
{
|
{
|
||||||
writeRegister(DRATE_REG, drate);
|
writeRegister(DRATE_REG, drate);
|
||||||
_DRATE = drate;
|
_DRATE = drate;
|
||||||
delayMicroseconds(500);
|
delay(200);
|
||||||
}
|
}
|
||||||
|
|
||||||
void ADS1256::setMUX(uint8_t mux) //Setting MUX (input channel)
|
void ADS1256::setMUX(uint8_t mux) //Setting MUX (input channel)
|
||||||
{
|
{
|
||||||
writeRegister(MUX_REG, mux);
|
writeRegister(MUX_REG, mux);
|
||||||
_MUX = mux;
|
_MUX = mux;
|
||||||
//delayMicroseconds(500);
|
delay(200);
|
||||||
}
|
}
|
||||||
|
|
||||||
void ADS1256::setPGA(uint8_t pga) //Setting PGA (input voltage range)
|
void ADS1256::setPGA(uint8_t pga) //Setting PGA (input voltage range)
|
||||||
@@ -138,7 +138,7 @@ void ADS1256::setPGA(uint8_t pga) //Setting PGA (input voltage range)
|
|||||||
_ADCON = (_ADCON & 0b11111000) | (_PGA & 0b00000111); // Clearing and then setting bits 2-0 based on pga
|
_ADCON = (_ADCON & 0b11111000) | (_PGA & 0b00000111); // Clearing and then setting bits 2-0 based on pga
|
||||||
|
|
||||||
writeRegister(ADCON_REG, _ADCON);
|
writeRegister(ADCON_REG, _ADCON);
|
||||||
delayMicroseconds(1000); //Delay to allow the PGA to settle after changing its value
|
delay(200);
|
||||||
|
|
||||||
updateConversionParameter(); //Update the multiplier according top the new PGA value
|
updateConversionParameter(); //Update the multiplier according top the new PGA value
|
||||||
}
|
}
|
||||||
@@ -465,7 +465,7 @@ uint8_t ADS1256::readGPIO(uint8_t gpioPin) //Reading GPIO
|
|||||||
void ADS1256::sendDirectCommand(uint8_t directCommand)
|
void ADS1256::sendDirectCommand(uint8_t directCommand)
|
||||||
{
|
{
|
||||||
//Direct commands can be found in the datasheet Page 34, Table 24.
|
//Direct commands can be found in the datasheet Page 34, Table 24.
|
||||||
_spi->beginTransaction(SPISettings(1920000, MSBFIRST, SPI_MODE1));
|
_spi->beginTransaction(SPISettings(SPI_FREQ, MSBFIRST, SPI_MODE1));
|
||||||
|
|
||||||
CS_LOW(); //REF: P34: "CS must stay low during the entire command sequence"
|
CS_LOW(); //REF: P34: "CS must stay low during the entire command sequence"
|
||||||
delayMicroseconds(5);
|
delayMicroseconds(5);
|
||||||
@@ -486,14 +486,14 @@ void ADS1256::writeRegister(uint8_t registerAddress, uint8_t registerValueToWrit
|
|||||||
{
|
{
|
||||||
waitForLowDRDY();
|
waitForLowDRDY();
|
||||||
|
|
||||||
_spi->beginTransaction(SPISettings(1920000, MSBFIRST, SPI_MODE1));
|
_spi->beginTransaction(SPISettings(SPI_FREQ, MSBFIRST, SPI_MODE1));
|
||||||
//SPI_MODE1 = output edge: rising, data capture: falling; clock polarity: 0, clock phase: 1.
|
//SPI_MODE1 = output edge: rising, data capture: falling; clock polarity: 0, clock phase: 1.
|
||||||
|
|
||||||
CS_LOW(); //CS must stay LOW during the entire sequence [Ref: P34, T24]
|
CS_LOW(); //CS must stay LOW during the entire sequence [Ref: P34, T24]
|
||||||
|
|
||||||
delayMicroseconds(5); //see t6 in the datasheet
|
delayMicroseconds(5); //see t6 in the datasheet
|
||||||
|
|
||||||
_spi->transfer(0x50 | registerAddress); // 0x50 = 01010000 = WREG
|
_spi->transfer(WREG | registerAddress); // 0x50 = 01010000 = WREG
|
||||||
|
|
||||||
_spi->transfer(0x00); //2nd (empty) command byte
|
_spi->transfer(0x00); //2nd (empty) command byte
|
||||||
|
|
||||||
@@ -501,38 +501,40 @@ void ADS1256::writeRegister(uint8_t registerAddress, uint8_t registerValueToWrit
|
|||||||
|
|
||||||
CS_HIGH();
|
CS_HIGH();
|
||||||
_spi->endTransaction();
|
_spi->endTransaction();
|
||||||
|
delay(100);
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
long ADS1256::readRegister(uint8_t registerAddress) //Reading a register
|
long ADS1256::readRegister(uint8_t registerAddress) //Reading a register
|
||||||
{
|
{
|
||||||
waitForLowDRDY();
|
waitForLowDRDY();
|
||||||
|
|
||||||
_spi->beginTransaction(SPISettings(1920000, MSBFIRST, SPI_MODE1));
|
_spi->beginTransaction(SPISettings(SPI_FREQ, MSBFIRST, SPI_MODE1));
|
||||||
//SPI_MODE1 = output edge: rising, data capture: falling; clock polarity: 0, clock phase: 1.
|
//SPI_MODE1 = output edge: rising, data capture: falling; clock polarity: 0, clock phase: 1.
|
||||||
|
|
||||||
CS_LOW(); //CS must stay LOW during the entire sequence [Ref: P34, T24]
|
CS_LOW(); //CS must stay LOW during the entire sequence [Ref: P34, T24]
|
||||||
|
|
||||||
_spi->transfer(0x10 | registerAddress); //0x10 = 0001000 = RREG - OR together the two numbers (command + address)
|
_spi->transfer(RREG | registerAddress); //0x10 = 0001000 = RREG - OR together the two numbers (command + address)
|
||||||
|
|
||||||
_spi->transfer(0x00); //2nd (empty) command byte
|
_spi->transfer(0x00); //2nd (empty) command byte
|
||||||
|
|
||||||
delayMicroseconds(5); //see t6 in the datasheet
|
delayMicroseconds(5); //see t6 in the datasheet
|
||||||
|
|
||||||
uint8_t regValue = _spi->transfer(0xFF); //read out the register value
|
uint8_t regValue = _spi->transfer(0x00); //read out the register value
|
||||||
|
|
||||||
CS_HIGH();
|
CS_HIGH();
|
||||||
_spi->endTransaction();
|
_spi->endTransaction();
|
||||||
|
delay(100);
|
||||||
return regValue;
|
return regValue;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
long ADS1256::readSingle() //Reading a single value ONCE using the RDATA command
|
long ADS1256::readSingle() //Reading a single value ONCE using the RDATA command
|
||||||
{
|
{
|
||||||
_spi->beginTransaction(SPISettings(1920000, MSBFIRST, SPI_MODE1));
|
_spi->beginTransaction(SPISettings(SPI_FREQ, MSBFIRST, SPI_MODE1));
|
||||||
CS_LOW(); //REF: P34: "CS must stay low during the entire command sequence"
|
CS_LOW(); //REF: P34: "CS must stay low during the entire command sequence"
|
||||||
waitForLowDRDY();
|
waitForLowDRDY();
|
||||||
_spi->transfer(0b00000001); //Issue RDATA (0000 0001) command
|
_spi->transfer(RDATA); //Issue RDATA (0000 0001) command
|
||||||
delayMicroseconds(7); //Wait t6 time (~6.51 us) REF: P34, FIG:30.
|
delayMicroseconds(7); //Wait t6 time (~6.51 us) REF: P34, FIG:30.
|
||||||
|
|
||||||
_outputBuffer[0] = _spi->transfer(0); // MSB
|
_outputBuffer[0] = _spi->transfer(0); // MSB
|
||||||
@@ -554,10 +556,10 @@ long ADS1256::readSingleContinuous() //Reads the recently selected input channel
|
|||||||
if(_isAcquisitionRunning == false)
|
if(_isAcquisitionRunning == false)
|
||||||
{
|
{
|
||||||
_isAcquisitionRunning = true;
|
_isAcquisitionRunning = true;
|
||||||
_spi->beginTransaction(SPISettings(1920000, MSBFIRST, SPI_MODE1));
|
_spi->beginTransaction(SPISettings(SPI_FREQ, MSBFIRST, SPI_MODE1));
|
||||||
CS_LOW(); //REF: P34: "CS must stay low during the entire command sequence"
|
CS_LOW(); //REF: P34: "CS must stay low during the entire command sequence"
|
||||||
waitForLowDRDY();
|
waitForLowDRDY();
|
||||||
_spi->transfer(0b00000011); //Issue RDATAC (0000 0011)
|
_spi->transfer(RDATAC); //Issue RDATAC (0000 0011)
|
||||||
delayMicroseconds(7); //Wait t6 time (~6.51 us) REF: P34, FIG:30.
|
delayMicroseconds(7); //Wait t6 time (~6.51 us) REF: P34, FIG:30.
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
@@ -583,14 +585,12 @@ long ADS1256::cycleSingle()
|
|||||||
{
|
{
|
||||||
_isAcquisitionRunning = true;
|
_isAcquisitionRunning = true;
|
||||||
_cycle = 0;
|
_cycle = 0;
|
||||||
_spi->beginTransaction(SPISettings(1920000, MSBFIRST, SPI_MODE1));
|
_spi->beginTransaction(SPISettings(SPI_FREQ, MSBFIRST, SPI_MODE1));
|
||||||
CS_LOW(); //CS must stay LOW during the entire sequence [Ref: P34, T24]
|
CS_LOW(); //CS must stay LOW during the entire sequence [Ref: P34, T24]
|
||||||
_spi->transfer(0x50 | 1); // 0x50 = WREG //1 = MUX
|
_spi->transfer(WREG | MUX_REG); // 0x50 = WREG //1 = MUX
|
||||||
_spi->transfer(0x00);
|
_spi->transfer(0x00);
|
||||||
_spi->transfer(SING_0); //AIN0+AINCOM
|
_spi->transfer(SING_0); //AIN0+AINCOM
|
||||||
CS_HIGH();
|
delayMicroseconds(250);
|
||||||
delay(50);
|
|
||||||
CS_LOW(); //CS must stay LOW during the entire sequence [Ref: P34, T24]
|
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{}
|
{}
|
||||||
@@ -636,18 +636,18 @@ long ADS1256::cycleSingle()
|
|||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
//Step 2.
|
//Step 2.
|
||||||
_spi->transfer(0b11111100); //SYNC
|
_spi->transfer(SYNC); //SYNC
|
||||||
delayMicroseconds(4); //t11 delay 24*tau = 3.125 us //delay should be larger, so we delay by 4 us
|
delayMicroseconds(4); //t11 delay 24*tau = 3.125 us //delay should be larger, so we delay by 4 us
|
||||||
_spi->transfer(0b11111111); //WAKEUP
|
_spi->transfer(WAKEUP); //WAKEUP
|
||||||
|
|
||||||
//Step 3.
|
//Step 3.
|
||||||
//Issue RDATA (0000 0001) command
|
//Issue RDATA (0000 0001) command
|
||||||
_spi->transfer(0b00000001);
|
_spi->transfer(RDATA);
|
||||||
delayMicroseconds(7); //Wait t6 time (~6.51 us) REF: P34, FIG:30.
|
delayMicroseconds(7); //Wait t6 time (~6.51 us) REF: P34, FIG:30.
|
||||||
|
|
||||||
_outputBuffer[0] = _spi->transfer(0x0F); // MSB
|
_outputBuffer[0] = _spi->transfer(0); // MSB
|
||||||
_outputBuffer[1] = _spi->transfer(0x0F); // Mid-byte
|
_outputBuffer[1] = _spi->transfer(0); // Mid-byte
|
||||||
_outputBuffer[2] = _spi->transfer(0x0F); // LSB
|
_outputBuffer[2] = _spi->transfer(0); // LSB
|
||||||
|
|
||||||
_outputValue = ((long)_outputBuffer[0]<<16) | ((long)_outputBuffer[1]<<8) | (_outputBuffer[2]);
|
_outputValue = ((long)_outputBuffer[0]<<16) | ((long)_outputBuffer[1]<<8) | (_outputBuffer[2]);
|
||||||
_outputValue = convertSigned24BitToLong(_outputValue);
|
_outputValue = convertSigned24BitToLong(_outputValue);
|
||||||
@@ -668,16 +668,14 @@ long ADS1256::cycleDifferential()
|
|||||||
{
|
{
|
||||||
_cycle = 0;
|
_cycle = 0;
|
||||||
_isAcquisitionRunning = true;
|
_isAcquisitionRunning = true;
|
||||||
_spi->beginTransaction(SPISettings(1920000, MSBFIRST, SPI_MODE1));
|
_spi->beginTransaction(SPISettings(SPI_FREQ, MSBFIRST, SPI_MODE1));
|
||||||
|
|
||||||
//Set the AIN0+AIN1 as inputs manually
|
//Set the AIN0+AIN1 as inputs manually
|
||||||
CS_LOW(); //CS must stay LOW during the entire sequence [Ref: P34, T24]
|
CS_LOW(); //CS must stay LOW during the entire sequence [Ref: P34, T24]
|
||||||
_spi->transfer(0x50 | 1); // 0x50 = WREG //1 = MUX
|
_spi->transfer(WREG | MUX_REG); // 0x50 = WREG //1 = MUX
|
||||||
_spi->transfer(0x00);
|
_spi->transfer(0x00);
|
||||||
_spi->transfer(DIFF_0_1); //AIN0+AIN1
|
_spi->transfer(DIFF_0_1); //AIN0+AIN1
|
||||||
CS_HIGH();
|
delayMicroseconds(250);
|
||||||
delay(50);
|
|
||||||
CS_LOW(); //CS must stay LOW during the entire sequence [Ref: P34, T24]
|
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{}
|
{}
|
||||||
@@ -708,12 +706,12 @@ long ADS1256::cycleDifferential()
|
|||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
_spi->transfer(0b11111100); //SYNC
|
_spi->transfer(SYNC); //SYNC
|
||||||
delayMicroseconds(4); //t11 delay 24*tau = 3.125 us //delay should be larger, so we delay by 4 us
|
delayMicroseconds(4); //t11 delay 24*tau = 3.125 us //delay should be larger, so we delay by 4 us
|
||||||
_spi->transfer(0b11111111); //WAKEUP
|
_spi->transfer(WAKEUP); //WAKEUP
|
||||||
|
|
||||||
//Step 3.
|
//Step 3.
|
||||||
_spi->transfer(0b00000001); //Issue RDATA (0000 0001) command
|
_spi->transfer(RDATA); //Issue RDATA (0000 0001) command
|
||||||
delayMicroseconds(7); //Wait t6 time (~6.51 us) REF: P34, FIG:30.
|
delayMicroseconds(7); //Wait t6 time (~6.51 us) REF: P34, FIG:30.
|
||||||
|
|
||||||
_outputBuffer[0] = _spi->transfer(0); // MSB
|
_outputBuffer[0] = _spi->transfer(0); // MSB
|
||||||
@@ -742,7 +740,7 @@ void ADS1256::updateConversionParameter()
|
|||||||
|
|
||||||
void ADS1256::updateMUX(uint8_t muxValue)
|
void ADS1256::updateMUX(uint8_t muxValue)
|
||||||
{
|
{
|
||||||
_spi->transfer(0x50 | MUX_REG); //Write to the MUX register (0x50 is the WREG command)
|
_spi->transfer(WREG | MUX_REG); //Write to the MUX register (0x50 is the WREG command)
|
||||||
_spi->transfer(0x00);
|
_spi->transfer(0x00);
|
||||||
_spi->transfer(muxValue); //Write the new MUX value
|
_spi->transfer(muxValue); //Write the new MUX value
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -15,6 +15,9 @@
|
|||||||
|
|
||||||
#include <SPI.h>
|
#include <SPI.h>
|
||||||
|
|
||||||
|
// SPI Frequency
|
||||||
|
#define SPI_FREQ 1920000
|
||||||
|
|
||||||
//Differential inputs
|
//Differential inputs
|
||||||
#define DIFF_0_1 0b00000001 //A0 + A1 as differential input
|
#define DIFF_0_1 0b00000001 //A0 + A1 as differential input
|
||||||
#define DIFF_2_3 0b00100011 //A2 + A3 as differential input
|
#define DIFF_2_3 0b00100011 //A2 + A3 as differential input
|
||||||
|
|||||||
@@ -4,6 +4,7 @@ RGBled::RGBled(const uint8_t pin) : m_led(pin)
|
|||||||
{
|
{
|
||||||
pinMode(m_led, OUTPUT);
|
pinMode(m_led, OUTPUT);
|
||||||
writeStatus(RGBled::ERROR);
|
writeStatus(RGBled::ERROR);
|
||||||
|
m_brightness = 1.0f;
|
||||||
}
|
}
|
||||||
|
|
||||||
RGBled::~RGBled()
|
RGBled::~RGBled()
|
||||||
@@ -11,6 +12,11 @@ RGBled::~RGBled()
|
|||||||
pinMode(m_led, INPUT);
|
pinMode(m_led, INPUT);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void RGBled::setBrightness(const float b)
|
||||||
|
{
|
||||||
|
m_brightness = b;
|
||||||
|
}
|
||||||
|
|
||||||
void RGBled::setStatus(const LedStatus s)
|
void RGBled::setStatus(const LedStatus s)
|
||||||
{
|
{
|
||||||
if (m_status == s)
|
if (m_status == s)
|
||||||
@@ -27,6 +33,6 @@ const RGBled::LedStatus RGBled::getSatus(void)
|
|||||||
|
|
||||||
void RGBled::writeStatus(const RGBled::LedStatus s)
|
void RGBled::writeStatus(const RGBled::LedStatus s)
|
||||||
{
|
{
|
||||||
RGBled::color_u u{.status = s};
|
const RGBled::color_u u{.status = s};
|
||||||
rgbLedWrite(m_led, u.color.r, u.color.g, u.color.b);
|
rgbLedWrite(m_led, (uint8_t)(m_brightness*u.color.r), (uint8_t)(m_brightness*u.color.g), (uint8_t)(m_brightness*u.color.b));
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -50,6 +50,7 @@ public:
|
|||||||
RGBled(const uint8_t pin = 48);
|
RGBled(const uint8_t pin = 48);
|
||||||
~RGBled();
|
~RGBled();
|
||||||
|
|
||||||
|
void setBrightness(const float b);
|
||||||
void setStatus(const LedStatus s);
|
void setStatus(const LedStatus s);
|
||||||
const LedStatus getSatus(void);
|
const LedStatus getSatus(void);
|
||||||
|
|
||||||
@@ -59,5 +60,6 @@ private:
|
|||||||
private:
|
private:
|
||||||
LedStatus m_status = LedStatus::IDLE;
|
LedStatus m_status = LedStatus::IDLE;
|
||||||
std::mutex m_mutex;
|
std::mutex m_mutex;
|
||||||
|
float m_brightness;
|
||||||
const uint8_t m_led;
|
const uint8_t m_led;
|
||||||
};
|
};
|
||||||
@@ -28,7 +28,7 @@ monitor_port = /dev/ttyACM0
|
|||||||
monitor_speed = 921600
|
monitor_speed = 921600
|
||||||
build_type = release
|
build_type = release
|
||||||
build_flags =
|
build_flags =
|
||||||
-DCORE_DEBUG_LEVEL=1
|
-DCORE_DEBUG_LEVEL=5
|
||||||
-DARDUINO_USB_CDC_ON_BOOT=0
|
-DARDUINO_USB_CDC_ON_BOOT=0
|
||||||
-DARDUINO_USB_MODE=0
|
-DARDUINO_USB_MODE=0
|
||||||
-DCONFIG_ASYNC_TCP_MAX_ACK_TIME=5000
|
-DCONFIG_ASYNC_TCP_MAX_ACK_TIME=5000
|
||||||
@@ -59,7 +59,7 @@ build_flags =
|
|||||||
-O0
|
-O0
|
||||||
-g3
|
-g3
|
||||||
-ggdb3
|
-ggdb3
|
||||||
-DCORE_DEBUG_LEVEL=3
|
-DCORE_DEBUG_LEVEL=5
|
||||||
-DARDUINO_USB_CDC_ON_BOOT=0
|
-DARDUINO_USB_CDC_ON_BOOT=0
|
||||||
-DARDUINO_USB_MODE=0
|
-DARDUINO_USB_MODE=0
|
||||||
-DCONFIG_ASYNC_TCP_MAX_ACK_TIME=5000
|
-DCONFIG_ASYNC_TCP_MAX_ACK_TIME=5000
|
||||||
|
|||||||
@@ -1,8 +1,6 @@
|
|||||||
#include "datasave.h"
|
#include "datasave.h"
|
||||||
#include <math.h>
|
#include <math.h>
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
LITTLEFSGuard::LITTLEFSGuard()
|
LITTLEFSGuard::LITTLEFSGuard()
|
||||||
{
|
{
|
||||||
if (!LittleFS.begin(true, "/littlefs", 10, "littlefs"))
|
if (!LittleFS.begin(true, "/littlefs", 10, "littlefs"))
|
||||||
@@ -12,7 +10,7 @@ LITTLEFSGuard::LITTLEFSGuard()
|
|||||||
else
|
else
|
||||||
{
|
{
|
||||||
LOG_INFO("LittleFS mounted successfully");
|
LOG_INFO("LittleFS mounted successfully");
|
||||||
LOG_INFO("LittleFS Free KBytes:", (LittleFS.totalBytes() - LittleFS.usedBytes()) /1024);
|
LOG_INFO("LittleFS Free KBytes:", (LittleFS.totalBytes() - LittleFS.usedBytes()) / 1024);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -49,8 +47,7 @@ void ignitionBoxStatusFiltered::update(const ignitionBoxStatus &new_status)
|
|||||||
}
|
}
|
||||||
m_count++;
|
m_count++;
|
||||||
// simple moving average calculation
|
// simple moving average calculation
|
||||||
m_last.timestamp = new_status.timestamp; // keep timestamp of latest status
|
m_last.timestamp = new_status.timestamp; // keep timestamp of latest status
|
||||||
|
|
||||||
m_last.coils12.n_events = new_status.coils12.n_events; // sum events instead of averaging
|
m_last.coils12.n_events = new_status.coils12.n_events; // sum events instead of averaging
|
||||||
m_last.coils12.n_missed_firing = new_status.coils12.n_missed_firing; // sum missed firings instead of averaging
|
m_last.coils12.n_missed_firing = new_status.coils12.n_missed_firing; // sum missed firings instead of averaging
|
||||||
m_last.coils12.spark_status = new_status.coils12.spark_status; // take latest spark status
|
m_last.coils12.spark_status = new_status.coils12.spark_status; // take latest spark status
|
||||||
@@ -72,7 +69,7 @@ void ignitionBoxStatusFiltered::update(const ignitionBoxStatus &new_status)
|
|||||||
filter(m_last.coils34.peak_n_out, new_status.coils34.peak_n_out, m_max_count); // incremental average calculation
|
filter(m_last.coils34.peak_n_out, new_status.coils34.peak_n_out, m_max_count); // incremental average calculation
|
||||||
filter(m_last.eng_rpm, new_status.eng_rpm, m_max_count); // incremental average calculation // incremental average calculation
|
filter(m_last.eng_rpm, new_status.eng_rpm, m_max_count); // incremental average calculation // incremental average calculation
|
||||||
filter(m_last.adc_read_time, m_last.adc_read_time, m_max_count); // incremental average calculation
|
filter(m_last.adc_read_time, m_last.adc_read_time, m_max_count); // incremental average calculation
|
||||||
m_last.n_queue_errors = new_status.n_queue_errors; // take last of queue errors since it's a cumulative count of errors in the queue, not an average value
|
m_last.n_queue_errors = new_status.n_queue_errors;
|
||||||
|
|
||||||
if (m_count >= m_max_count)
|
if (m_count >= m_max_count)
|
||||||
{
|
{
|
||||||
@@ -124,4 +121,3 @@ const ArduinoJson::JsonDocument ignitionBoxStatusFiltered::toJson() const
|
|||||||
}
|
}
|
||||||
return doc;
|
return doc;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -9,7 +9,8 @@
|
|||||||
// Device Libraries
|
// Device Libraries
|
||||||
#include <ADS1256.h>
|
#include <ADS1256.h>
|
||||||
#include <AD5292.h>
|
#include <AD5292.h>
|
||||||
#include <PCA95x5.h>
|
#include <extio.h>
|
||||||
|
#include <Wire.h>
|
||||||
|
|
||||||
// ADC Channel mapping
|
// ADC Channel mapping
|
||||||
#define ADC_CH_PEAK_12P_IN SING_0
|
#define ADC_CH_PEAK_12P_IN SING_0
|
||||||
@@ -24,34 +25,31 @@
|
|||||||
// Device Pointer structs for tasks
|
// Device Pointer structs for tasks
|
||||||
struct Devices
|
struct Devices
|
||||||
{
|
{
|
||||||
|
// Busses
|
||||||
|
std::unique_ptr<TwoWire> m_i2c = nullptr;
|
||||||
std::unique_ptr<SPIClass> m_spi_a = nullptr;
|
std::unique_ptr<SPIClass> m_spi_a = nullptr;
|
||||||
std::unique_ptr<SPIClass> m_spi_b = nullptr;
|
std::unique_ptr<SPIClass> m_spi_b = nullptr;
|
||||||
|
|
||||||
|
// Bus Mutextes
|
||||||
|
std::mutex m_spi_a_mutex;
|
||||||
|
std::mutex m_spi_b_mutex;
|
||||||
|
std::mutex m_i2c_mutex;
|
||||||
|
|
||||||
|
// Device Pointers
|
||||||
std::unique_ptr<AD5292> m_pot_a = nullptr;
|
std::unique_ptr<AD5292> m_pot_a = nullptr;
|
||||||
std::unique_ptr<AD5292> m_pot_b = nullptr;
|
std::unique_ptr<AD5292> m_pot_b = nullptr;
|
||||||
|
|
||||||
std::unique_ptr<ADS1256> m_adc_a = nullptr;
|
std::unique_ptr<ADS1256> m_adc_a = nullptr;
|
||||||
std::unique_ptr<ADS1256> m_adc_b = nullptr;
|
std::unique_ptr<ADS1256> m_adc_b = nullptr;
|
||||||
|
|
||||||
std::unique_ptr<PCA9555> m_expander_a = nullptr;
|
std::unique_ptr<ExternalIO> m_ext_io = nullptr;
|
||||||
std::unique_ptr<PCA9555> m_expander_b = nullptr;
|
|
||||||
std::unique_ptr<PCA9555> m_expander_inputs_ab = nullptr;
|
|
||||||
|
|
||||||
std::mutex m_spi_a_mutex;
|
|
||||||
std::mutex m_spi_b_mutex;
|
|
||||||
|
|
||||||
std::mutex m_i2c_mutex;
|
|
||||||
};
|
};
|
||||||
|
|
||||||
// Adc read channel wrapper to selet mux before reading
|
// Adc read channel wrapper to selet mux before reading
|
||||||
inline float adcReadChannel(ADS1256 *adc, const uint8_t ch)
|
inline float adcReadChannel(ADS1256 *adc, const uint8_t ch)
|
||||||
{
|
{
|
||||||
adc->setMUX(ch);
|
adc->setMUX(ch);
|
||||||
// scarta 3 conversioni
|
adc->readSingle();
|
||||||
for (int i = 0; i < 3; i++)
|
|
||||||
{
|
|
||||||
adc->readSingle();
|
|
||||||
}
|
|
||||||
// ora lettura valida a 30kSPS → ~100 µs di settling
|
// ora lettura valida a 30kSPS → ~100 µs di settling
|
||||||
return adc->convertToVoltage(adc->readSingle());
|
return adc->convertToVoltage(adc->readSingle());
|
||||||
}
|
}
|
||||||
|
|||||||
129
RotaxMonitor/src/extio.cpp
Normal file
129
RotaxMonitor/src/extio.cpp
Normal file
@@ -0,0 +1,129 @@
|
|||||||
|
#include <extio.h>
|
||||||
|
|
||||||
|
// Static interrupt callback
|
||||||
|
static void onExpanderInterrupt(void *arg)
|
||||||
|
{
|
||||||
|
auto cls = (ExternalIO *)(arg);
|
||||||
|
if (!cls) // invalid args
|
||||||
|
return;
|
||||||
|
cls->extReadInterrupt();
|
||||||
|
}
|
||||||
|
|
||||||
|
ExternalIO::ExternalIO(TwoWire &i2c, std::mutex &i2c_mutex, const uint8_t int_pin) : m_i2cMutex(i2c_mutex), m_i2c(i2c), m_intPin(int_pin)
|
||||||
|
{
|
||||||
|
std::lock_guard<std::mutex> lock(m_i2cMutex);
|
||||||
|
// Attach OUT expanders on BUS
|
||||||
|
m_outMap[EXPANDER_A_OUT_ADDR] = std::make_unique<PCA9555>();
|
||||||
|
m_outMap[EXPANDER_A_OUT_ADDR]->attach(m_i2c, EXPANDER_A_OUT_ADDR);
|
||||||
|
m_outMap[EXPANDER_B_OUT_ADDR] = std::make_unique<PCA9555>();
|
||||||
|
m_outMap[EXPANDER_B_OUT_ADDR]->attach(m_i2c, EXPANDER_B_OUT_ADDR);
|
||||||
|
|
||||||
|
for (auto &[a, e] : m_outMap)
|
||||||
|
{
|
||||||
|
e->direction(PCA95x5::Direction::OUT_ALL);
|
||||||
|
e->polarity(PCA95x5::Polarity::ORIGINAL_ALL);
|
||||||
|
};
|
||||||
|
|
||||||
|
// Attach IN Expanders on Bus
|
||||||
|
m_inMap[EXPANDER_A_IN_ADDR] = std::make_unique<PCA9555>();
|
||||||
|
m_inMap[EXPANDER_A_IN_ADDR]->attach(m_i2c, EXPANDER_A_IN_ADDR);
|
||||||
|
m_inMap[EXPANDER_B_IN_ADDR] = std::make_unique<PCA9555>();
|
||||||
|
m_inMap[EXPANDER_B_IN_ADDR]->attach(m_i2c, EXPANDER_B_IN_ADDR);
|
||||||
|
|
||||||
|
for (auto &[a, e] : m_inMap)
|
||||||
|
{
|
||||||
|
e->direction(PCA95x5::Direction::IN_ALL);
|
||||||
|
e->polarity(PCA95x5::Polarity::ORIGINAL_ALL);
|
||||||
|
m_lastInputState[a] = e->read(); /// initialize input state to collect interrupts
|
||||||
|
};
|
||||||
|
}
|
||||||
|
ExternalIO::~ExternalIO() {
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
void ExternalIO::extDigitalWrite(const uint32_t mappedPin, const bool val)
|
||||||
|
{
|
||||||
|
std::lock_guard<std::mutex> lock(m_i2cMutex);
|
||||||
|
const io_t pa = map2pin(mappedPin);
|
||||||
|
if (!m_outMap.contains(pa.addr))
|
||||||
|
{
|
||||||
|
LOG_ERROR("Undefined IO Expander addr: [", pa.addr, "]");
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
auto &io = m_outMap.at(pa.addr);
|
||||||
|
if (!io->write(static_cast<PCA95x5::Port::Port>(pa.pin), val ? PCA95x5::Level::H : PCA95x5::Level::L))
|
||||||
|
{
|
||||||
|
LOG_ERROR("IO Expander [", pa.addr, "] Unable to WRITE Port [", pa.pin, "] to [", val ? "HIGH" : "LOW");
|
||||||
|
LOG_ERROR("IO Expander Error [", io->i2c_error(), "]");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
const bool ExternalIO::extDigitalRead(const uint32_t mappedPin)
|
||||||
|
{
|
||||||
|
std::lock_guard<std::mutex> lock(m_i2cMutex);
|
||||||
|
const io_t pa = map2pin(mappedPin);
|
||||||
|
if (!m_inMap.contains(pa.addr))
|
||||||
|
{
|
||||||
|
LOG_ERROR("Undefined IO Expander addr: [", pa.addr, "]");
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
auto &io = m_inMap.at(pa.addr);
|
||||||
|
const bool rv = io->read(static_cast<PCA95x5::Port::Port>(pa.pin)) == PCA95x5::Level::H ? true : false; // read value
|
||||||
|
const uint8_t err = io->i2c_error();
|
||||||
|
if (err)
|
||||||
|
{
|
||||||
|
LOG_ERROR("IO Expander [", pa.addr, "] Unable to READ Port [", pa.pin, "]");
|
||||||
|
LOG_ERROR("IO Expander Error [", err, "]");
|
||||||
|
}
|
||||||
|
return rv;
|
||||||
|
}
|
||||||
|
|
||||||
|
void ExternalIO::extAttachInterrupt(ExtInterruptCb cb)
|
||||||
|
{
|
||||||
|
attachInterruptArg(EXPANDER_ALL_INTERRUPT, onExpanderInterrupt, (void *)(this), FALLING);
|
||||||
|
m_extInterruptCb = cb;
|
||||||
|
}
|
||||||
|
|
||||||
|
void ExternalIO::extDetachInterrupt()
|
||||||
|
{
|
||||||
|
detachInterrupt(EXPANDER_ALL_INTERRUPT);
|
||||||
|
}
|
||||||
|
|
||||||
|
void ExternalIO::extReadInterrupt()
|
||||||
|
{
|
||||||
|
std::lock_guard<std::mutex> lock(m_i2cMutex);
|
||||||
|
disableInterrupt(EXPANDER_ALL_INTERRUPT);
|
||||||
|
// read all registers and collect
|
||||||
|
IOstate interruptState;
|
||||||
|
for (auto &[a, e] : m_inMap)
|
||||||
|
{
|
||||||
|
interruptState[a] = e->read();
|
||||||
|
}
|
||||||
|
m_lastInputState = interruptState; // restore to current values
|
||||||
|
// compare to last state to see the difference
|
||||||
|
if (m_extInterruptCb)
|
||||||
|
{
|
||||||
|
for (auto &[a, v] : interruptState)
|
||||||
|
{
|
||||||
|
if (v)
|
||||||
|
m_extInterruptCb(stat2map(a, v));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
enableInterrupt(EXPANDER_ALL_INTERRUPT);
|
||||||
|
}
|
||||||
|
|
||||||
|
const ExternalIO::io_t ExternalIO::map2pin(const uint32_t mappedIO)
|
||||||
|
{
|
||||||
|
return io_t{
|
||||||
|
.addr = (uint8_t)((mappedIO >> 16) & (uint8_t)0xFF),
|
||||||
|
.pin = (uint8_t)(mappedIO && (uint32_t)0xFF),
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
const uint32_t ExternalIO::stat2map(const uint8_t addr, const uint16_t stat)
|
||||||
|
{
|
||||||
|
if (!stat)
|
||||||
|
return 0;
|
||||||
|
return (uint32_t)(addr << 16) | (1UL << __builtin_ctz(stat));
|
||||||
|
}
|
||||||
49
RotaxMonitor/src/extio.h
Normal file
49
RotaxMonitor/src/extio.h
Normal file
@@ -0,0 +1,49 @@
|
|||||||
|
#pragma once
|
||||||
|
#define DEBUGLOG_DEFAULT_LOG_LEVEL_DEBUG
|
||||||
|
|
||||||
|
#include <Arduino.h>
|
||||||
|
#include <DebugLog.h>
|
||||||
|
#include <PCA95x5.h>
|
||||||
|
|
||||||
|
#include <pins.h>
|
||||||
|
|
||||||
|
#include <memory>
|
||||||
|
#include <map>
|
||||||
|
|
||||||
|
class ExternalIO
|
||||||
|
{
|
||||||
|
using IOptr = std::unique_ptr<PCA9555>;
|
||||||
|
using IOmap = std::map<const uint8_t, IOptr>;
|
||||||
|
using IOstate = std::map<const uint8_t, uint16_t>;
|
||||||
|
using ExtInterruptCb = std::function<void(const uint32_t)>;
|
||||||
|
|
||||||
|
struct io_t
|
||||||
|
{
|
||||||
|
uint8_t addr;
|
||||||
|
uint8_t pin;
|
||||||
|
};
|
||||||
|
|
||||||
|
public:
|
||||||
|
ExternalIO(TwoWire &i2c, std::mutex &i2c_mutex, const uint8_t int_pin);
|
||||||
|
~ExternalIO();
|
||||||
|
|
||||||
|
void extDigitalWrite(const uint32_t mappedPin, const bool val);
|
||||||
|
const bool extDigitalRead(const uint32_t mappedPin);
|
||||||
|
void extAttachInterrupt(ExtInterruptCb cb = nullptr);
|
||||||
|
void extDetachInterrupt();
|
||||||
|
void extReadInterrupt();
|
||||||
|
|
||||||
|
private:
|
||||||
|
const io_t map2pin(const uint32_t mappedIO);
|
||||||
|
const uint32_t stat2map(const uint8_t addr, const uint16_t stat);
|
||||||
|
|
||||||
|
private:
|
||||||
|
const uint8_t m_intPin;
|
||||||
|
IOmap m_inMap;
|
||||||
|
IOmap m_outMap;
|
||||||
|
uint8_t m_intPinChanged;
|
||||||
|
IOstate m_lastInputState;
|
||||||
|
ExtInterruptCb m_extInterruptCb = nullptr;
|
||||||
|
std::mutex &m_i2cMutex;
|
||||||
|
TwoWire &m_i2c;
|
||||||
|
};
|
||||||
@@ -17,12 +17,13 @@
|
|||||||
#include <led.h>
|
#include <led.h>
|
||||||
|
|
||||||
// Defines to enable channel B
|
// Defines to enable channel B
|
||||||
#define CH_B_ENABLE
|
// #define CH_B_ENABLE
|
||||||
// #define TEST
|
|
||||||
|
|
||||||
// Debug Defines
|
// Debug Defines
|
||||||
#define WIFI_SSID "AstroRotaxMonitor"
|
#define WIFI_SSID "AstroRotaxMonitor"
|
||||||
#define WIFI_PASSWORD "maledettirotax"
|
#define WIFI_PASSWORD "maledettirotax"
|
||||||
|
#define PSRAM_MAX 4096
|
||||||
|
#define QUEUE_MAX 256
|
||||||
|
|
||||||
void setup()
|
void setup()
|
||||||
{
|
{
|
||||||
@@ -31,7 +32,7 @@ void setup()
|
|||||||
|
|
||||||
// Setup Logger
|
// Setup Logger
|
||||||
LOG_ATTACH_SERIAL(Serial);
|
LOG_ATTACH_SERIAL(Serial);
|
||||||
LOG_SET_LEVEL(DebugLogLevel::LVL_DEBUG);
|
LOG_SET_LEVEL(DebugLogLevel::LVL_INFO);
|
||||||
|
|
||||||
// Print Processor Info
|
// Print Processor Info
|
||||||
LOG_DEBUG("ESP32 Chip:", ESP.getChipModel());
|
LOG_DEBUG("ESP32 Chip:", ESP.getChipModel());
|
||||||
@@ -52,7 +53,7 @@ void setup()
|
|||||||
IPAddress gateway(10, 11, 12, 1);
|
IPAddress gateway(10, 11, 12, 1);
|
||||||
IPAddress subnet(255, 255, 255, 0);
|
IPAddress subnet(255, 255, 255, 0);
|
||||||
WiFi.softAPConfig(local_IP, gateway, subnet);
|
WiFi.softAPConfig(local_IP, gateway, subnet);
|
||||||
WiFi.setTxPower(WIFI_POWER_13dBm); // reduce wifi power
|
WiFi.setTxPower(WIFI_POWER_5dBm); // reduce wifi power
|
||||||
if (WiFi.softAP(WIFI_SSID, WIFI_PASSWORD))
|
if (WiFi.softAP(WIFI_SSID, WIFI_PASSWORD))
|
||||||
{
|
{
|
||||||
LOG_INFO("WiFi AP Mode Started");
|
LOG_INFO("WiFi AP Mode Started");
|
||||||
@@ -79,23 +80,30 @@ void loop()
|
|||||||
{
|
{
|
||||||
// global variables
|
// global variables
|
||||||
RGBled led;
|
RGBled led;
|
||||||
|
led.setBrightness(0.025f);
|
||||||
led.setStatus(RGBled::LedStatus::INIT);
|
led.setStatus(RGBled::LedStatus::INIT);
|
||||||
|
|
||||||
|
std::shared_ptr<Devices> dev = std::make_shared<Devices>();
|
||||||
bool running = true;
|
bool running = true;
|
||||||
std::mutex fs_mutex;
|
std::mutex fs_mutex;
|
||||||
LITTLEFSGuard fsGuard;
|
LITTLEFSGuard fsGuard;
|
||||||
|
|
||||||
//////// INIT SPI PORTS ////////
|
//////// INIT SPI INTERFACES ////////
|
||||||
bool spiA_ok = true;
|
bool spiA_ok = true;
|
||||||
bool spiB_ok = true;
|
bool spiB_ok = true;
|
||||||
// Init 2 SPI interfaces
|
LOG_DEBUG("Init SPI Interfaces");
|
||||||
// SPIClass SPI_A(FSPI);
|
SPIClass SPI_A(FSPI);
|
||||||
// spiA_ok = SPI_A.begin(SPI_A_SCK, SPI_A_MISO, SPI_A_MOSI);
|
spiA_ok = SPI_A.begin(SPI_A_SCK, SPI_A_MISO, SPI_A_MOSI);
|
||||||
// SPI_A.setDataMode(SPI_MODE1); // ADS1256 requires SPI mode 1
|
SPI_A.setDataMode(SPI_MODE1); // ADS1256 requires SPI mode 1
|
||||||
// #ifdef CH_B_ENABLE
|
LOG_DEBUG("Init SPI A ok");
|
||||||
// SPIClass SPI_B(HSPI);
|
#ifdef CH_B_ENABLE
|
||||||
// spiB_ok = SPI_B.begin(SPI_B_SCK, SPI_B_MISO, SPI_B_MOSI);
|
delay(50);
|
||||||
// SPI_B.setDataMode(SPI_MODE1); // ADS1256 requires SPI mode 1
|
SPIClass SPI_B(HSPI);
|
||||||
// #endif
|
spiB_ok = SPI_B.begin(SPI_B_SCK, SPI_B_MISO, SPI_B_MOSI);
|
||||||
|
SPI_B.setDataMode(SPI_MODE1); // ADS1256 requires SPI mode 1
|
||||||
|
LOG_DEBUG("Init SPI B ok");
|
||||||
|
#endif
|
||||||
|
|
||||||
if (!spiA_ok || !spiB_ok)
|
if (!spiA_ok || !spiB_ok)
|
||||||
{
|
{
|
||||||
LOG_ERROR("Unable to Initialize SPI Busses");
|
LOG_ERROR("Unable to Initialize SPI Busses");
|
||||||
@@ -103,25 +111,71 @@ void loop()
|
|||||||
vTaskDelay(pdMS_TO_TICKS(5000));
|
vTaskDelay(pdMS_TO_TICKS(5000));
|
||||||
esp_restart();
|
esp_restart();
|
||||||
}
|
}
|
||||||
|
dev->m_spi_a.reset(&SPI_A);
|
||||||
|
#ifdef CH_B_ENABLE
|
||||||
|
dev->m_spi_b.reset(&SPI_B);
|
||||||
|
#endif
|
||||||
|
// Init ADCs
|
||||||
|
dev->m_adc_a = std::make_unique<ADS1256>(ADC_A_DRDY, ADS1256::PIN_UNUSED, ADS1256::PIN_UNUSED, ADC_A_CS, 2.5, &SPI_A);
|
||||||
|
#ifdef CH_B_ENABLE
|
||||||
|
dev->m_adc_b = std::make_unique<ADS1256>(ADC_B_DRDY, ADS1256::PIN_UNUSED, ADS1256::PIN_UNUSED, ADC_B_CS, 2.5, &SPI_B);
|
||||||
|
#endif
|
||||||
|
// Configure ADCs
|
||||||
|
dev->m_adc_a->InitializeADC();
|
||||||
|
dev->m_adc_a->setPGA(PGA_1);
|
||||||
|
dev->m_adc_a->setDRATE(DRATE_7500SPS);
|
||||||
|
#ifdef CH_B_ENABLE
|
||||||
|
dev->m_adc_b->InitializeADC();
|
||||||
|
dev->m_adc_b->setPGA(PGA_1);
|
||||||
|
dev->m_adc_b->setDRATE(DRATE_30000SPS);
|
||||||
|
#endif
|
||||||
LOG_DEBUG("Init SPI OK");
|
LOG_DEBUG("Init SPI OK");
|
||||||
|
|
||||||
// Resources Initialization
|
uint8_t chs[8] = {
|
||||||
std::shared_ptr<Devices> dev = std::make_shared<Devices>();
|
SING_0, SING_1, SING_2, SING_3, SING_4, SING_5, SING_6, SING_7};
|
||||||
// dev->m_spi_a = std::make_unique<SPIClass>(SPI_A);
|
float res[8];
|
||||||
// dev->m_spi_b = std::make_unique<SPIClass>(SPI_B);
|
auto timeout = Serial.getTimeout();
|
||||||
|
Serial.setTimeout(0);
|
||||||
|
uint64_t count = 0;
|
||||||
|
|
||||||
// // Init ADC_A
|
while (Serial.read() != 's') // The conversion is stopped by a character received from the serial port
|
||||||
// dev->m_adc_a = std::make_unique<ADS1256>(ADC_A_DRDY, ADS1256::PIN_UNUSED, ADS1256::PIN_UNUSED, ADC_A_CS, 2.5, &SPI_A);
|
{
|
||||||
// dev->m_adc_b = std::make_unique<ADS1256>(ADC_B_DRDY, ADS1256::PIN_UNUSED, ADS1256::PIN_UNUSED, ADC_B_CS, 2.5, &SPI_B);
|
auto start = esp_timer_get_time();
|
||||||
|
for (int i = 0; i < 8; i++)
|
||||||
|
{
|
||||||
|
// dev->m_adc_a->setMUX(chs[i]);
|
||||||
|
res[i] += 0.1f * (dev->m_adc_a->convertToVoltage(dev->m_adc_a->cycleSingle()) - res[i]);
|
||||||
|
}
|
||||||
|
auto stop = esp_timer_get_time();
|
||||||
|
if (count++ % 25 == 0)
|
||||||
|
{
|
||||||
|
clearScreen();
|
||||||
|
for (int j = 0; j < 8; j++)
|
||||||
|
{
|
||||||
|
Serial.printf("ADC_A SING_%d: %5.4f\n", j, res[j]);
|
||||||
|
}
|
||||||
|
Serial.printf("ADC Time: %5.3f ms\n", (float)((stop - start) / 1000.0f));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
Serial.setTimeout(timeout);
|
||||||
|
dev->m_adc_a->stopConversion();
|
||||||
|
|
||||||
// dev->m_adc_a->InitializeADC();
|
//////// INIT I2C INTERFACES ////////
|
||||||
// dev->m_adc_a->setPGA(PGA_1);
|
LOG_DEBUG("Init I2C Interfaces");
|
||||||
// dev->m_adc_a->setDRATE(DRATE_7500SPS);
|
bool i2c_ok = true;
|
||||||
|
i2c_ok = Wire.begin(SDA, SCL, 100000);
|
||||||
|
if (!i2c_ok)
|
||||||
|
{
|
||||||
|
LOG_ERROR("Unable to Initialize I2C Bus");
|
||||||
|
LOG_ERROR("5 seconds to restart...");
|
||||||
|
vTaskDelay(pdMS_TO_TICKS(5000));
|
||||||
|
esp_restart();
|
||||||
|
}
|
||||||
|
|
||||||
// dev->m_adc_b->InitializeADC();
|
// Init IO Expanders
|
||||||
// dev->m_adc_b->setPGA(PGA_1);
|
// dev->m_ext_io = std::make_unique<ExternalIO>(Wire, dev->m_i2c_mutex, EXPANDER_ALL_INTERRUPT);
|
||||||
// dev->m_adc_b->setDRATE(DRATE_7500SPS);
|
|
||||||
|
|
||||||
|
//////// INIT REALTIME TASKS PARAMETERS ////////
|
||||||
const rtIgnitionTask::rtTaskParams taskA_params{
|
const rtIgnitionTask::rtTaskParams taskA_params{
|
||||||
.rt_running = true,
|
.rt_running = true,
|
||||||
.name = "rtIgnTask_A",
|
.name = "rtIgnTask_A",
|
||||||
@@ -184,9 +238,10 @@ void loop()
|
|||||||
.rt_queue = nullptr,
|
.rt_queue = nullptr,
|
||||||
.dev = dev};
|
.dev = dev};
|
||||||
|
|
||||||
auto task_A = rtIgnitionTask(taskA_params, 4096, 256, CORE_0, fs_mutex);
|
//////// SPAWN REALTIME TASKS ////////
|
||||||
|
auto task_A = rtIgnitionTask(taskA_params, PSRAM_MAX, QUEUE_MAX, CORE_0, fs_mutex);
|
||||||
delay(50);
|
delay(50);
|
||||||
auto task_B = rtIgnitionTask(taskB_params, 4096, 256, CORE_1, fs_mutex);
|
auto task_B = rtIgnitionTask(taskB_params, PSRAM_MAX, QUEUE_MAX, CORE_1, fs_mutex);
|
||||||
|
|
||||||
// Ignition A on Core 0
|
// Ignition A on Core 0
|
||||||
auto ignA_task_success = task_A.getStatus() == rtIgnitionTask::OK ? pdPASS : pdFAIL;
|
auto ignA_task_success = task_A.getStatus() == rtIgnitionTask::OK ? pdPASS : pdFAIL;
|
||||||
@@ -206,22 +261,26 @@ void loop()
|
|||||||
{
|
{
|
||||||
led.setStatus(RGBled::LedStatus::ERROR);
|
led.setStatus(RGBled::LedStatus::ERROR);
|
||||||
LOG_ERROR("Unable to start realtime tasks");
|
LOG_ERROR("Unable to start realtime tasks");
|
||||||
} else
|
}
|
||||||
LOG_DEBUG("Real Time Tasks A & B initialized");
|
else
|
||||||
led.setStatus(RGBled::LedStatus::OK);
|
{
|
||||||
|
LOG_DEBUG("Real Time Tasks A & B initialized");
|
||||||
|
led.setStatus(RGBled::LedStatus::OK);
|
||||||
|
}
|
||||||
|
|
||||||
AstroWebServer webPage(80, LittleFS); // Initialize webserver and Websocket
|
//////// SPAWN WEBSERVER and WEBSOCKET ////////
|
||||||
|
AstroWebServer webPage(80, LittleFS);
|
||||||
ArduinoJson::JsonDocument json_data;
|
ArduinoJson::JsonDocument json_data;
|
||||||
bool data_a, data_b;
|
bool data_a, data_b;
|
||||||
task_A.onMessage([&webPage, &json_data, &data_a](ignitionBoxStatusFiltered sts){
|
task_A.onMessage([&webPage, &json_data, &data_a](ignitionBoxStatusFiltered sts)
|
||||||
|
{
|
||||||
json_data["box_a"] = sts.toJson();
|
json_data["box_a"] = sts.toJson();
|
||||||
data_a = true;
|
data_a = true; });
|
||||||
});
|
|
||||||
|
|
||||||
task_B.onMessage([&webPage, &json_data, &data_b](ignitionBoxStatusFiltered sts){
|
task_B.onMessage([&webPage, &json_data, &data_b](ignitionBoxStatusFiltered sts)
|
||||||
|
{
|
||||||
json_data["box_b"] = sts.toJson();
|
json_data["box_b"] = sts.toJson();
|
||||||
data_b = true;
|
data_b = true; });
|
||||||
});
|
|
||||||
|
|
||||||
// task_A.enableSave(true, "ignitionA_test.csv");
|
// task_A.enableSave(true, "ignitionA_test.csv");
|
||||||
// task_B.enableSave(true, "ignitionB_test.csv");
|
// task_B.enableSave(true, "ignitionB_test.csv");
|
||||||
@@ -238,7 +297,8 @@ void loop()
|
|||||||
printRunningTasksMod(Serial);
|
printRunningTasksMod(Serial);
|
||||||
monitor_loop = millis();
|
monitor_loop = millis();
|
||||||
}
|
}
|
||||||
if ((data_a && data_b) || (this_loop - data_loop > 500)) {
|
if ((data_a && data_b) || (this_loop - data_loop > 500))
|
||||||
|
{
|
||||||
webPage.sendWsData(json_data.as<String>());
|
webPage.sendWsData(json_data.as<String>());
|
||||||
json_data.clear();
|
json_data.clear();
|
||||||
data_a = data_b = false;
|
data_a = data_b = false;
|
||||||
|
|||||||
@@ -53,12 +53,6 @@
|
|||||||
#define ADC_B_CS 21
|
#define ADC_B_CS 21
|
||||||
#define ADC_B_DRDY 47
|
#define ADC_B_DRDY 47
|
||||||
|
|
||||||
// =====================
|
|
||||||
// DIGITAL POT
|
|
||||||
// =====================
|
|
||||||
#define POT_A_CS 18
|
|
||||||
#define POT_B_CS 35
|
|
||||||
|
|
||||||
// =====================
|
// =====================
|
||||||
// TRIGGER INPUT INTERRUPTS
|
// TRIGGER INPUT INTERRUPTS
|
||||||
// =====================
|
// =====================
|
||||||
@@ -79,86 +73,87 @@
|
|||||||
#define SPARK_PIN_B12 1
|
#define SPARK_PIN_B12 1
|
||||||
#define SPARK_PIN_B34 2
|
#define SPARK_PIN_B34 2
|
||||||
|
|
||||||
// =====================
|
// +++++++++++++++++++++
|
||||||
// PCA9555 I/O EXPANDER BOX_A
|
// MACRO TO COMBINE PIN NUMBER AND ADDRESS
|
||||||
// =====================
|
#define PIN2ADDR(p, a) ((1UL << p) | ((uint32_t)(a) << 16))
|
||||||
|
// +++++++++++++++++++++
|
||||||
|
|
||||||
#define EXPANDER_A_ADDR 0x010101
|
// =====================
|
||||||
|
// PCA9555 I/O EXPANDER INTERRUPT (Common)
|
||||||
|
// =====================
|
||||||
|
#define EXPANDER_ALL_INTERRUPT 17
|
||||||
|
|
||||||
|
// =====================
|
||||||
|
// PCA9555 I/O EXPANDER BOX_A (OUT)
|
||||||
|
// =====================
|
||||||
|
#define EXPANDER_A_OUT_ADDR 0xFF
|
||||||
|
|
||||||
// --- DIGITAL POT CHIP SELECT LINES ---
|
// --- DIGITAL POT CHIP SELECT LINES ---
|
||||||
#define POT_CS_A12 0
|
#define POT_CS_A12 PIN2ADDR(0, EXPANDER_A_OUT_ADDR)
|
||||||
#define POT_CS_A34 1
|
#define POT_CS_A34 PIN2ADDR(1, EXPANDER_A_OUT_ADDR)
|
||||||
|
|
||||||
// --- SOFT START FORCE LINES ---
|
// --- SOFT START FORCE LINES ---
|
||||||
#define SS_FORCE_A 2
|
#define SS_FORCE_A PIN2ADDR(2, EXPANDER_A_OUT_ADDR)
|
||||||
#define SS_INIBHIT_A12 3
|
#define SS_INIBHIT_A12 PIN2ADDR(3, EXPANDER_A_OUT_ADDR)
|
||||||
#define SS_INHIBIT_A34 4
|
#define SS_INHIBIT_A34 PIN2ADDR(4, EXPANDER_A_OUT_ADDR)
|
||||||
|
|
||||||
// --- SAMPLE AND HOLD ARM AND DISCHARGE ---
|
// --- SAMPLE AND HOLD ARM AND DISCHARGE ---
|
||||||
#define SH_DISCH_A12 5
|
#define SH_DISCH_A12 PIN2ADDR(5, EXPANDER_A_OUT_ADDR)
|
||||||
#define SH_DISCH_A34 6
|
#define SH_DISCH_A34 PIN2ADDR(6, EXPANDER_A_OUT_ADDR)
|
||||||
#define SH_ARM_A12 7
|
#define SH_ARM_A12 PIN2ADDR(7, EXPANDER_A_OUT_ADDR)
|
||||||
#define SH_ARM_A34 8
|
#define SH_ARM_A34 PIN2ADDR(8, EXPANDER_A_OUT_ADDR)
|
||||||
|
|
||||||
// --- RELAY ---
|
// --- RELAY ---
|
||||||
#define RELAY_IN_A12 9
|
#define RELAY_IN_A12 PIN2ADDR(9, EXPANDER_A_OUT_ADDR)
|
||||||
#define RELAY_OUT_A12 10
|
#define RELAY_OUT_A12 PIN2ADDR(10, EXPANDER_A_OUT_ADDR)
|
||||||
#define RELAY_IN_A34 11
|
#define RELAY_IN_A34 PIN2ADDR(11, EXPANDER_A_OUT_ADDR)
|
||||||
#define RELAY_OUT_A34 12
|
#define RELAY_OUT_A34 PIN2ADDR(12, EXPANDER_A_OUT_ADDR)
|
||||||
|
|
||||||
// --- STATUS / BUTTON ---
|
|
||||||
#define STA_2 13
|
|
||||||
#define STA_3 14
|
|
||||||
#define STA_4 15
|
|
||||||
|
|
||||||
// =====================
|
// =====================
|
||||||
// PCA9555 I/O EXPANDER BOX_B
|
// PCA9555 I/O EXPANDER BOX_A (IN)
|
||||||
// =====================
|
// =====================
|
||||||
|
#define EXPANDER_A_IN_ADDR 0xFF
|
||||||
|
|
||||||
#define EXPANDER_B_ADDR 0x101010
|
#define SS_A12_ON PIN2ADDR(0, EXPANDER_A_IN_ADDR)
|
||||||
|
#define SS_A12_OFF PIN2ADDR(1, EXPANDER_A_IN_ADDR)
|
||||||
|
#define SS_A34_ON PIN2ADDR(2, EXPANDER_A_IN_ADDR)
|
||||||
|
#define SS_A34_OFF PIN2ADDR(3, EXPANDER_A_IN_ADDR)
|
||||||
|
|
||||||
|
// =====================
|
||||||
|
// PCA9555 I/O EXPANDER BOX_B (OUT)
|
||||||
|
// =====================
|
||||||
|
#define EXPANDER_B_OUT_ADDR 0xFF
|
||||||
|
|
||||||
// --- DIGITAL POT CHIP SELECT LINES ---
|
// --- DIGITAL POT CHIP SELECT LINES ---
|
||||||
#define POT_CS_B12 0
|
#define POT_CS_B12 PIN2ADDR(0, EXPANDER_B_OUT_ADDR)
|
||||||
#define POT_CS_B34 1
|
#define POT_CS_B34 PIN2ADDR(1, EXPANDER_B_OUT_ADDR)
|
||||||
|
|
||||||
// --- SOFT START FORCE LINES ---
|
// --- SOFT START FORCE LINES ---
|
||||||
#define SS_FORCE_B 2
|
#define SS_FORCE_B PIN2ADDR(2, EXPANDER_B_OUT_ADDR)
|
||||||
#define SS_INIBHIT_B12 3
|
#define SS_INIBHIT_B12 PIN2ADDR(3, EXPANDER_B_OUT_ADDR)
|
||||||
#define SS_INHIBIT_B34 4
|
#define SS_INHIBIT_B34 PIN2ADDR(4, EXPANDER_B_OUT_ADDR)
|
||||||
|
|
||||||
// --- SAMPLE AND HOLD ARM AND DISCHARGE ---
|
// --- SAMPLE AND HOLD ARM AND DISCHARGE ---
|
||||||
#define SH_DISCH_B12 5
|
#define SH_DISCH_B12 PIN2ADDR(5, EXPANDER_B_OUT_ADDR)
|
||||||
#define SH_DISCH_B34 6
|
#define SH_DISCH_B34 PIN2ADDR(6, EXPANDER_B_OUT_ADDR)
|
||||||
#define SH_ARM_B12 7
|
#define SH_ARM_B12 PIN2ADDR(7, EXPANDER_B_OUT_ADDR)
|
||||||
#define SH_ARM_B34 8
|
#define SH_ARM_B34 PIN2ADDR(8, EXPANDER_B_OUT_ADDR)
|
||||||
|
|
||||||
// --- RELAY ---
|
// --- RELAY ---
|
||||||
#define RELAY_IN_B12 9
|
#define RELAY_IN_B12 PIN2ADDR(9, EXPANDER_B_OUT_ADDR)
|
||||||
#define RELAY_OUT_B12 10
|
#define RELAY_OUT_B12 PIN2ADDR(10, EXPANDER_B_OUT_ADDR)
|
||||||
#define RELAY_IN_B34 11
|
#define RELAY_IN_B34 PIN2ADDR(11, EXPANDER_B_OUT_ADDR)
|
||||||
#define RELAY_OUT_B34 12
|
#define RELAY_OUT_B34 PIN2ADDR(12, EXPANDER_B_OUT_ADDR)
|
||||||
|
|
||||||
// --- STATUS / BUTTON ---
|
|
||||||
#define STA_2 13
|
|
||||||
#define STA_3 14
|
|
||||||
#define STA_4 15
|
|
||||||
|
|
||||||
// =====================
|
// =====================
|
||||||
// PCA9555 I/O EXPANDER INPUTS A+B
|
// PCA9555 I/O EXPANDER BOX_B (IN)
|
||||||
// =====================
|
// =====================
|
||||||
|
#define EXPANDER_B_IN_ADDR 0xFF
|
||||||
|
|
||||||
#define EXPANDER_IN_ADDR 0x0a0a0a
|
#define SS_B12_ON PIN2ADDR(0, EXPANDER_B_IN_ADDR)
|
||||||
|
#define SS_B12_OFF PIN2ADDR(1, EXPANDER_B_IN_ADDR)
|
||||||
#define SS_A12_ON
|
#define SS_B34_ON PIN2ADDR(2, EXPANDER_B_IN_ADDR)
|
||||||
#define SS_A12_OFF
|
#define SS_B34_OFF PIN2ADDR(3, EXPANDER_B_IN_ADDR)
|
||||||
#define SS_A34_ON
|
|
||||||
#define SS_A34_OFF
|
|
||||||
|
|
||||||
#define SS_B12_ON
|
|
||||||
#define SS_B12_OFF
|
|
||||||
#define SS_B34_ON
|
|
||||||
#define SS_B34_OFF
|
|
||||||
|
|
||||||
|
|
||||||
// Init Pin Functions
|
// Init Pin Functions
|
||||||
inline void initTriggerPinsInputs()
|
inline void initTriggerPinsInputs()
|
||||||
|
|||||||
@@ -1,6 +1,7 @@
|
|||||||
#include "tasks.h"
|
#include "tasks.h"
|
||||||
#include <esp_timer.h>
|
#include <esp_timer.h>
|
||||||
#include <datasave.h>
|
#include <datasave.h>
|
||||||
|
#include <mutex>
|
||||||
|
|
||||||
//// GLOBAL STATIC FUNCTIONS
|
//// GLOBAL STATIC FUNCTIONS
|
||||||
|
|
||||||
@@ -38,14 +39,14 @@ void rtIgnitionTask::rtIgnitionTask_realtime(void *pvParameters)
|
|||||||
const rtTaskIOParams rt_rst = params->rt_io; // copy to avoid external override
|
const rtTaskIOParams rt_rst = params->rt_io; // copy to avoid external override
|
||||||
QueueHandle_t rt_queue = params->rt_queue;
|
QueueHandle_t rt_queue = params->rt_queue;
|
||||||
Devices *dev = params->dev.get();
|
Devices *dev = params->dev.get();
|
||||||
ADS1256 *adc = dev->m_adc_a.get();
|
ADS1256 *adc = params->name == "rtIgnTask_A" ? dev->m_adc_a.get() : dev->m_adc_b.get();
|
||||||
PCA9555 *io = dev->m_expander_a.get();
|
std::mutex &spi_mutex = params->name == "rtIgnTask_A" ? dev->m_spi_a_mutex : dev->m_spi_b_mutex;
|
||||||
|
ExternalIO *io = dev->m_ext_io.get();
|
||||||
|
|
||||||
TaskStatus_t rt_task_info;
|
TaskStatus_t rt_task_info;
|
||||||
vTaskGetInfo(NULL, &rt_task_info, pdFALSE, eInvalid);
|
vTaskGetInfo(NULL, &rt_task_info, pdFALSE, eInvalid);
|
||||||
|
|
||||||
const auto rt_task_name = pcTaskGetName(rt_task_info.xHandle);
|
LOG_INFO("rtTask Params OK [", params->name.c_str(), "]");
|
||||||
LOG_INFO("rtTask Params OK [", rt_task_name, "]");
|
|
||||||
|
|
||||||
ignitionBoxStatus ign_box_sts;
|
ignitionBoxStatus ign_box_sts;
|
||||||
|
|
||||||
@@ -96,7 +97,7 @@ void rtIgnitionTask::rtIgnitionTask_realtime(void *pvParameters)
|
|||||||
attachInterruptArg(digitalPinToInterrupt(rt_int.spark_pin_12), rt_int.isr_ptr, (void *)&isr_params_sp12, RISING);
|
attachInterruptArg(digitalPinToInterrupt(rt_int.spark_pin_12), rt_int.isr_ptr, (void *)&isr_params_sp12, RISING);
|
||||||
attachInterruptArg(digitalPinToInterrupt(rt_int.spark_pin_34), rt_int.isr_ptr, (void *)&isr_params_sp34, RISING);
|
attachInterruptArg(digitalPinToInterrupt(rt_int.spark_pin_34), rt_int.isr_ptr, (void *)&isr_params_sp34, RISING);
|
||||||
|
|
||||||
LOG_INFO("rtTask ISR Attach OK [", rt_task_name, "]");
|
LOG_INFO("rtTask ISR Attach OK [", params->name.c_str(), "]");
|
||||||
|
|
||||||
// Global rt_task_ptr variables
|
// Global rt_task_ptr variables
|
||||||
bool first_cycle = true;
|
bool first_cycle = true;
|
||||||
@@ -234,17 +235,19 @@ void rtIgnitionTask::rtIgnitionTask_realtime(void *pvParameters)
|
|||||||
// read adc channels: pickup12, out12 [ pos + neg ]
|
// read adc channels: pickup12, out12 [ pos + neg ]
|
||||||
if (adc) // read only if adc initialized
|
if (adc) // read only if adc initialized
|
||||||
{
|
{
|
||||||
|
std::lock_guard<std::mutex> lock(spi_mutex);
|
||||||
uint32_t start_adc_read = esp_timer_get_time();
|
uint32_t start_adc_read = esp_timer_get_time();
|
||||||
// from peak detector circuits
|
// from peak detector circuits
|
||||||
ign_box_sts.coils12.peak_p_in = adcReadChannel(adc, ADC_CH_PEAK_12P_IN);
|
ign_box_sts.coils12.peak_p_in = adc->convertToVoltage(adc->cycleSingle());
|
||||||
ign_box_sts.coils12.peak_n_in = adcReadChannel(adc, ADC_CH_PEAK_12N_IN);
|
ign_box_sts.coils12.peak_n_in = adc->convertToVoltage(adc->cycleSingle());
|
||||||
ign_box_sts.coils34.peak_p_in = adcReadChannel(adc, ADC_CH_PEAK_34P_IN);
|
ign_box_sts.coils34.peak_p_in = adc->convertToVoltage(adc->cycleSingle());
|
||||||
ign_box_sts.coils34.peak_n_in = adcReadChannel(adc, ADC_CH_PEAK_34N_IN);
|
ign_box_sts.coils34.peak_n_in = adc->convertToVoltage(adc->cycleSingle());
|
||||||
ign_box_sts.coils12.peak_p_out = adcReadChannel(adc, ADC_CH_PEAK_12P_OUT);
|
ign_box_sts.coils12.peak_p_out =adc->convertToVoltage(adc->cycleSingle());
|
||||||
ign_box_sts.coils12.peak_n_out = adcReadChannel(adc, ADC_CH_PEAK_12N_OUT);
|
ign_box_sts.coils12.peak_n_out =adc->convertToVoltage(adc->cycleSingle());
|
||||||
ign_box_sts.coils34.peak_p_out = adcReadChannel(adc, ADC_CH_PEAK_34P_OUT);
|
ign_box_sts.coils34.peak_p_out =adc->convertToVoltage(adc->cycleSingle());
|
||||||
ign_box_sts.coils34.peak_n_out = adcReadChannel(adc, ADC_CH_PEAK_34N_OUT);
|
ign_box_sts.coils34.peak_n_out =adc->convertToVoltage(adc->cycleSingle());
|
||||||
ign_box_sts.adc_read_time = (int32_t)(esp_timer_get_time() - start_adc_read);
|
ign_box_sts.adc_read_time = (int32_t)(esp_timer_get_time() - start_adc_read);
|
||||||
|
adc->stopConversion();
|
||||||
}
|
}
|
||||||
else // simulate adc read timig
|
else // simulate adc read timig
|
||||||
vTaskDelay(pdMS_TO_TICKS(c_adc_time));
|
vTaskDelay(pdMS_TO_TICKS(c_adc_time));
|
||||||
@@ -253,10 +256,23 @@ void rtIgnitionTask::rtIgnitionTask_realtime(void *pvParameters)
|
|||||||
// outputs on io expander
|
// outputs on io expander
|
||||||
if (io)
|
if (io)
|
||||||
{
|
{
|
||||||
// [TODO] code to reset sample and hold and arm trigger level detectors
|
// Discharge Pulse
|
||||||
|
io->extDigitalWrite(rt_rst.sh_disch_12, true);
|
||||||
|
io->extDigitalWrite(rt_rst.sh_disch_34, true);
|
||||||
|
delayMicroseconds(250);
|
||||||
|
io->extDigitalWrite(rt_rst.sh_disch_12, false);
|
||||||
|
io->extDigitalWrite(rt_rst.sh_disch_34, false);
|
||||||
|
// Safety delay
|
||||||
|
delayMicroseconds(500);
|
||||||
|
// Re-Arm Pulse
|
||||||
|
io->extDigitalWrite(rt_rst.sh_arm_12, true);
|
||||||
|
io->extDigitalWrite(rt_rst.sh_arm_34, true);
|
||||||
|
delayMicroseconds(250);
|
||||||
|
io->extDigitalWrite(rt_rst.sh_arm_12, false);
|
||||||
|
io->extDigitalWrite(rt_rst.sh_arm_34, false);
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
vTaskDelay(pdMS_TO_TICKS(1));
|
vTaskDelay(pdMS_TO_TICKS(c_io_time));
|
||||||
|
|
||||||
// send essage to main loop with ignition info, by copy so local static variable is ok
|
// send essage to main loop with ignition info, by copy so local static variable is ok
|
||||||
if (rt_queue)
|
if (rt_queue)
|
||||||
@@ -269,7 +285,7 @@ void rtIgnitionTask::rtIgnitionTask_realtime(void *pvParameters)
|
|||||||
}
|
}
|
||||||
// Delete the timeout timer
|
// Delete the timeout timer
|
||||||
esp_timer_delete(timeout_timer);
|
esp_timer_delete(timeout_timer);
|
||||||
LOG_WARN("rtTask Ending [", rt_task_name, "]");
|
LOG_WARN("rtTask Ending [", params->name.c_str(), "]");
|
||||||
// Ignition A Interrupts DETACH
|
// Ignition A Interrupts DETACH
|
||||||
detachInterrupt(rt_int.trig_pin_12p);
|
detachInterrupt(rt_int.trig_pin_12p);
|
||||||
detachInterrupt(rt_int.trig_pin_12n);
|
detachInterrupt(rt_int.trig_pin_12n);
|
||||||
|
|||||||
@@ -59,19 +59,19 @@ public:
|
|||||||
struct rtTaskIOParams
|
struct rtTaskIOParams
|
||||||
{
|
{
|
||||||
const uint32_t expander_addr;
|
const uint32_t expander_addr;
|
||||||
const uint8_t pot_cs_12;
|
const uint32_t pot_cs_12;
|
||||||
const uint8_t pot_cs_34;
|
const uint32_t pot_cs_34;
|
||||||
const uint8_t ss_force;
|
const uint32_t ss_force;
|
||||||
const uint8_t ss_inhibit_12;
|
const uint32_t ss_inhibit_12;
|
||||||
const uint8_t ss_inhibit_34;
|
const uint32_t ss_inhibit_34;
|
||||||
const uint8_t sh_disch_12;
|
const uint32_t sh_disch_12;
|
||||||
const uint8_t sh_disch_34;
|
const uint32_t sh_disch_34;
|
||||||
const uint8_t sh_arm_12;
|
const uint32_t sh_arm_12;
|
||||||
const uint8_t sh_arm_34;
|
const uint32_t sh_arm_34;
|
||||||
const uint8_t relay_in_12;
|
const uint32_t relay_in_12;
|
||||||
const uint8_t relay_in_34;
|
const uint32_t relay_in_34;
|
||||||
const uint8_t relay_out_12;
|
const uint32_t relay_out_12;
|
||||||
const uint8_t relay_out_34;
|
const uint32_t relay_out_34;
|
||||||
};
|
};
|
||||||
|
|
||||||
// RT task parameters
|
// RT task parameters
|
||||||
|
|||||||
@@ -22,7 +22,7 @@ build_type = release
|
|||||||
[env:esp32-devtest-debug]
|
[env:esp32-devtest-debug]
|
||||||
board = esp32dev
|
board = esp32dev
|
||||||
platform = https://github.com/pioarduino/platform-espressif32/releases/download/stable/platform-espressif32.zip
|
platform = https://github.com/pioarduino/platform-espressif32/releases/download/stable/platform-espressif32.zip
|
||||||
|
framework = arduino
|
||||||
lib_deps =
|
lib_deps =
|
||||||
hideakitai/DebugLog@^0.8.4
|
hideakitai/DebugLog@^0.8.4
|
||||||
board_build.flash_size = 4MB
|
board_build.flash_size = 4MB
|
||||||
|
|||||||
12
RotaxMonitorTester/src/colors.h
Normal file
12
RotaxMonitorTester/src/colors.h
Normal file
@@ -0,0 +1,12 @@
|
|||||||
|
#pragma once
|
||||||
|
|
||||||
|
// ANSI colors
|
||||||
|
#define COLOR_RESET "\033[0m"
|
||||||
|
#define COLOR_RED "\033[31m"
|
||||||
|
#define COLOR_GREEN "\033[32m"
|
||||||
|
#define COLOR_BLUE "\033[34m"
|
||||||
|
#define COLOR_MAGENTA "\033[35m"
|
||||||
|
#define COLOR_CYAN "\033[36m"
|
||||||
|
#define COLOR_YELLOW "\033[33m"
|
||||||
|
#define COLOR_WHITE "\033[37m"
|
||||||
|
#define COLOR_LBLUE "\033[94m"
|
||||||
@@ -4,6 +4,8 @@
|
|||||||
#include <DebugLog.h>
|
#include <DebugLog.h>
|
||||||
|
|
||||||
#include "timer.h"
|
#include "timer.h"
|
||||||
|
#include "colors.h"
|
||||||
|
|
||||||
#include <map>
|
#include <map>
|
||||||
|
|
||||||
static hw_timer_t *timerA = NULL;
|
static hw_timer_t *timerA = NULL;
|
||||||
@@ -17,6 +19,12 @@ static uint32_t count = 0;
|
|||||||
#define SPARK_DLY_MIN 10
|
#define SPARK_DLY_MIN 10
|
||||||
#define SPARK_DLY_MAX 490
|
#define SPARK_DLY_MAX 490
|
||||||
|
|
||||||
|
#define COIL_PULSE_MIN 100
|
||||||
|
#define COIL_PULSE_MAX 1000
|
||||||
|
|
||||||
|
#define SPARK_PULSE_MIN 10
|
||||||
|
#define SPARK_PULSE_MAX 500
|
||||||
|
|
||||||
#define PAUSE_LONG_MIN 5000
|
#define PAUSE_LONG_MIN 5000
|
||||||
#define PAUSE_LONG_MAX PAUSE_LONG_MIN * 100
|
#define PAUSE_LONG_MAX PAUSE_LONG_MIN * 100
|
||||||
|
|
||||||
@@ -30,7 +38,8 @@ void clearScreen()
|
|||||||
Serial.flush();
|
Serial.flush();
|
||||||
}
|
}
|
||||||
|
|
||||||
static double filtered_rpm = 0;
|
static uint32_t set_rpm = 500;
|
||||||
|
static uint32_t set_delay = 100;
|
||||||
|
|
||||||
static const std::map<const uint32_t, const char *> pin2Name = {
|
static const std::map<const uint32_t, const char *> pin2Name = {
|
||||||
{PIN_TRIG_A12P, "HIGH_PIN_TRIG_A12P"},
|
{PIN_TRIG_A12P, "HIGH_PIN_TRIG_A12P"},
|
||||||
@@ -68,7 +77,7 @@ static timerStatus stsB = {
|
|||||||
.clock_period_us = (uint32_t)PERIOD_US,
|
.clock_period_us = (uint32_t)PERIOD_US,
|
||||||
.pause_long_us = 10000,
|
.pause_long_us = 10000,
|
||||||
.pause_short_us = 1000,
|
.pause_short_us = 1000,
|
||||||
.coil_pulse_us = 1000,
|
.coil_pulse_us = 500,
|
||||||
.spark_pulse_us = 100,
|
.spark_pulse_us = 100,
|
||||||
.spark_delay_us = 50,
|
.spark_delay_us = 50,
|
||||||
.pins = {
|
.pins = {
|
||||||
@@ -83,11 +92,14 @@ static timerStatus stsB = {
|
|||||||
static bool isEnabled_A = false;
|
static bool isEnabled_A = false;
|
||||||
static bool isEnabled_B = false;
|
static bool isEnabled_B = false;
|
||||||
|
|
||||||
|
static String last_command;
|
||||||
|
|
||||||
void setup()
|
void setup()
|
||||||
{
|
{
|
||||||
|
|
||||||
Serial.begin(115200);
|
Serial.begin(115200);
|
||||||
delay(1000);
|
delay(1000);
|
||||||
|
Serial.setTimeout(100);
|
||||||
LOG_ATTACH_SERIAL(Serial);
|
LOG_ATTACH_SERIAL(Serial);
|
||||||
|
|
||||||
pinMode(PIN_TRIG_A12P, OUTPUT);
|
pinMode(PIN_TRIG_A12P, OUTPUT);
|
||||||
@@ -133,63 +145,124 @@ void setup()
|
|||||||
|
|
||||||
void loop()
|
void loop()
|
||||||
{
|
{
|
||||||
LOG_INFO("Loop: ", count++);
|
clearScreen();
|
||||||
uint32_t spark_delay = (uint32_t)(map(analogRead(SPARK_DELAY_POT), 0, 4096, SPARK_DLY_MIN, SPARK_DLY_MAX) / PERIOD_US);
|
|
||||||
stsA.spark_delay_us = spark_delay * PERIOD_US;
|
|
||||||
if (stsA.spark_delay_us > (SPARK_DLY_MIN + SPARK_DLY_MAX) / 2)
|
|
||||||
{
|
|
||||||
stsA.soft_start = true;
|
|
||||||
stsA.spark_delay_us -= (SPARK_DLY_MIN + SPARK_DLY_MAX) / 2;
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
stsA.soft_start = false;
|
|
||||||
}
|
|
||||||
stsB.soft_start = stsA.soft_start;
|
|
||||||
stsB.spark_delay_us = stsA.spark_delay_us;
|
|
||||||
|
|
||||||
double new_rpm = (double)(map(analogRead(FREQ_POT), 0, 4096, RPM_MIN, RPM_MAX));
|
Serial.printf("\t++++ Loop: %u ++++\n", count++);
|
||||||
filtered_rpm = filtered_rpm + 0.1 * (new_rpm - filtered_rpm);
|
|
||||||
stsA.pause_long_us = (uint32_t)(60000000.0f / filtered_rpm / 2.0f);
|
|
||||||
stsB.pause_long_us = stsA.pause_long_us;
|
|
||||||
|
|
||||||
if (isEnabled_A)
|
if (isEnabled_A)
|
||||||
LOG_INFO("==== System A is ENABLED ====");
|
Serial.println("==== System A is" COLOR_GREEN " ENABLED" COLOR_RESET " ====");
|
||||||
else
|
else
|
||||||
LOG_INFO("==== System A is DISABLED ====");
|
Serial.println("==== System A is" COLOR_RED " DISABLED" COLOR_RESET " ====");
|
||||||
|
|
||||||
if (isEnabled_B)
|
if (isEnabled_B)
|
||||||
LOG_INFO("==== System B is ENABLED ====");
|
Serial.println("==== System B is" COLOR_GREEN " ENABLED" COLOR_RESET " ====");
|
||||||
else
|
else
|
||||||
LOG_INFO("==== System B is DISABLED ====");
|
Serial.println("==== System B is" COLOR_RED " DISABLED" COLOR_RESET " ====");
|
||||||
|
|
||||||
LOG_INFO("Spark Delay uS: ", stsA.spark_delay_us, "\tSoft Start: ", stsA.soft_start ? "TRUE" : "FALSE");
|
Serial.printf("Spark Delay uS: %u\n", stsA.spark_delay_us);
|
||||||
LOG_INFO("Engine Rpm: ", (uint32_t)(filtered_rpm));
|
Serial.printf("Soft Start: %s\n", stsA.soft_start ? "ENABLED" : "DISABLED");
|
||||||
LOG_INFO("Coil Pulse: ", stsA.coil_pulse_us, "us");
|
Serial.printf("Engine Rpm: %u\n", (uint32_t)(set_rpm));
|
||||||
LOG_INFO("Spark Pulse: ", stsA.spark_pulse_us, "us");
|
Serial.printf("Coil Pulse: %u uS\n", stsA.coil_pulse_us);
|
||||||
|
Serial.printf("Spark Pulse: %u uS\n", stsA.spark_pulse_us);
|
||||||
|
Serial.println(COLOR_CYAN "-------------------------------------");
|
||||||
|
Serial.println("E[a/b] > Enable Box a/b | D[a/b] > Disable a/b");
|
||||||
|
Serial.println("S[ddd] > Spark Delay | R[dddd] > Engine RPM");
|
||||||
|
Serial.println("C[ddd] > Spark Pulse | P[ddd] > Coil Pulse");
|
||||||
|
Serial.println("-------------------------------------" COLOR_RESET);
|
||||||
|
Serial.printf("Last Command: %s\n", last_command.c_str());
|
||||||
|
|
||||||
if (digitalRead(ENABLE_PIN_A) == LOW && !isEnabled_A)
|
auto str = Serial.readStringUntil('\n');
|
||||||
|
if (!str.isEmpty())
|
||||||
{
|
{
|
||||||
timerStart(timerA);
|
last_command = str;
|
||||||
isEnabled_A = true;
|
const auto cmd = str.charAt(0);
|
||||||
}
|
char c;
|
||||||
else if (digitalRead(ENABLE_PIN_A) == HIGH && isEnabled_A)
|
switch (cmd)
|
||||||
{
|
{
|
||||||
timerStop(timerA);
|
case 'E':
|
||||||
isEnabled_A = false;
|
{
|
||||||
|
char box;
|
||||||
|
sscanf(str.c_str(), "%c%c\n", &c, &box);
|
||||||
|
if (box == 'a' && !isEnabled_A)
|
||||||
|
{
|
||||||
|
timerStart(timerA);
|
||||||
|
isEnabled_A = true;
|
||||||
|
}
|
||||||
|
else if (box == 'b' && !isEnabled_B)
|
||||||
|
{
|
||||||
|
timerStart(timerB);
|
||||||
|
isEnabled_B = true;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case 'D':
|
||||||
|
{
|
||||||
|
char c;
|
||||||
|
char box;
|
||||||
|
sscanf(str.c_str(), "%c%c\n", &c, &box);
|
||||||
|
if (box == 'a' && isEnabled_A)
|
||||||
|
{
|
||||||
|
timerStop(timerA);
|
||||||
|
isEnabled_A = false;
|
||||||
|
}
|
||||||
|
else if (box == 'b' && isEnabled_B)
|
||||||
|
{
|
||||||
|
timerStop(timerB);
|
||||||
|
isEnabled_B = false;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case 'R':
|
||||||
|
{
|
||||||
|
int new_rpm;
|
||||||
|
sscanf(str.c_str(), "%c%d\n", &c, &new_rpm);
|
||||||
|
new_rpm = min(RPM_MAX, max(RPM_MIN, new_rpm));
|
||||||
|
stsA.pause_long_us = (uint32_t)(60000000.0f / (float)new_rpm / 2.0f);
|
||||||
|
stsB.pause_long_us = stsA.pause_long_us;
|
||||||
|
set_rpm = (uint32_t)new_rpm;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case 'S':
|
||||||
|
{
|
||||||
|
int new_delay;
|
||||||
|
sscanf(str.c_str(), "%c%d\n", &c, &new_delay);
|
||||||
|
new_delay = min(SPARK_DLY_MAX, max(SPARK_DLY_MIN, new_delay));
|
||||||
|
stsA.spark_delay_us = (uint32_t)(new_delay);
|
||||||
|
if (stsA.spark_delay_us > (SPARK_DLY_MIN + SPARK_DLY_MAX) / 2)
|
||||||
|
{
|
||||||
|
stsA.soft_start = true;
|
||||||
|
stsA.spark_delay_us -= (SPARK_DLY_MIN + SPARK_DLY_MAX) / 2;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
stsA.soft_start = false;
|
||||||
|
}
|
||||||
|
stsB.soft_start = stsA.soft_start;
|
||||||
|
stsB.spark_delay_us = stsA.spark_delay_us;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case 'P':
|
||||||
|
{
|
||||||
|
int new_pulse;
|
||||||
|
sscanf(str.c_str(), "%c%d\n", &c, &new_pulse);
|
||||||
|
new_pulse = min(COIL_PULSE_MAX, max(COIL_PULSE_MIN, new_pulse));
|
||||||
|
stsA.coil_pulse_us = stsB.coil_pulse_us = (uint32_t)new_pulse;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case 'C':
|
||||||
|
{
|
||||||
|
int new_pulse;
|
||||||
|
sscanf(str.c_str(), "%c%d\n", &c, &new_pulse);
|
||||||
|
new_pulse = min(SPARK_PULSE_MAX, max(SPARK_PULSE_MIN, new_pulse));
|
||||||
|
stsA.spark_pulse_us = stsB.spark_pulse_us = (uint32_t)new_pulse;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
Serial.read();
|
||||||
}
|
}
|
||||||
|
|
||||||
if (digitalRead(ENABLE_PIN_B) == LOW && !isEnabled_B)
|
str.clear();
|
||||||
{
|
delay(1000);
|
||||||
timerStart(timerB);
|
|
||||||
isEnabled_B = true;
|
|
||||||
}
|
|
||||||
else if (digitalRead(ENABLE_PIN_B) == HIGH && isEnabled_B)
|
|
||||||
{
|
|
||||||
timerStop(timerB);
|
|
||||||
isEnabled_B = false;
|
|
||||||
}
|
|
||||||
|
|
||||||
delay(100);
|
|
||||||
clearScreen();
|
|
||||||
}
|
}
|
||||||
|
|||||||
Reference in New Issue
Block a user