diff --git a/.gitmodules b/.gitmodules index ae4a93c..270b1b9 100644 --- a/.gitmodules +++ b/.gitmodules @@ -128,12 +128,9 @@ [submodule "test/external/googletest"] path = test/external/googletest url = https://github.com/google/googletest.git -[submodule "test/external/fff"] - path = test/external/fff - url = https://github.com/meekrosoft/fff.git [submodule "lib/FlightControl-platform-dependencies"] path = lib/FlightControl-platform-dependencies - url = https://github.com/gemsiot/FlightControl-platform-dependencies + url = https://github.com/RTGS-Lab/FlightControl-platform-dependencies.git [submodule "lib/FlightControl-hardware-dependencies"] path = lib/FlightControl-hardware-dependencies - url = https://github.com/gemsiot/FlightControl-hardware-dependencies + url = https://github.com/RTGS-Lab/FlightControl-hardware-dependencies diff --git a/lib/Driver_-_Kestrel b/lib/Driver_-_Kestrel index 3591e84..6ee4e49 160000 --- a/lib/Driver_-_Kestrel +++ b/lib/Driver_-_Kestrel @@ -1 +1 @@ -Subproject commit 3591e84f206a1f09ebe7635247c32d3427809086 +Subproject commit 6ee4e491ed35d5edfee389d9641acc1ffe85bead diff --git a/lib/Driver_-_Li710 b/lib/Driver_-_Li710 index d5616c6..d069e84 160000 --- a/lib/Driver_-_Li710 +++ b/lib/Driver_-_Li710 @@ -1 +1 @@ -Subproject commit d5616c60261d93517faf6d8b580ec932b9185ef2 +Subproject commit d069e84a7a34cfcd93b190f0911cd94ebe521e70 diff --git a/lib/Driver_-_Sensor b/lib/Driver_-_Sensor index afef963..f3cf454 160000 --- a/lib/Driver_-_Sensor +++ b/lib/Driver_-_Sensor @@ -1 +1 @@ -Subproject commit afef96338232e397656a907ce12338a4c9cad288 +Subproject commit f3cf4548da02ee763da53837507083c3843f9162 diff --git a/lib/FlightControl-hardware-dependencies b/lib/FlightControl-hardware-dependencies index 1fec360..71518ce 160000 --- a/lib/FlightControl-hardware-dependencies +++ b/lib/FlightControl-hardware-dependencies @@ -1 +1 @@ -Subproject commit 1fec36002d6e53980f6091d81b1e466944b55345 +Subproject commit 71518ce14301a13934eb9d9159ca375887c4caaa diff --git a/lib/FlightControl-platform-dependencies b/lib/FlightControl-platform-dependencies index 183167f..8844b22 160000 --- a/lib/FlightControl-platform-dependencies +++ b/lib/FlightControl-platform-dependencies @@ -1 +1 @@ -Subproject commit 183167f55afbe499f67b8ad22292a9c12602bdc6 +Subproject commit 8844b2280ec01d1398ae6ddc4783f2091f8ff210 diff --git a/lib/PCAL9535A_Library b/lib/PCAL9535A_Library index b922cdf..a18f31f 160000 --- a/lib/PCAL9535A_Library +++ b/lib/PCAL9535A_Library @@ -1 +1 @@ -Subproject commit b922cdf198f93788c9ac4454a98640972e74ff1e +Subproject commit a18f31f866447159b6ac7189299f4073dc37a625 diff --git a/src/FlightControl_Demo.cpp b/src/FlightControl_Demo.cpp index b9085d5..b09877e 100644 --- a/src/FlightControl_Demo.cpp +++ b/src/FlightControl_Demo.cpp @@ -59,8 +59,23 @@ int configurePowerSave(int desiredPowerSaveMode); #include #include -#include "hardware/SDI12TalonAdapter.h" #include "platform/ParticleTimeProvider.h" +#include "platform/ParticleGpio.h" +#include "platform/ParticleSystem.h" +#include "platform/ParticleWire.h" +#include "platform/ParticleCloud.h" +#include "platform/ParticleSerial.h" + +#include "hardware/IOExpanderPCAL9535A.h" +#include "hardware/SDI12TalonAdapter.h" +#include "hardware/CurrentSenseAmplifierPAC1934.h" +#include "hardware/LedPCA9634.h" +#include "hardware/RtcMCP79412.h" +#include "hardware/AmbientLightVEML3328.h" +#include "hardware/GpsSFE_UBLOX_GNSS.h" +#include "hardware/HumidityTemperatureAdafruit_SHT4X.h" +#include "hardware/AccelerometerMXC6655.h" +#include "hardware/AccelerometerBMA456.h" const String firmwareVersion = "2.9.11"; const String schemaVersion = "2.2.9"; @@ -70,16 +85,53 @@ const unsigned long indicatorTimeout = 60000; //Wait for up to 1 minute with ind const uint64_t balancedDiagnosticPeriod = 3600000; //Report diagnostics once an hour //DEBUG! int powerSaveMode = 0; //Default to 0, update when configure power save mode is called -Kestrel logger(true); +ParticleTimeProvider realTimeProvider; +ParticleGpio realGpio; +ParticleSystem realSystem; +ParticleWire realWire; +ParticleCloud realCloud; +ParticleUSBSerial realSerialDebug; +ParticleHardwareSerial realSerialSdi12; + +IOExpanderPCAL9535A realIoOB(0x20); //0x20 is the PCAL Base address +IOExpanderPCAL9535A realIoTalon(0x21); +CurrentSenseAmplifierPAC1934 realCsaAlpha(2,2,2,2,0x18); +CurrentSenseAmplifierPAC1934 realCsaBeta(2,10,10,10,0x14); +LedPCA9634 realLed(0x52); +RtcMCP79412 realRtc; +AmbientLightVEML3328 realAls; +GpsSFE_UBLOX_GNSS realGps; +HumidityTemperatureAdafruit_SHT4X realTempHumidity; +AccelerometerMXC6655 realAccel; +AccelerometerBMA456 realBackupAccel; + +Kestrel logger(realTimeProvider, + realGpio, + realSystem, + realWire, + realCloud, + realSerialDebug, + realSerialSdi12, + realIoOB, + realIoTalon, + realCsaAlpha, + realCsaBeta, + realLed, + realRtc, + realAls, + realGps, + realTempHumidity, + realAccel, + realBackupAccel, + true); KestrelFileHandler fileSys(logger); Gonk battery(5); //Instantiate with defaults, manually set to port 5 AuxTalon aux(0, 0x14); //Instantiate AUX talon with deaults - null port and hardware v1.4 I2CTalon i2c(0, 0x21); //Instantiate I2C talon with alt - null port and hardware v2.1 SDI12Talon sdi12(0, 0x14); //Instantiate SDI12 talon with alt - null port and hardware v1.4 -PCAL9535A ioAlpha(0x20); -PCAL9535A ioBeta(0x21); SDI12TalonAdapter realSdi12(sdi12); -ParticleTimeProvider realTimeProvider; +IOExpanderPCAL9535A ioAlpha(0x20); +IOExpanderPCAL9535A ioBeta(0x21); String globalNodeID = ""; //Store current node ID @@ -122,7 +174,7 @@ Hedorah gas(0, 0, 0x10); //Instantiate CO2 sensor with default ports and v1.0 ha LI710 et(realTimeProvider, realSdi12, 0, 0); //Instantiate ET sensor with default ports and unknown version, pass over SDI12 Talon interface BaroVue10 campPressure(sdi12, 0, 0x00); // Instantiate Barovue10 with default ports and v0.0 hardware -const uint8_t numSensors = 7; //Number must match the number of objects defined in `sensors` array +const uint8_t numSensors = 8; //Number must match the number of objects defined in `sensors` array Sensor* const sensors[numSensors] = { &fileSys, @@ -131,8 +183,8 @@ Sensor* const sensors[numSensors] = { &sdi12, &battery, &logger, //Add sensors after this line - &et - // &haar, + &et, + &haar // &soil1, // &apogeeSolar, @@ -289,13 +341,13 @@ void setup() { // fileSys.writeToSD(initDiagnostic, "Dummy.txt"); #ifndef RAPID_START //Only do this if not rapid starting - while((!Particle.connected() || logger.gps.getFixType() == 0) && (millis() - startTime) < maxConnectTime) { //Wait while at least one of the remote systems is not connected + while((!Particle.connected() || logger.m_gps.getFixType() == 0) && (millis() - startTime) < maxConnectTime) { //Wait while at least one of the remote systems is not connected if(Particle.connected()) { logger.setIndicatorState(IndicatorLight::CELL, IndicatorMode::PASS); //If cell is connected, set to PASS state if(WAIT_GPS == false) break; //If not told to wait for GPS, break out after cell is connected } - if(logger.gps.getTimeValid() == true) { - if(logger.gps.getFixType() >= 2 && logger.gps.getFixType() <= 4 && logger.gps.getGnssFixOk()) { //If you get a 2D fix or better, pass GPS + if(logger.m_gps.getTimeValid() == true) { + if(logger.m_gps.getFixType() >= 2 && logger.m_gps.getFixType() <= 4 && logger.m_gps.getGnssFixOk()) { //If you get a 2D fix or better, pass GPS logger.setIndicatorState(IndicatorLight::GPS, IndicatorMode::PASS); } else { @@ -312,7 +364,7 @@ void setup() { logger.setIndicatorState(IndicatorLight::CELL, IndicatorMode::ERROR); //If cell still not connected, display error // Particle.disconnect(); //DEBUG! } - if(logger.gps.getFixType() >= 2 && logger.gps.getFixType() <= 4 && logger.gps.getGnssFixOk()) { //Make fix report is in range and fix is OK + if(logger.m_gps.getFixType() >= 2 && logger.m_gps.getFixType() <= 4 && logger.m_gps.getGnssFixOk()) { //Make fix report is in range and fix is OK logger.setIndicatorState(IndicatorLight::GPS, IndicatorMode::PASS); //Catches connection of GPS is second device to connect } else { diff --git a/src/hardware/AccelerometerBMA456.cpp b/src/hardware/AccelerometerBMA456.cpp new file mode 100644 index 0000000..9595575 --- /dev/null +++ b/src/hardware/AccelerometerBMA456.cpp @@ -0,0 +1,52 @@ +/** + * @file AccelerometerBMA456.cpp + * @brief Implementation of the AccelerometerBMA456 class. + * + * © 2025 Regents of the University of Minnesota. All rights reserved. + */ + + #include "AccelerometerBMA456.h" + + AccelerometerBMA456::AccelerometerBMA456() : accel() { + // Default constructor, nothing to initialize here + } + + int AccelerometerBMA456::begin() { + return accel.begin(); + } + + float AccelerometerBMA456::getAccel(uint8_t axis, uint8_t range) { + float x, y, z; + accel.getAcceleration(&x, &y, &z); + switch(axis) + { + case 0: + return x; + case 1: + return y; + case 2: + return z; + default: + return x; + } + } + + int AccelerometerBMA456::updateAccelAll() { + accel.initialize(); + return 0; + } + + float AccelerometerBMA456::getTemp() { + return accel.getTemperature(); + } + + float* AccelerometerBMA456::getData() { //unimplemented + return 0; + } + + float* AccelerometerBMA456::getOffset() { //unimplemented + return 0; + } + + void AccelerometerBMA456::setOffset(float offsetX, float offsetY, float offsetZ) { //unimplemented + } \ No newline at end of file diff --git a/src/hardware/AccelerometerBMA456.h b/src/hardware/AccelerometerBMA456.h new file mode 100644 index 0000000..9f11c4c --- /dev/null +++ b/src/hardware/AccelerometerBMA456.h @@ -0,0 +1,40 @@ +/** + * @file AccelerometerBMA456.h + * @brief Concrete implementation of IAccelerometer using BMA456 + * + * Adapts the BMA456 accelerometer to the IAccelerometer interface + * for dependency injection and testing. + * + * © 2025 Regents of the University of Minnesota. All rights reserved. + */ + + #ifndef ACCELEROMETER_BMA456_H + #define ACCELEROMETER_BMA456_H + + #include "IAccelerometer.h" + #include "arduino_bma456.h" + + /** + * @brief Concrete implementation of IAccelerometer using BMA456 + */ + class AccelerometerBMA456 : public IAccelerometer { + public: + /** + * @brief Constructor + */ + AccelerometerBMA456(); + ~AccelerometerBMA456() override = default; + + int begin() override; + float getAccel(uint8_t axis, uint8_t range = 0) override; + int updateAccelAll() override; + float getTemp() override; + float* getData() override; + float* getOffset() override; + void setOffset(float offsetX, float offsetY, float offsetZ) override; + + private: + BMA456 accel; // The concrete BMA456 instance + }; + + #endif // ACCELEROMETER_BMA456_H \ No newline at end of file diff --git a/src/hardware/AccelerometerMXC6655.cpp b/src/hardware/AccelerometerMXC6655.cpp new file mode 100644 index 0000000..83a5107 --- /dev/null +++ b/src/hardware/AccelerometerMXC6655.cpp @@ -0,0 +1,42 @@ +/** + * @file AccelerometerMXC6655.cpp + * @brief Implementation of the AccelerometerMXC6655 class. + * + * © 2025 Regents of the University of Minnesota. All rights reserved. + */ + + #include "AccelerometerMXC6655.h" + + AccelerometerMXC6655::AccelerometerMXC6655() : accel() { + // Default constructor, nothing to initialize here + } + + int AccelerometerMXC6655::begin() { + return accel.begin(); + } + + float AccelerometerMXC6655::getAccel(uint8_t axis, uint8_t range) { + return accel.getAccel(axis, range); + } + + int AccelerometerMXC6655::updateAccelAll() { + return accel.updateAccelAll(); + } + + float AccelerometerMXC6655::getTemp() { + return accel.getTemp(); + } + + float* AccelerometerMXC6655::getData() { + return accel.data; + } + + float* AccelerometerMXC6655::getOffset() { + return accel.offset; + } + + void AccelerometerMXC6655::setOffset(float offsetX, float offsetY, float offsetZ) { + accel.offset[0] = offsetX; + accel.offset[1] = offsetY; + accel.offset[2] = offsetZ; + } \ No newline at end of file diff --git a/src/hardware/AccelerometerMXC6655.h b/src/hardware/AccelerometerMXC6655.h new file mode 100644 index 0000000..d50aaf5 --- /dev/null +++ b/src/hardware/AccelerometerMXC6655.h @@ -0,0 +1,40 @@ +/** + * @file AccelerometerMXC6655.h + * @brief Concrete implementation of IAccelerometer using MXC6655 + * + * Adapts the MXC6655 accelerometer to the IAccelerometer interface + * for dependency injection and testing. + * + * © 2025 Regents of the University of Minnesota. All rights reserved. + */ + + #ifndef ACCELEROMETER_MXC6655_H + #define ACCELEROMETER_MXC6655_H + + #include "IAccelerometer.h" + #include "MXC6655.h" + + /** + * @brief Concrete implementation of IAccelerometer using MXC6655 + */ + class AccelerometerMXC6655 : public IAccelerometer { + public: + /** + * @brief Constructor + */ + AccelerometerMXC6655(); + ~AccelerometerMXC6655() override = default; + + int begin() override; + float getAccel(uint8_t axis, uint8_t range = 0) override; + int updateAccelAll() override; + float getTemp() override; + float* getData() override; + float* getOffset() override; + void setOffset(float offsetX, float offsetY, float offsetZ) override; + + private: + MXC6655 accel; // The concrete MXC6655 instance + }; + + #endif // ACCELEROMETER_MXC6655_H \ No newline at end of file diff --git a/src/hardware/AmbientLightVEML3328.cpp b/src/hardware/AmbientLightVEML3328.cpp new file mode 100644 index 0000000..e238d60 --- /dev/null +++ b/src/hardware/AmbientLightVEML3328.cpp @@ -0,0 +1,80 @@ +/** + * @file AmbientLightVEML3328.cpp + * @brief Implementation of the AmbientLightVEML3328 class. + * + * © 2025 Regents of the University of Minnesota. All rights reserved. + */ + + #include "AmbientLightVEML3328.h" + + AmbientLightVEML3328::AmbientLightVEML3328() : veml() { + // Default constructor, delegates to VEML3328 constructor + } + + int AmbientLightVEML3328::begin() { + return veml.begin(); + } + + float AmbientLightVEML3328::getValue(Channel channel) { + // Map from IAmbientLight::Channel to VEML3328::Channel + VEML3328::Channel vemlChannel; + switch (channel) { + case Channel::Clear: + vemlChannel = VEML3328::Channel::Clear; + break; + case Channel::Red: + vemlChannel = VEML3328::Channel::Red; + break; + case Channel::Green: + vemlChannel = VEML3328::Channel::Green; + break; + case Channel::Blue: + vemlChannel = VEML3328::Channel::Blue; + break; + case Channel::IR: + vemlChannel = VEML3328::Channel::IR; + break; + default: + // Default to Clear if invalid channel + vemlChannel = VEML3328::Channel::Clear; + break; + } + + return veml.GetValue(vemlChannel); + } + + float AmbientLightVEML3328::getValue(Channel channel, bool &state) { + // Map from IAmbientLight::Channel to VEML3328::Channel + VEML3328::Channel vemlChannel; + switch (channel) { + case Channel::Clear: + vemlChannel = VEML3328::Channel::Clear; + break; + case Channel::Red: + vemlChannel = VEML3328::Channel::Red; + break; + case Channel::Green: + vemlChannel = VEML3328::Channel::Green; + break; + case Channel::Blue: + vemlChannel = VEML3328::Channel::Blue; + break; + case Channel::IR: + vemlChannel = VEML3328::Channel::IR; + break; + default: + // Default to Clear if invalid channel + vemlChannel = VEML3328::Channel::Clear; + break; + } + + return veml.GetValue(vemlChannel, state); + } + + float AmbientLightVEML3328::getLux() { + return veml.GetLux(); + } + + int AmbientLightVEML3328::autoRange() { + return veml.AutoRange(); + } \ No newline at end of file diff --git a/src/hardware/AmbientLightVEML3328.h b/src/hardware/AmbientLightVEML3328.h new file mode 100644 index 0000000..3318739 --- /dev/null +++ b/src/hardware/AmbientLightVEML3328.h @@ -0,0 +1,35 @@ +/** + * @file AmbientLightVEML3328.h + * @brief Concrete implementation of IAmbientLight using VEML3328 + * + * Adapts the VEML3328 ambient light sensor to the IAmbientLight interface + * for dependency injection and testing. + * + * © 2025 Regents of the University of Minnesota. All rights reserved. + */ + + #ifndef AMBIENT_LIGHT_VEML3328_H + #define AMBIENT_LIGHT_VEML3328_H + + #include "IAmbientLight.h" + #include "VEML3328.h" // Include the actual VEML3328 library + + /** + * @brief Concrete implementation of IAmbientLight using VEML3328 + */ + class AmbientLightVEML3328 : public IAmbientLight { + public: + AmbientLightVEML3328(); + ~AmbientLightVEML3328() override = default; + + int begin() override; + float getValue(Channel channel) override; + float getValue(Channel channel, bool &state) override; + float getLux() override; + int autoRange() override; + + private: + VEML3328 veml; // The concrete VEML3328 instance + }; + + #endif // AMBIENT_LIGHT_VEML3328_H \ No newline at end of file diff --git a/src/hardware/CurrentSenseAmplifierPAC1934.cpp b/src/hardware/CurrentSenseAmplifierPAC1934.cpp new file mode 100644 index 0000000..943f887 --- /dev/null +++ b/src/hardware/CurrentSenseAmplifierPAC1934.cpp @@ -0,0 +1,101 @@ +// src/hardware/CurrentSenseAmplifierPAC1934.cpp + +#include "CurrentSenseAmplifierPAC1934.h" + +CurrentSenseAmplifierPAC1934::CurrentSenseAmplifierPAC1934(float r1, float r2, float r3, float r4, uint8_t addr) + : pac1934(r1, r2, r3, r4, addr) { + // Constructor delegates to PAC1934 constructor +} + +bool CurrentSenseAmplifierPAC1934::begin() { + return pac1934.begin(); +} + +bool CurrentSenseAmplifierPAC1934::setAddress(uint8_t addr) { + return pac1934.setAddress(addr); +} + +bool CurrentSenseAmplifierPAC1934::enableChannel(uint8_t channel, bool state) { + return pac1934.enableChannel(channel, state); +} + +bool CurrentSenseAmplifierPAC1934::setFrequency(uint16_t frequency) { + // Map the uint16_t frequency to the PAC1934 Frequency enum + Frequency freq; + switch (frequency) { + case 8: + freq = SPS_8; + break; + case 64: + freq = SPS_64; + break; + case 256: + freq = SPS_256; + break; + case 1024: + default: + freq = SPS_1024; + break; + } + return pac1934.setFrequency(freq); +} + +int CurrentSenseAmplifierPAC1934::getFrequency() { + return pac1934.getFrequency(); +} + +void CurrentSenseAmplifierPAC1934::setVoltageDirection(uint8_t channel, bool bidirectional) { + pac1934.setVoltageDirection(channel, bidirectional); +} + +void CurrentSenseAmplifierPAC1934::setCurrentDirection(uint8_t channel, bool bidirectional) { + pac1934.setCurrentDirection(channel, bidirectional); +} + +bool CurrentSenseAmplifierPAC1934::getVoltageDirection(uint8_t channel) { + return pac1934.getVoltageDirection(channel); +} + +bool CurrentSenseAmplifierPAC1934::getCurrentDirection(uint8_t channel) { + return pac1934.getCurrentDirection(channel); +} + +float CurrentSenseAmplifierPAC1934::getBusVoltage(uint8_t channel, bool average, bool& status) { + return pac1934.getBusVoltage(channel, average, status); +} + +float CurrentSenseAmplifierPAC1934::getBusVoltage(uint8_t channel, bool average) { + return pac1934.getBusVoltage(channel, average); +} + +float CurrentSenseAmplifierPAC1934::getSenseVoltage(uint8_t channel, bool average, bool& status) { + return pac1934.getSenseVoltage(channel, average, status); +} + +float CurrentSenseAmplifierPAC1934::getSenseVoltage(uint8_t channel, bool average) { + return pac1934.getSenseVoltage(channel, average); +} + +float CurrentSenseAmplifierPAC1934::getCurrent(uint8_t channel, bool average, bool& status) { + return pac1934.getCurrent(channel, average, status); +} + +float CurrentSenseAmplifierPAC1934::getCurrent(uint8_t channel, bool average) { + return pac1934.getCurrent(channel, average); +} + +float CurrentSenseAmplifierPAC1934::getPowerAvg(uint8_t channel, bool& status) { + return pac1934.getPowerAvg(channel, status); +} + +float CurrentSenseAmplifierPAC1934::getPowerAvg(uint8_t channel) { + return pac1934.getPowerAvg(channel); +} + +uint8_t CurrentSenseAmplifierPAC1934::update(uint8_t clear) { + return pac1934.update(clear); +} + +bool CurrentSenseAmplifierPAC1934::testOverflow() { + return pac1934.testOverflow(); +} \ No newline at end of file diff --git a/src/hardware/CurrentSenseAmplifierPAC1934.h b/src/hardware/CurrentSenseAmplifierPAC1934.h new file mode 100644 index 0000000..d4cbb65 --- /dev/null +++ b/src/hardware/CurrentSenseAmplifierPAC1934.h @@ -0,0 +1,59 @@ +// src/hardware/CurrentSenseAmplifierPAC1934.h + +#ifndef CURRENT_SENSE_AMPLIFIER_PAC1934_H +#define CURRENT_SENSE_AMPLIFIER_PAC1934_H + +#include "ICurrentSenseAmplifier.h" +#include "PAC1934.h" // Include the driver header + +/** + * @brief Concrete implementation of ICurrentSenseAmplifier using PAC1934 + * + * Adapts the PAC1934 current sense amplifier driver to the ICurrentSenseAmplifier interface + * for dependency injection and testing. + */ +class CurrentSenseAmplifierPAC1934 : public ICurrentSenseAmplifier { +public: + /** + * @brief Constructor + * @param r1 Channel 1 sense resistor value in milliohms + * @param r2 Channel 2 sense resistor value in milliohms + * @param r3 Channel 3 sense resistor value in milliohms + * @param r4 Channel 4 sense resistor value in milliohms + * @param addr I2C address of the PAC1934 chip + */ + CurrentSenseAmplifierPAC1934(float r1 = 0, float r2 = 0, float r3 = 0, float r4 = 0, uint8_t addr = 0x18); + ~CurrentSenseAmplifierPAC1934() override = default; + + // Configuration methods + bool begin() override; + bool setAddress(uint8_t addr) override; + bool enableChannel(uint8_t channel, bool state) override; + bool setFrequency(uint16_t frequency) override; + int getFrequency() override; + + // Measurement direction + void setVoltageDirection(uint8_t channel, bool bidirectional) override; + void setCurrentDirection(uint8_t channel, bool bidirectional) override; + bool getVoltageDirection(uint8_t channel) override; + bool getCurrentDirection(uint8_t channel) override; + + // Measurement methods + float getBusVoltage(uint8_t channel, bool average, bool& status) override; + float getBusVoltage(uint8_t channel, bool average = false) override; + float getSenseVoltage(uint8_t channel, bool average, bool& status) override; + float getSenseVoltage(uint8_t channel, bool average = false) override; + float getCurrent(uint8_t channel, bool average, bool& status) override; + float getCurrent(uint8_t channel, bool average = false) override; + float getPowerAvg(uint8_t channel, bool& status) override; + float getPowerAvg(uint8_t channel) override; + + // Status and control + uint8_t update(uint8_t clear = 0) override; + bool testOverflow() override; + +private: + PAC1934 pac1934; // The underlying PAC1934 driver instance +}; + +#endif // CURRENT_SENSE_AMPLIFIER_PAC1934_H \ No newline at end of file diff --git a/src/hardware/GpsSFE_UBLOX_GNSS.cpp b/src/hardware/GpsSFE_UBLOX_GNSS.cpp new file mode 100644 index 0000000..ab71b73 --- /dev/null +++ b/src/hardware/GpsSFE_UBLOX_GNSS.cpp @@ -0,0 +1,173 @@ +/** + * @file GpsSFE_UBLOX_GNSS.cpp + * @brief Implementation of GpsSFE_UBLOX_GNSS class + * + * © 2025 Regents of the University of Minnesota. All rights reserved. + */ + +#include "GpsSFE_UBLOX_GNSS.h" + +GpsSFE_UBLOX_GNSS::GpsSFE_UBLOX_GNSS() : gps(){ + //default constructor +} + +bool GpsSFE_UBLOX_GNSS::begin() { + return gps.begin(); +} + +void GpsSFE_UBLOX_GNSS::setI2COutput(uint8_t comType) { + gps.setI2COutput(comType); +} + +bool GpsSFE_UBLOX_GNSS::setNavigationFrequency(uint8_t navFreq) { + return gps.setNavigationFrequency(navFreq); +} + +void GpsSFE_UBLOX_GNSS::setAutoPVT(bool autoPVT) { + gps.setAutoPVT(autoPVT); +} + +uint8_t GpsSFE_UBLOX_GNSS::getNavigationFrequency() { + return gps.getNavigationFrequency(); +} + +uint8_t GpsSFE_UBLOX_GNSS::getMeasurementRate() { + return gps.getMeasurementRate(); +} + +uint8_t GpsSFE_UBLOX_GNSS::getNavigationRate() { + return gps.getNavigationRate(); +} + +int16_t GpsSFE_UBLOX_GNSS::getATTroll() { + return gps.getATTroll(); +} + +int16_t GpsSFE_UBLOX_GNSS::getATTpitch() { + return gps.getATTpitch(); +} + +int16_t GpsSFE_UBLOX_GNSS::getATTheading() { + return gps.getATTheading(); +} + +void GpsSFE_UBLOX_GNSS::setPacketCfgPayloadSize(uint16_t payloadSize) { + gps.setPacketCfgPayloadSize(payloadSize); +} + +uint8_t GpsSFE_UBLOX_GNSS::getSIV() { + return gps.getSIV(); +} + +uint8_t GpsSFE_UBLOX_GNSS::getFixType() { + return gps.getFixType(); +} + +bool GpsSFE_UBLOX_GNSS::getPVT() { + return gps.getPVT(); +} + +bool GpsSFE_UBLOX_GNSS::getGnssFixOk() { + return gps.getGnssFixOk(); +} + +long GpsSFE_UBLOX_GNSS::getAltitude() { + return gps.getAltitude(); +} + +long GpsSFE_UBLOX_GNSS::getLongitude() { + return gps.getLongitude(); +} + +long GpsSFE_UBLOX_GNSS::getLatitude() { + return gps.getLatitude(); +} + +uint8_t GpsSFE_UBLOX_GNSS::getHour() { + return gps.getHour(); +} + +uint8_t GpsSFE_UBLOX_GNSS::getMinute() { + return gps.getMinute(); +} + +uint8_t GpsSFE_UBLOX_GNSS::getSecond() { + return gps.getSecond(); +} + +bool GpsSFE_UBLOX_GNSS::getDateValid() { + return gps.getDateValid(); +} + +bool GpsSFE_UBLOX_GNSS::getTimeValid() { + return gps.getTimeValid(); +} + +bool GpsSFE_UBLOX_GNSS::getTimeFullyResolved() { + return gps.getTimeFullyResolved(); +} + +bool GpsSFE_UBLOX_GNSS::powerOffWithInterrupt(uint32_t durationInMs, uint32_t wakeupSources, bool forceWhileUsb /*= true*/) { + // Directly call the underlying library function with the provided arguments. + // The SFE library function has a 'maxWait' parameter which we can use a default for here, + // or you could add it to the interface if needed. Using default for now. + // Note: The SFE library uses defaultMaxWait (often 1100ms) + return gps.powerOffWithInterrupt(durationInMs, wakeupSources, forceWhileUsb); // Pass arguments directly +} + +Isfe_ublox_status_e GpsSFE_UBLOX_GNSS::sendCommand(IUbxPacket *outgoingUBX, uint16_t maxWait) { + + if (outgoingUBX == nullptr) { + return INVALID_ARG; // Or another appropriate error status + } + + // 1. Create a temporary ubxPacket structure compatible with the SFE library + ubxPacket internalPacket; + + // 2. Copy the essential fields from the interface packet (IUbxPacket) + // to the internal packet (ubxPacket). + internalPacket.cls = outgoingUBX->cls; + internalPacket.id = outgoingUBX->id; + internalPacket.len = outgoingUBX->len; + internalPacket.payload = outgoingUBX->payload; // Share the payload pointer + + // These fields are typically managed by the SFE library during sending (checksum) + // or receiving (counter, startingSpot, validity flags), so initialize reasonably. + internalPacket.counter = 0; + internalPacket.startingSpot = 0; + internalPacket.checksumA = 0; // Will be calculated by gps.sendCommand() + internalPacket.checksumB = 0; // Will be calculated by gps.sendCommand() + internalPacket.valid = SFE_UBLOX_PACKET_VALIDITY_NOT_DEFINED; // Status set upon reception if used + internalPacket.classAndIDmatch = SFE_UBLOX_PACKET_VALIDITY_NOT_DEFINED; // Status set upon reception if used + + // 3. Call the underlying SFE library's sendCommand function, passing the address + // of the temporary internalPacket. + sfe_ublox_status_e status = gps.sendCommand(&internalPacket, maxWait); + + // 4. Translate the SFE library's status enum (sfe_ublox_status_e) + // to the interface's status enum (Isfe_ublox_status_e). + Isfe_ublox_status_e returnStatus; + switch (status) { + case SFE_UBLOX_STATUS_SUCCESS: returnStatus = SUCCESS; break; + case SFE_UBLOX_STATUS_FAIL: returnStatus = FAIL; break; + case SFE_UBLOX_STATUS_CRC_FAIL: returnStatus = CRC_FAIL; break; + case SFE_UBLOX_STATUS_TIMEOUT: returnStatus = TIMEOUT; break; + case SFE_UBLOX_STATUS_COMMAND_NACK: returnStatus = COMMAND_NACK; break; + case SFE_UBLOX_STATUS_OUT_OF_RANGE: returnStatus = OUT_OF_RANGE; break; + case SFE_UBLOX_STATUS_INVALID_ARG: returnStatus = INVALID_ARG; break; + case SFE_UBLOX_STATUS_INVALID_OPERATION:returnStatus = INVALID_OPERATION; break; + case SFE_UBLOX_STATUS_MEM_ERR: returnStatus = MEM_ERR; break; + case SFE_UBLOX_STATUS_HW_ERR: returnStatus = HW_ERR; break; + case SFE_UBLOX_STATUS_DATA_SENT: returnStatus = DATA_SENT; break; + case SFE_UBLOX_STATUS_DATA_RECEIVED: returnStatus = DATA_RECEIVED; break; + case SFE_UBLOX_STATUS_I2C_COMM_FAILURE: returnStatus = I2C_COMM_FAILURE; break; + case SFE_UBLOX_STATUS_DATA_OVERWRITTEN: returnStatus = DATA_OVERWRITTEN; break; + default: + // Handle any unexpected status from the SFE library, map to a generic failure. + returnStatus = FAIL; + break; + } + + // 5. Return the translated status defined by the IGps interface. + return returnStatus; +} \ No newline at end of file diff --git a/src/hardware/GpsSFE_UBLOX_GNSS.h b/src/hardware/GpsSFE_UBLOX_GNSS.h new file mode 100644 index 0000000..5983be5 --- /dev/null +++ b/src/hardware/GpsSFE_UBLOX_GNSS.h @@ -0,0 +1,60 @@ +/** + * @file GpsSFE_UBLOX_GNSS.h + * @brief Concrete implementation of IGPS using SparkFun u-blox GNSS library + * + * Adapts the SparkFun u-blox GNSS library to the IGPS interface + * for dependency injection and testing. + * + * © 2025 Regents of the University of Minnesota. All rights reserved. + */ + +#ifndef GPS_SFE_UBLOX_GNSS_H +#define GPS_SFE_UBLOX_GNSS_H + +#include "../../lib/FlightControl-hardware-dependencies/src/IGps.h" +#include "../../lib/SparkFun_u-blox_GNSS_Arduino_Library/src/SparkFun_u-blox_GNSS_Arduino_Library.h" +#include "../../lib/FlightControl-platform-dependencies/src/IWire.h" + +/** + * @brief Concrete implementation of IGPS using SFE_UBLOX_GNSS + */ +class GpsSFE_UBLOX_GNSS : public IGps { +public: + /** + * @brief Constructor + * @param wire IWire instance for I2C communication + */ + GpsSFE_UBLOX_GNSS(); + ~GpsSFE_UBLOX_GNSS() override = default; + + bool begin() override; + void setI2COutput(uint8_t comType) override; + bool setNavigationFrequency(uint8_t navFreq) override; + void setAutoPVT(bool autoPVT) override; + uint8_t getNavigationFrequency() override; + uint8_t getMeasurementRate() override; + uint8_t getNavigationRate() override; + int16_t getATTroll() override; + int16_t getATTpitch() override; + int16_t getATTheading() override; + void setPacketCfgPayloadSize(uint16_t payloadSize) override; + uint8_t getSIV() override; + uint8_t getFixType() override; + bool getPVT() override; + bool getGnssFixOk() override; + long getAltitude() override; + long getLongitude() override; + long getLatitude() override; + uint8_t getHour() override; + uint8_t getMinute() override; + uint8_t getSecond() override; + bool getDateValid() override; + bool getTimeValid() override; + bool getTimeFullyResolved() override; + bool powerOffWithInterrupt(uint32_t durationInMs, uint32_t wakeupSources, bool forceWhileUsb = true) override; + Isfe_ublox_status_e sendCommand(IUbxPacket *outgoingUBX, uint16_t maxWait) override; +private: + SFE_UBLOX_GNSS gps; // The concrete GPS instance +}; + +#endif // GPS_SFE_UBLOX_GNSS_H \ No newline at end of file diff --git a/src/hardware/HumidityTemperatureAdafruit_SHT4X.cpp b/src/hardware/HumidityTemperatureAdafruit_SHT4X.cpp new file mode 100644 index 0000000..f51324c --- /dev/null +++ b/src/hardware/HumidityTemperatureAdafruit_SHT4X.cpp @@ -0,0 +1,74 @@ +/** + * @file HumidityTemperatureAdafruit_SHT4X.cpp + * @brief Implementation of HumidityTemperatureAdafruit_SHT4X class + * + * © 2025 Regents of the University of Minnesota. All rights reserved. + */ + + #include "HumidityTemperatureAdafruit_SHT4X.h" + + HumidityTemperatureAdafruit_SHT4X::HumidityTemperatureAdafruit_SHT4X() : currentPrecision(HT_HIGH_PRECISION) { + // Constructor initializes with high precision by default + } + + bool HumidityTemperatureAdafruit_SHT4X::begin() { + // Initialize the underlying Adafruit_SHT4x sensor + return sht4x.begin(); + } + + void HumidityTemperatureAdafruit_SHT4X::setPrecision(Iht_precision_t prec) { + // Store current precision setting + currentPrecision = prec; + + // Convert to Adafruit enum and apply to the hardware + sht4x_precision_t adafruitPrec = mapPrecision(prec); + sht4x.setPrecision(adafruitPrec); + } + + Iht_precision_t HumidityTemperatureAdafruit_SHT4X::getPrecision() { + // Return the stored precision setting + return currentPrecision; + } + + bool HumidityTemperatureAdafruit_SHT4X::getEvent(Isensors_event_t *humidity, Isensors_event_t *temp) { + //translate Isensors_event_t to Adafruit_Sensor event + sensors_event_t humidityEvent; + sensors_event_t tempEvent; + + // Call the underlying implementation to get the events + bool success = sht4x.getEvent(&humidityEvent, &tempEvent); + + //set the interface struct values + humidity->relative_humidity = humidityEvent.relative_humidity; + temp->temperature = tempEvent.temperature; + + return success; + } + + sht4x_precision_t HumidityTemperatureAdafruit_SHT4X::mapPrecision(Iht_precision_t prec) { + // Map interface precision enum to implementation precision enum + switch (prec) { + case HT_HIGH_PRECISION: + return SHT4X_HIGH_PRECISION; + case HT_MED_PRECISION: + return SHT4X_MED_PRECISION; + case HT_LOW_PRECISION: + return SHT4X_LOW_PRECISION; + default: + return SHT4X_HIGH_PRECISION; // Default to high precision + } + } + + Iht_precision_t HumidityTemperatureAdafruit_SHT4X::mapPrecision(sht4x_precision_t prec) { + // Map implementation precision enum to interface precision enum + switch (prec) { + case SHT4X_HIGH_PRECISION: + return HT_HIGH_PRECISION; + case SHT4X_MED_PRECISION: + return HT_MED_PRECISION; + case SHT4X_LOW_PRECISION: + return HT_LOW_PRECISION; + default: + return HT_HIGH_PRECISION; // Default to high precision + } + } \ No newline at end of file diff --git a/src/hardware/HumidityTemperatureAdafruit_SHT4X.h b/src/hardware/HumidityTemperatureAdafruit_SHT4X.h new file mode 100644 index 0000000..91f1293 --- /dev/null +++ b/src/hardware/HumidityTemperatureAdafruit_SHT4X.h @@ -0,0 +1,67 @@ +/** + * @file HumidityTemperatureAdafruit_SHT4X.h + * @brief Concrete implementation of IHumidityTemperature using Adafruit_SHT4x + * + * Adapts the Adafruit SHT4x humidity and temperature sensor to the IHumidityTemperature + * interface for dependency injection and testing. + * + * © 2025 Regents of the University of Minnesota. All rights reserved. + */ + + #ifndef HUMIDITY_TEMPERATURE_ADAFRUIT_SHT4X_H + #define HUMIDITY_TEMPERATURE_ADAFRUIT_SHT4X_H + + #include "IHumidityTemperature.h" + #include + + /** + * @brief Concrete implementation of IHumidityTemperature using Adafruit_SHT4x + */ + class HumidityTemperatureAdafruit_SHT4X : public IHumidityTemperature { + public: + /** + * @brief Constructor + */ + HumidityTemperatureAdafruit_SHT4X(); + + /** + * @brief Destructor + */ + ~HumidityTemperatureAdafruit_SHT4X() override = default; + + /** + * @brief Initialize the sensor + * @return true on success, false on failure + */ + bool begin() override; + + /** + * @brief Sets the precision level for measurements + * @param prec The desired precision setting + */ + void setPrecision(Iht_precision_t prec) override; + + /** + * @brief Gets the current precision setting + * @return Current precision setting + */ + Iht_precision_t getPrecision() override; + + /** + * @brief Get humidity and temperature values as sensor events + * @param humidity Event object to be populated with humidity data (can be NULL) + * @param temp Event object to be populated with temperature data (can be NULL) + * @return true if read was successful + */ + bool getEvent(Isensors_event_t *humidity, Isensors_event_t *temp) override; + + private: + Adafruit_SHT4x sht4x; // The concrete SHT4x instance + Iht_precision_t currentPrecision; + + // Helper to map between interface and implementation enums + sht4x_precision_t mapPrecision(Iht_precision_t prec); + Iht_precision_t mapPrecision(sht4x_precision_t prec); + }; + + #endif // HUMIDITY_TEMPERATURE_ADAFRUIT_SHT4X_H \ No newline at end of file diff --git a/src/hardware/IOExpanderPCAL9535A.cpp b/src/hardware/IOExpanderPCAL9535A.cpp new file mode 100644 index 0000000..7c32a9b --- /dev/null +++ b/src/hardware/IOExpanderPCAL9535A.cpp @@ -0,0 +1,193 @@ +/****************************************************************************** + * IOExpanderPCAL9535A.cpp + * Concrete implementation of IIOExpander for the PCAL9535A chip. + * Delegates calls to the PCAL9535A_Library driver. + * + * + * Distributed as-is; no warranty is given. + ******************************************************************************/ + + #include "IOExpanderPCAL9535A.h" + + // Include standard types/constants if not guaranteed by includes above + // (e.g., if IIOExpander.h doesn't define INPUT, OUTPUT etc.) + // #include // Or + + // --- Constructor --- + IOExpanderPCAL9535A::IOExpanderPCAL9535A(int address): pcal9535a(address) {} + + // --- IIOExpander Interface Method Implementations --- + + int IOExpanderPCAL9535A::begin() { + // Address is typically set in the constructor for I2C devices. + // The driver's begin() usually initializes Wire and checks presence. + return pcal9535a.begin(); + } + + // --- Core IO --- + int IOExpanderPCAL9535A::pinMode(int Pin, uint8_t State, bool Port) { + return pcal9535a.pinMode(Pin, State, Port); + } + + int IOExpanderPCAL9535A::pinMode(int Pin, uint8_t State) { + return pcal9535a.pinMode(Pin, State); + } + + int IOExpanderPCAL9535A::digitalWrite(int Pin, bool State, bool Port) { + return pcal9535a.digitalWrite(Pin, State, Port); + } + + int IOExpanderPCAL9535A::digitalWrite(int Pin, bool State) { + return pcal9535a.digitalWrite(Pin, State); + } + + int IOExpanderPCAL9535A::digitalRead(int Pin, bool Port) { + return pcal9535a.digitalRead(Pin, Port); + } + + int IOExpanderPCAL9535A::digitalRead(int Pin) { + return pcal9535a.digitalRead(Pin); + } + + // --- Specific Features --- + + + int IOExpanderPCAL9535A::pinSetDriveStrength(int Pin, IDriveStrength State, bool Port) { + DriveStrength realState; + switch(State) + { + case DRIVE_STRENGTH_DEFAULT: + //realState = DriveStrength::DEFAULT; //commented out because of macro overlapping + //break; + case DRIVE_STRENGTH_HIGH: + realState = DriveStrength::HIGH; + break; + case DRIVE_STRENGTH_STANDARD: + realState = DriveStrength::STANDARD; + break; + default: + realState = DriveStrength::STANDARD; + break; + } + return pcal9535a.pinSetDriveStrength(Pin, realState, Port); + } + + int IOExpanderPCAL9535A::pinSetDriveStrength(int Pin, IDriveStrength State) { + DriveStrength realState; + switch(State) + { + case DRIVE_STRENGTH_DEFAULT: + //realState = DriveStrength::DEFAULT; //commented out because of macro overlapping + //break; + case DRIVE_STRENGTH_HIGH: + realState = DriveStrength::HIGH; + break; + case DRIVE_STRENGTH_STANDARD: + realState = DriveStrength::STANDARD; + break; + default: + realState = DriveStrength::STANDARD; + break; + } + return pcal9535a.pinSetDriveStrength(Pin, realState); + } + + + int IOExpanderPCAL9535A::setInterrupt(int Pin, bool State, bool Port) { + return pcal9535a.setInterrupt(Pin, State, Port); + } + + int IOExpanderPCAL9535A::setInterrupt(int Pin, bool State) { + return pcal9535a.setInterrupt(Pin, State); + } + + int IOExpanderPCAL9535A::getInterrupt(int Pin) { + return pcal9535a.getInterrupt(Pin); + } + + uint16_t IOExpanderPCAL9535A::getAllInterrupts(uint8_t Option) { + // Delegate using the mapped age/status value + return pcal9535a.getAllInterrupts(Option); + } + + uint16_t IOExpanderPCAL9535A::getInterruptMask() { + return pcal9535a.getInterruptMask(); + } + + unsigned int IOExpanderPCAL9535A::clearInterrupt(uint8_t age) { + // Delegate using the mapped age/status value + return pcal9535a.clearInterrupt(age); + } + + bool IOExpanderPCAL9535A::isInterrupt(uint8_t age) { + // Driver doesn't have direct isInterrupt, implement via getAllInterrupts + return (pcal9535a.getAllInterrupts(age) != 0); + } + + int IOExpanderPCAL9535A::setLatch(int Pin, bool State, bool Port) { + return pcal9535a.setLatch(Pin, State, Port); + } + + int IOExpanderPCAL9535A::setLatch(int Pin, bool State) { + return pcal9535a.setLatch(Pin, State); + } + + uint16_t IOExpanderPCAL9535A::getLatch() { + return pcal9535a.getLatch(); + } + + int IOExpanderPCAL9535A::setInputPolarity(int Pin, bool State, bool Port) { + return pcal9535a.setInputPolarity(Pin, State, Port); + } + + int IOExpanderPCAL9535A::setInputPolarity(int Pin, bool State) { + return pcal9535a.setInputPolarity(Pin, State); + } + + bool IOExpanderPCAL9535A::getInputPolarity(int Pin, bool Port) { + // Driver returns int (-1 error, 0/1 state), interface expects bool + int result = pcal9535a.getInputPolarity(Pin, Port); + // Consider result >= 0 for true if 0 is valid, or just result == 1? + // Assuming 1 means "polarity inverted enabled", 0 means "disabled" + return (result == 1); // Adjust if 0 means true for your interface + } + + bool IOExpanderPCAL9535A::getInputPolarity(int Pin) { + int result = pcal9535a.getInputPolarity(Pin); + return (result == 1); // Adjust as needed + } + + int IOExpanderPCAL9535A::setBusOutput(uint8_t mode, bool Port) { + // Assumes interface OutputType constants match driver expectations + return pcal9535a.setBusOutput(mode, Port); + } + + uint8_t IOExpanderPCAL9535A::getBusOutput() { + return 0; //not implemented in driver + } + + uint16_t IOExpanderPCAL9535A::readBus() { + return pcal9535a.readBus(); + } + + // --- Error handling --- + uint16_t IOExpanderPCAL9535A::getError() { + return pcal9535a.getError(); + } + + uint16_t IOExpanderPCAL9535A::clearError() { + return pcal9535a.clearError(); + } + + void IOExpanderPCAL9535A::safeMode(int state) { + // Assumes interface constants match driver's SAFE, SAFE1, etc. + pcal9535a.safeMode(state); + } + + uint16_t IOExpanderPCAL9535A::readWord(int Pos, int &Error) { + return pcal9535a.readWord(Pos, Error); + } + + int IOExpanderPCAL9535A::setIntPinConfig(int Pin, bool Latch) { + return pcal9535a.setIntPinConfig(Pin, Latch); +} \ No newline at end of file diff --git a/src/hardware/IOExpanderPCAL9535A.h b/src/hardware/IOExpanderPCAL9535A.h new file mode 100644 index 0000000..2d62ee5 --- /dev/null +++ b/src/hardware/IOExpanderPCAL9535A.h @@ -0,0 +1,64 @@ +// src/hardware/IOExpanderPCAL9535A.h + +#ifndef IOEXPANDERPCAL9535A_H +#define IOEXPANDERPCAL9535A_H + +#include "../../lib/PCAL9535A_Library/src/PCAL9535A.h" //include the driver of PCAL9535A here +#include "IIOExpander.h" //include the interface of IIOExpander here + +/** + * * @breif Concrete implementation of IIOExpander for PCAL9535A + */ +class IOExpanderPCAL9535A : public IIOExpander { + public: + IOExpanderPCAL9535A(int _ADR = PCAL9535A_BASE_ADR); + ~IOExpanderPCAL9535A() = default; + + int begin() override; // Address argument ignored here, set in constructor + + // Core IO + int pinMode(int Pin, uint8_t State, bool Port) override; + int pinMode(int Pin, uint8_t State) override; + int digitalWrite(int Pin, bool State, bool Port) override; + int digitalWrite(int Pin, bool State) override; + int digitalRead(int Pin, bool Port) override; + int digitalRead(int Pin) override; + + // Specific Features + int pinSetDriveStrength(int Pin, IDriveStrength State, bool Port) override; + int pinSetDriveStrength(int Pin, IDriveStrength State) override; + + int setInterrupt(int Pin, bool State, bool Port) override; + int setInterrupt(int Pin, bool State) override; + int getInterrupt(int Pin) override; + uint16_t getAllInterrupts(uint8_t Option) override; + uint16_t getInterruptMask() override; + unsigned int clearInterrupt(uint8_t age) override; + bool isInterrupt(uint8_t age) override; + + int setLatch(int Pin, bool State, bool Port) override; + int setLatch(int Pin, bool State) override; + uint16_t getLatch() override; + + int setInputPolarity(int Pin, bool State, bool Port) override; + int setInputPolarity(int Pin, bool State) override; + bool getInputPolarity(int Pin, bool Port) override; + bool getInputPolarity(int Pin) override; + int setIntPinConfig(int Pin, bool Latch) override; + + int setBusOutput(uint8_t mode, bool Port) override; + uint8_t getBusOutput() override; // Driver returns uint8_t, maybe add to interface later + + uint16_t readBus() override; + + // Error handling + uint16_t getError() override; + uint16_t clearError() override; + void safeMode(int state) override; + + uint16_t readWord(int Pos, int &Error) override; + private: + PCAL9535A pcal9535a; +}; + +#endif // IOEXPANDERPCAL9535A_H \ No newline at end of file diff --git a/src/hardware/LedPCA9634.cpp b/src/hardware/LedPCA9634.cpp new file mode 100644 index 0000000..8c0d5e6 --- /dev/null +++ b/src/hardware/LedPCA9634.cpp @@ -0,0 +1,118 @@ +// src/hardware/LedPCA9634.cpp +#include "LedPCA9634.h" + +// Constructor +LedPCA9634::LedPCA9634(int address) + : driver(address) // Initialize the driver with address +{ + // Constructor body is empty as the initialization is done in the initializer list +} + +// Core methods +int LedPCA9634::begin() { + return driver.begin(); +} + +int LedPCA9634::sleep(bool State) { + return driver.sleep(State); +} + +// Configuration methods +int LedPCA9634::setOutputMode(IOutputMode State) { + // Convert from interface enum to driver enum + OutputMode driverState; + switch (State) { + case IOutputMode::OpenDrain: + driverState = OpenDrain; + break; + case IOutputMode::TotemPole: + driverState = TotemPole; + break; + default: + driverState = OpenDrain; // Default case + break; + } + return driver.setOutputMode(driverState); +} + +int LedPCA9634::setGroupMode(IGroupMode State) { + // Convert from interface enum to driver enum + GroupMode driverState; + switch (State) { + case IGroupMode::Dim: + driverState = Dim; + break; + case IGroupMode::Blink: + driverState = Blink; + break; + default: + driverState = Dim; // Default case + break; + } + return driver.setGroupMode(driverState); +} + +// Group control +int LedPCA9634::setGroupBlinkPeriod(uint16_t Period) { + return driver.setGroupBlinkPeriod(Period); +} + +int LedPCA9634::setGroupOnTime(uint16_t Period) { + return driver.setGroupOnTime(Period); +} + +// Brightness control +int LedPCA9634::setBrightness(uint8_t Pos, float Brightness) { + return driver.setBrightness(Pos, Brightness); +} + +int LedPCA9634::setBrightnessArray(float Brightness) { + return driver.setBrightnessArray(Brightness); +} + +// Output state control +int LedPCA9634::setOutput(uint8_t Pos, IPortState State) { + // Convert from interface enum to driver enum + PortState driverState; + switch (State) { + case IPortState::Off: + driverState = Off; + break; + case IPortState::On: + driverState = On; + break; + case IPortState::PWM: + driverState = PWM; + break; + case IPortState::Group: + driverState = Group; + break; + default: + driverState = Off; // Default case + break; + } + return driver.setOutput(Pos, driverState); +} + +int LedPCA9634::setOutputArray(IPortState Val) { + // Convert from interface enum to driver enum + PortState driverState; + switch (Val) { + case IPortState::Off: + driverState = Off; + break; + case IPortState::On: + driverState = On; + break; + case IPortState::PWM: + driverState = PWM; + break; + case IPortState::Group: + driverState = Group; + break; + default: + driverState = Off; // Default case + break; + } + return driver.setOutputArray(driverState); +} \ No newline at end of file diff --git a/src/hardware/LedPCA9634.h b/src/hardware/LedPCA9634.h new file mode 100644 index 0000000..0ee8466 --- /dev/null +++ b/src/hardware/LedPCA9634.h @@ -0,0 +1,41 @@ +// src/hardware/LedPCA9634.h +#ifndef LED_PCA9634_H +#define LED_PCA9634_H + +#include "ILed.h" // Include the interface definition +#include "../../PCA9634/src/PCA9634.h" // Include the actual driver + +/** + * @brief Concrete implementation of ILed using PCA9634 driver + */ +class LedPCA9634 : public ILed { +public: + // Constructor/Destructor + explicit LedPCA9634(int address); + ~LedPCA9634() override = default; + + // Core methods + int begin() override; + int sleep(bool State) override; + + // Configuration methods + int setOutputMode(IOutputMode State) override; + int setGroupMode(IGroupMode State) override; + + // Group control + int setGroupBlinkPeriod(uint16_t Period) override; + int setGroupOnTime(uint16_t Period) override; + + // Brightness control + int setBrightness(uint8_t Pos, float Brightness) override; + int setBrightnessArray(float Brightness) override; + + // Output state control + int setOutput(uint8_t Pos, IPortState State) override; + int setOutputArray(IPortState Val) override; + +private: + PCA9634 driver; // The concrete driver instance +}; + +#endif // LED_PCA9634_H \ No newline at end of file diff --git a/src/hardware/RtcMCP79412.cpp b/src/hardware/RtcMCP79412.cpp new file mode 100644 index 0000000..8e0cdd5 --- /dev/null +++ b/src/hardware/RtcMCP79412.cpp @@ -0,0 +1,108 @@ +/** + * @file RtcMCP79412.cpp + * @brief Implementation of the RtcMCP79412 class. + * + * © 2025 Regents of the University of Minnesota. All rights reserved. + */ + + #include "RtcMCP79412.h" + + RtcMCP79412::RtcMCP79412() : rtc() { + // Default constructor, delegates to MCP79412 constructor + } + + int RtcMCP79412::begin(bool UseExtOsc) { + return rtc.begin(UseExtOsc); + } + + int RtcMCP79412::setTime(int Year, int Month, int Day, int DoW, int Hour, int Min, int Sec) { + return rtc.setTime(Year, Month, Day, DoW, Hour, Min, Sec); + } + + int RtcMCP79412::setTime(int Year, int Month, int Day, int Hour, int Min, int Sec) { + return rtc.setTime(Year, Month, Day, Hour, Min, Sec); + } + + IRtc::Timestamp RtcMCP79412::getRawTime() { + MCP79412::Timestamp rtcTimestamp = rtc.getRawTime(); + + // Convert from MCP79412::Timestamp to IRtc::Timestamp + IRtc::Timestamp interfaceTimestamp; + interfaceTimestamp.year = rtcTimestamp.year; + interfaceTimestamp.month = rtcTimestamp.month; + interfaceTimestamp.mday = rtcTimestamp.mday; + interfaceTimestamp.wday = rtcTimestamp.wday; + interfaceTimestamp.hour = rtcTimestamp.hour; + interfaceTimestamp.min = rtcTimestamp.min; + interfaceTimestamp.sec = rtcTimestamp.sec; + + return interfaceTimestamp; + } + + time_t RtcMCP79412::getTimeUnix() { + return rtc.getTimeUnix(); + } + + int RtcMCP79412::setMode(Mode Val) { + MCP79412::Mode mcpMode; + + // Convert from IRtc::Mode to MCP79412::Mode + switch(Val) { + case Mode::Normal: + mcpMode = MCP79412::Mode::Normal; + break; + case Mode::Inverted: + mcpMode = MCP79412::Mode::Inverted; + break; + default: + // Default to Normal mode + mcpMode = MCP79412::Mode::Normal; + break; + } + + return rtc.setMode(mcpMode); + } + + int RtcMCP79412::setAlarm(unsigned int Seconds, bool AlarmNum) { + return rtc.setAlarm(Seconds, AlarmNum); + } + + int RtcMCP79412::setMinuteAlarm(unsigned int Offset, bool AlarmNum) { + return rtc.setMinuteAlarm(Offset, AlarmNum); + } + + int RtcMCP79412::setHourAlarm(unsigned int Offset, bool AlarmNum) { + return rtc.setHourAlarm(Offset, AlarmNum); + } + + int RtcMCP79412::setDayAlarm(unsigned int Offset, bool AlarmNum) { + return rtc.setDayAlarm(Offset, AlarmNum); + } + + int RtcMCP79412::enableAlarm(bool State, bool AlarmNum) { + return rtc.enableAlarm(State, AlarmNum); + } + + int RtcMCP79412::clearAlarm(bool AlarmNum) { + return rtc.clearAlarm(AlarmNum); + } + + bool RtcMCP79412::readAlarm(bool AlarmNum) { + return rtc.readAlarm(AlarmNum); + } + + String RtcMCP79412::getUUIDString() { + return rtc.getUUIDString(); + } + + uint8_t RtcMCP79412::readByte(int Reg) { + return rtc.readByte(Reg); + } + + uint8_t RtcMCP79412::getErrorsArray(uint32_t errors[]) { + return rtc.getErrorsArray(errors); + } + + int RtcMCP79412::throwError(uint32_t error) { + return rtc.throwError(error); + } \ No newline at end of file diff --git a/src/hardware/RtcMCP79412.h b/src/hardware/RtcMCP79412.h new file mode 100644 index 0000000..2fd750a --- /dev/null +++ b/src/hardware/RtcMCP79412.h @@ -0,0 +1,47 @@ +/** + * @file RtcMCP79412.h + * @brief Concrete implementation of IRtc using the MCP79412 real-time clock. + * + * Adapts the MCP79412 real-time clock to the IRtc interface + * for dependency injection and testing. + * + * © 2025 Regents of the University of Minnesota. All rights reserved. + */ + + #ifndef RTC_MCP79412_H + #define RTC_MCP79412_H + + #include "IRtc.h" + #include "MCP79412.h" // Include the actual MCP79412 library + + /** + * @brief Concrete implementation of IRtc using MCP79412 + */ + class RtcMCP79412 : public IRtc { + public: + RtcMCP79412(); + ~RtcMCP79412() override = default; + + int begin(bool UseExtOsc = false) override; + int setTime(int Year, int Month, int Day, int DoW, int Hour, int Min, int Sec) override; + int setTime(int Year, int Month, int Day, int Hour, int Min, int Sec) override; + Timestamp getRawTime() override; + time_t getTimeUnix() override; + int setMode(Mode Val) override; + int setAlarm(unsigned int Seconds, bool AlarmNum = false) override; + int setMinuteAlarm(unsigned int Offset, bool AlarmNum = false) override; + int setHourAlarm(unsigned int Offset, bool AlarmNum = false) override; + int setDayAlarm(unsigned int Offset, bool AlarmNum = false) override; + int enableAlarm(bool State = true, bool AlarmNum = false) override; + int clearAlarm(bool AlarmNum = false) override; + bool readAlarm(bool AlarmNum = false) override; + String getUUIDString() override; + uint8_t readByte(int Reg) override; + uint8_t getErrorsArray(uint32_t errors[]) override; + int throwError(uint32_t error) override; + + private: + MCP79412 rtc; // The concrete MCP79412 instance + }; + + #endif // RTC_MCP79412_H \ No newline at end of file diff --git a/src/platform/ParticleCloud.cpp b/src/platform/ParticleCloud.cpp new file mode 100644 index 0000000..989fb92 --- /dev/null +++ b/src/platform/ParticleCloud.cpp @@ -0,0 +1,11 @@ +#include "ParticleCloud.h" + +void ParticleCloud::connect() {Particle.connect();} +void ParticleCloud::disconnect(const ICloudDisconnectOptions& options) { + Particle.disconnect(CloudDisconnectOptions().graceful(options.graceful).timeout(options.timeout)); +} +bool ParticleCloud::connected() {return Particle.connected();} +bool ParticleCloud::syncTime() {return Particle.syncTime();} +bool ParticleCloud::syncTimePending() {return Particle.syncTimePending();} +bool ParticleCloud::syncTimeDone() {return Particle.syncTimeDone();} +bool ParticleCloud::process() {return Particle.process();} \ No newline at end of file diff --git a/src/platform/ParticleCloud.h b/src/platform/ParticleCloud.h new file mode 100644 index 0000000..d9575e9 --- /dev/null +++ b/src/platform/ParticleCloud.h @@ -0,0 +1,27 @@ +// src/platform/ParticleCloud.h +#ifndef PARTICLE_CLOUD_H +#define PARTICLE_CLOUD_H + +#include "ICloud.h" // Include the interface definition +#include "Particle.h" // Include the actual Particle header HERE + +/** + * @brief Concrete implementation of ICloud for Particle platform + */ +class ParticleCloud : public ICloud { +public: + // Constructor/Destructor + ParticleCloud() = default; + ~ParticleCloud() override = default; + + // Implement methods from ICloud + void connect() override; + void disconnect(const ICloudDisconnectOptions& options) override; + bool connected() override; + bool syncTime() override; + bool syncTimePending() override; + bool syncTimeDone() override; + bool process() override; +}; + +#endif // PARTICLE_CLOUD_H \ No newline at end of file diff --git a/src/platform/ParticleGpio.cpp b/src/platform/ParticleGpio.cpp new file mode 100644 index 0000000..a6cd2bf --- /dev/null +++ b/src/platform/ParticleGpio.cpp @@ -0,0 +1,20 @@ +#include "ParticleGpio.h" + +void ParticleGpio::pinMode(uint16_t pin, IPinMode mode){ + PinMode particlePinMode; + switch(mode) + { + case IPinMode::INPUT: + particlePinMode = ::INPUT; + break; + case IPinMode::OUTPUT: + particlePinMode = ::OUTPUT; + break; + default: + particlePinMode = ::INPUT; + break; + } + ::pinMode(pin, particlePinMode); +} +void ParticleGpio::digitalWrite(uint16_t pin, uint8_t value){::digitalWrite(pin, value);} +int32_t ParticleGpio::digitalRead(uint16_t pin){return ::digitalRead(pin);} \ No newline at end of file diff --git a/src/platform/ParticleGpio.h b/src/platform/ParticleGpio.h new file mode 100644 index 0000000..b10d121 --- /dev/null +++ b/src/platform/ParticleGpio.h @@ -0,0 +1,23 @@ +// src/platform/ParticleGpio.h +#ifndef PARTICLE_GPIO_H +#define PARTICLE_GPIO_H + +#include "IGpio.h" // Include the interface definition +#include "Particle.h" // Include the actual Particle header HERE + +/** + * @brief Concrete implementation of IGpio + */ +class ParticleGpio : public IGpio { +public: + // Constructor/Destructor (often default is fine) + ParticleGpio() = default; + ~ParticleGpio() override = default; + + // Implement methods from IGpio + void pinMode(uint16_t pin, IPinMode mode) override; + void digitalWrite(uint16_t pin, uint8_t value) override; + int32_t digitalRead(uint16_t pin) override; +}; + +#endif // PARTICLE_GPIO_H \ No newline at end of file diff --git a/src/platform/ParticleSerial.cpp b/src/platform/ParticleSerial.cpp new file mode 100644 index 0000000..a4bf6b2 --- /dev/null +++ b/src/platform/ParticleSerial.cpp @@ -0,0 +1,131 @@ +/** + * @file ParticleSerial.cpp + * @brief Particle implementation of ISerial interface + */ + +#include "ParticleSerial.h" +#include "Particle.h" + +// ParticleUSBSerial implementation (Serial) + +void ParticleUSBSerial::begin(long speed) { + Serial.begin(speed); +} + +size_t ParticleUSBSerial::print(const char* str) { + return Serial.print(str); +} + +size_t ParticleUSBSerial::print(int value) { + return Serial.print(value); +} + +size_t ParticleUSBSerial::print(uint32_t value) { + return Serial.print(value); +} + +size_t ParticleUSBSerial::print(time_t value) { + return Serial.print(value); +} + +size_t ParticleUSBSerial::print(unsigned int value, int base) { + return Serial.print(value, base); +} + +size_t ParticleUSBSerial::print(float value) { + return Serial.print(value); +} + +size_t ParticleUSBSerial::print(double value) { + return Serial.print(value); +} + +size_t ParticleUSBSerial::println() { + return Serial.println(); +} + +size_t ParticleUSBSerial::println(const char* str) { + return Serial.println(str); +} + +size_t ParticleUSBSerial::println(int value) { + return Serial.println(value); +} + +size_t ParticleUSBSerial::println(uint32_t value) { + return Serial.println(value); +} + +size_t ParticleUSBSerial::println(time_t value) { + return Serial.println(value); +} + +size_t ParticleUSBSerial::println(unsigned int value, int base) { + return Serial.println(value, base); +} + +void ParticleUSBSerial::flush() { + Serial.flush(); +} + +// ParticleHardwareSerial implementation (Serial1) + +void ParticleHardwareSerial::begin(unsigned long speed, uint32_t config) { + Serial1.begin(speed, config); +} + +size_t ParticleHardwareSerial::print(const char* str) { + return Serial1.print(str); +} + +size_t ParticleHardwareSerial::print(int value) { + return Serial1.print(value); +} + +size_t ParticleHardwareSerial::print(uint32_t value) { + return Serial1.print(value); +} + +size_t ParticleHardwareSerial::print(time_t value) { + return Serial1.print(value); +} + +size_t ParticleHardwareSerial::print(unsigned int value, int base) { + return Serial1.print(value, base); +} + +size_t ParticleHardwareSerial::print(float value) { + return Serial1.print(value); +} + +size_t ParticleHardwareSerial::print(double value) { + return Serial1.print(value); +} + +size_t ParticleHardwareSerial::println() { + return Serial1.println(); +} + +size_t ParticleHardwareSerial::println(const char* str) { + return Serial1.println(str); +} + +size_t ParticleHardwareSerial::println(int value) { + return Serial1.println(value); +} + +size_t ParticleHardwareSerial::println(uint32_t value) { + return Serial1.println(value); +} + +size_t ParticleHardwareSerial::println(time_t value) { + return Serial1.println(value); +} + +size_t ParticleHardwareSerial::println(unsigned int value, int base) { + return Serial1.println(value, base); +} + +void ParticleHardwareSerial::flush() { + Serial1.flush(); +} \ No newline at end of file diff --git a/src/platform/ParticleSerial.h b/src/platform/ParticleSerial.h new file mode 100644 index 0000000..4cb7a6c --- /dev/null +++ b/src/platform/ParticleSerial.h @@ -0,0 +1,63 @@ +/** + * @file ParticleSerial.h + * @brief Particle implementation of ISerial interface + */ + +#ifndef __PARTICLE_SERIAL_H +#define __PARTICLE_SERIAL_H + +#include "../../lib/FlightControl-platform-dependencies/src/ISerial.h" + +/** + * @brief Particle Serial implementation for Serial (USB) + */ +class ParticleUSBSerial : public ISerial { +public: + ParticleUSBSerial() = default; + virtual ~ParticleUSBSerial() = default; + + void begin(long speed) override; + void begin(unsigned long speed, uint32_t config) override { begin((long)speed); } + size_t print(const char* str) override; + size_t print(int value) override; + size_t print(uint32_t value) override; + size_t print(time_t value) override; + size_t print(unsigned int value, int base = 10) override; + size_t print(float value) override; + size_t print(double value) override; + size_t println() override; + size_t println(const char* str) override; + size_t println(int value) override; + size_t println(uint32_t value) override; + size_t println(time_t value) override; + size_t println(unsigned int value, int base = 10) override; + void flush() override; +}; + +/** + * @brief Particle Serial implementation for Serial1 (Hardware UART) + */ +class ParticleHardwareSerial : public ISerial { +public: + ParticleHardwareSerial() = default; + virtual ~ParticleHardwareSerial() = default; + + void begin(unsigned long speed, uint32_t config) override; + void begin(long speed) override { begin((unsigned long)speed, 0); } + size_t print(const char* str) override; + size_t print(int value) override; + size_t print(uint32_t value) override; + size_t print(time_t value) override; + size_t print(unsigned int value, int base = 10) override; + size_t print(float value) override; + size_t print(double value) override; + size_t println() override; + size_t println(const char* str) override; + size_t println(int value) override; + size_t println(uint32_t value) override; + size_t println(time_t value) override; + size_t println(unsigned int value, int base = 10) override; + void flush() override; +}; + +#endif // __PARTICLE_SERIAL_H \ No newline at end of file diff --git a/src/platform/ParticleSystem.cpp b/src/platform/ParticleSystem.cpp new file mode 100644 index 0000000..a726900 --- /dev/null +++ b/src/platform/ParticleSystem.cpp @@ -0,0 +1,169 @@ +#include "ParticleSystem.h" +#include "Particle.h" // Make sure Particle.h is included for Particle types/functions + +// --- Method Implementations --- + +void ParticleSystem::on(IEventType eventType, SystemEventHandler handler) { + system_event_t particleEvent; + switch (eventType) { + case IEventType::TIME_CHANGED: particleEvent = time_changed; break; + case IEventType::OUT_OF_MEMORY: particleEvent = out_of_memory; break; + default: Log.error("Unsupported IEventType in ParticleSystem::on"); return; + } + + // Wrapper lambda captures handler by value + auto particleHandlerWrapper = [handler](system_event_t sys_event, int data, void*) { + IEventType interfaceEventType; + switch (sys_event) { + case time_changed: interfaceEventType = IEventType::TIME_CHANGED; break; + case out_of_memory: interfaceEventType = IEventType::OUT_OF_MEMORY; break; + default: Log.warn("Unexpected system_event_t in wrapper: %d", (int)sys_event); return; + } + if (handler) { handler(interfaceEventType, data); } + }; + + System.on(particleEvent, particleHandlerWrapper); +} + +IResetReason ParticleSystem::resetReason() { + int particleReason = System.resetReason(); + // Assuming Particle's RESET_REASON_* constants match the values used in IResetReason enum + switch (particleReason) { + // Keep only the cases defined by Particle's resetReason() return values + case ::RESET_REASON_PIN_RESET: return IResetReason::PIN_RESET; + case ::RESET_REASON_POWER_MANAGEMENT: return IResetReason::POWER_MANAGEMENT; + case ::RESET_REASON_POWER_DOWN: return IResetReason::POWER_DOWN; + case ::RESET_REASON_POWER_BROWNOUT: return IResetReason::POWER_BROWNOUT; + case ::RESET_REASON_WATCHDOG: return IResetReason::WATCHDOG; + case ::RESET_REASON_UPDATE: return IResetReason::UPDATE; + case ::RESET_REASON_UPDATE_ERROR: return IResetReason::UPDATE_ERROR; + case ::RESET_REASON_UPDATE_TIMEOUT: return IResetReason::UPDATE_TIMEOUT; + case ::RESET_REASON_FACTORY_RESET: return IResetReason::FACTORY_RESET; + case ::RESET_REASON_SAFE_MODE: return IResetReason::SAFE_MODE; + case ::RESET_REASON_DFU_MODE: return IResetReason::DFU_MODE; + case ::RESET_REASON_PANIC: return IResetReason::PANIC; + case ::RESET_REASON_USER: return IResetReason::USER; + // Note: RESET_REASON_CONFIG_UPDATE might not be a standard Particle reason code. Check documentation. + // If it's not standard, remove or map appropriately. + // case ::RESET_REASON_CONFIG_UPDATE: return IResetReason::CONFIG_UPDATE; // Remove if not standard + case ::RESET_REASON_UNKNOWN: // Particle's unknown/default + default: + // Map Particle's 0 (NONE) or others to UNKNOWN + return IResetReason::UNKNOWN; + } +} + +uint32_t ParticleSystem::freeMemory() { + return System.freeMemory(); +} + +bool ParticleSystem::waitForCondition(std::function condition, std::chrono::milliseconds timeout) { + // Use Particle's System.waitCondition() instead of the waitFor macro + return System.waitCondition([&condition]{ return condition(); }, timeout.count()); +} + +// *** Updated sleep implementation *** +IWakeupReason ParticleSystem::sleep(const ISleepConfig& iConfig) { + // 1. Create the Particle-specific configuration object + particle::SystemSleepConfiguration particleConfig; + + // 2. Translate from ISleepConfig (interface) to particleConfig (Particle) + // Translate Mode + switch(iConfig.mode) { + case ISleepMode::ULTRA_LOW_POWER: + particleConfig.mode(SystemSleepMode::ULTRA_LOW_POWER); + break; + case ISleepMode::STOP: + particleConfig.mode(SystemSleepMode::STOP); + break; + case ISleepMode::HIBERNATE: + particleConfig.mode(SystemSleepMode::HIBERNATE); + break; + // Add other ISleepMode cases -> SystemSleepMode mapping if needed + default: + Log.warn("Unsupported ISleepMode passed, defaulting to ULP"); + particleConfig.mode(SystemSleepMode::ULTRA_LOW_POWER); // Default? + break; + } + + // Translate Duration + if (iConfig.duration.count() > 0) { + particleConfig.duration(iConfig.duration); + } + + // Translate Wake Pin + // Assuming 0xFFFF was used as the "invalid/not set" marker in ISleepConfig + if (iConfig.wakePin != 0xFFFF) { + // Translate IInterruptMode (interface) to Particle's InterruptMode + InterruptMode particleInterruptMode; + switch(iConfig.wakePinMode) { + case IInterruptMode::FALLING: particleInterruptMode = FALLING; break; + case IInterruptMode::RISING: particleInterruptMode = RISING; break; + case IInterruptMode::CHANGE: particleInterruptMode = CHANGE; break; + default: + Log.error("Unsupported IInterruptMode for wake pin %u, defaulting to CHANGE.", iConfig.wakePin); + particleInterruptMode = CHANGE; // Default? + break; + } + particleConfig.gpio(iConfig.wakePin, particleInterruptMode); + } + + // Translate Network Interface setting + switch(iConfig.network) { + case INetworkInterfaceIndex::CELLULAR: + particleConfig.network(NETWORK_INTERFACE_CELLULAR); // Basic keep alive + // particleConfig.network(NETWORK_INTERFACE_CELLULAR, SystemSleepNetworkFlag::INACTIVE_STANDBY); // Alternative for lower power standby + break; + case INetworkInterfaceIndex::WIFI: + particleConfig.network(NETWORK_INTERFACE_WIFI_AP); + break; + case INetworkInterfaceIndex::ETHERNET: + particleConfig.network(NETWORK_INTERFACE_ETHERNET); + break; + // case INetworkInterfaceIndex::ALL: // Ambiguous, map carefully if needed + // particleConfig.network(NETWORK_INTERFACE_CELLULAR); + // particleConfig.network(NETWORK_INTERFACE_WIFI); // Example + // break; + case INetworkInterfaceIndex::NONE: + case INetworkInterfaceIndex::LOOPBACK: // Loopback doesn't make sense for sleep network config + default: + // Default is often network off, so potentially do nothing here, + // or explicitly ensure it's off if Particle API requires it. + break; + } + + // Translate other flags from ISleepConfig if added... + // e.g., if (iConfig.waitForCloud) { particleConfig.flag(SystemSleepFlag::WAIT_CLOUD); } + + + // 3. Call the actual Particle function with the configured Particle object + SystemSleepResult result = System.sleep(particleConfig); + + // 4. Translate Particle's SystemSleepWakeupReason back to our IWakeupReason + switch (result.wakeupReason()) { + // Map all defined reasons + case SystemSleepWakeupReason::BY_GPIO: return IWakeupReason::BY_GPIO; + case SystemSleepWakeupReason::BY_ADC: return IWakeupReason::BY_ADC; + case SystemSleepWakeupReason::BY_DAC: return IWakeupReason::BY_DAC; + case SystemSleepWakeupReason::BY_RTC: return IWakeupReason::BY_RTC; + case SystemSleepWakeupReason::BY_LPCOMP: return IWakeupReason::BY_LPCOMP; + case SystemSleepWakeupReason::BY_USART: return IWakeupReason::BY_USART; + case SystemSleepWakeupReason::BY_I2C: return IWakeupReason::BY_I2C; + case SystemSleepWakeupReason::BY_SPI: return IWakeupReason::BY_SPI; + case SystemSleepWakeupReason::BY_TIMER: return IWakeupReason::BY_TIMER; + case SystemSleepWakeupReason::BY_CAN: return IWakeupReason::BY_CAN; + case SystemSleepWakeupReason::BY_USB: return IWakeupReason::BY_USB; + case SystemSleepWakeupReason::BY_BLE: return IWakeupReason::BY_BLE; + case SystemSleepWakeupReason::BY_NFC: return IWakeupReason::BY_NFC; + case SystemSleepWakeupReason::BY_NETWORK: return IWakeupReason::BY_NETWORK; + case SystemSleepWakeupReason::UNKNOWN: + default: + // Check error code for more info? + if (result.error() != SYSTEM_ERROR_NONE) { + Log.error("Sleep returned error code: %d", result.error()); + } + return IWakeupReason::UNKNOWN; + } +} + +// --- Implement overrides for other methods if added to ISystem --- \ No newline at end of file diff --git a/src/platform/ParticleSystem.h b/src/platform/ParticleSystem.h new file mode 100644 index 0000000..2407d0b --- /dev/null +++ b/src/platform/ParticleSystem.h @@ -0,0 +1,21 @@ +#ifndef PARTICLE_SYSTEM_H +#define PARTICLE_SYSTEM_H + +#include "ISystem.h" // Include the interface definition +#include "Particle.h" // Include the actual Particle header + +class ParticleSystem : public ISystem { +public: + ParticleSystem() = default; + ~ParticleSystem() override = default; + + void on(IEventType event, SystemEventHandler handler) override; + IResetReason resetReason() override; + uint32_t freeMemory() override; + bool waitForCondition(std::function condition, std::chrono::milliseconds timeout) override; + + // Updated sleep signature to use ISleepConfig from the interface + IWakeupReason sleep(const ISleepConfig& config) override; +}; + +#endif // PARTICLE_SYSTEM_H \ No newline at end of file diff --git a/src/platform/ParticleWire.cpp b/src/platform/ParticleWire.cpp new file mode 100644 index 0000000..b23928a --- /dev/null +++ b/src/platform/ParticleWire.cpp @@ -0,0 +1,10 @@ +#include "ParticleWire.h" + +void ParticleWire::begin(){Wire.begin();} +void ParticleWire::setClock(uint32_t speed){Wire.setClock(speed);} +bool ParticleWire::isEnabled(){return Wire.isEnabled();} +void ParticleWire::beginTransmission(int value){Wire.beginTransmission(value);} +uint8_t ParticleWire::endTransmission(){return Wire.endTransmission();} +size_t ParticleWire::write(uint8_t value){return Wire.write(value);} +int ParticleWire::reset(){return Wire.reset();} + diff --git a/src/platform/ParticleWire.h b/src/platform/ParticleWire.h new file mode 100644 index 0000000..9bb8399 --- /dev/null +++ b/src/platform/ParticleWire.h @@ -0,0 +1,28 @@ +// src/platform/ParticleWire.h +#ifndef PARTICLE_WIRE_H +#define PARTICLE_WIRE_H + +#include "IWire.h" // Include the interface definition +#include "Particle.h" // Include the actual Particle header HERE + +/** + * @brief Concrete implementation of IWire using Particle API. + */ +class ParticleWire: public IWire { +public: + // Constructor/Destructor (often default is fine) + ParticleWire() = default; + ~ParticleWire() override = default; + + // Implement methods from IWire + void begin() override; + void setClock(uint32_t speed) override; + bool isEnabled() override; + void beginTransmission(int) override; + uint8_t endTransmission() override; + size_t write(uint8_t) override; + int reset() override; + +}; + +#endif // PARTICLE_WIRE_H \ No newline at end of file diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index e052d37..061bba2 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -45,8 +45,8 @@ add_executable(unit_tests main.cpp # Kestrel tests - #unit/Driver_-_Kestrel/KestrelTest.cpp - #${CMAKE_SOURCE_DIR}/lib/Driver_-_Kestrel/src/Kestrel.cpp + unit/Driver_-_Kestrel/KestrelTest.cpp + ${CMAKE_SOURCE_DIR}/lib/Driver_-_Kestrel/src/Kestrel.cpp # Li710 tests unit/Driver_-_Li710/Li710Test.cpp diff --git a/test/external/fff b/test/external/fff deleted file mode 160000 index 5111c61..0000000 --- a/test/external/fff +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 5111c61e1ef7848e3afd3550044a8cf4405f4199 diff --git a/test/mocks/HARDWARE_INTERFACES.md b/test/mocks/HARDWARE_INTERFACES.md new file mode 100644 index 0000000..7bb5a27 --- /dev/null +++ b/test/mocks/HARDWARE_INTERFACES.md @@ -0,0 +1,215 @@ +# Hardware Interfaces and Mocks for Kestrel Testing + +## Current State + +The Kestrel class uses direct instantiation of hardware components, making them difficult to mock for unit testing. While we've successfully abstracted platform dependencies (TimeProvider, Gpio, System, etc.), hardware components remain tightly coupled. + +## Recommended Hardware Interface Abstractions + +To enable comprehensive unit testing, we should create interfaces for major hardware components. Here's a blueprint for implementing these interfaces: + +### 1. IO Expander Interface + +```cpp +// IPCAL9535A.h +class IPCAL9535A { +public: + virtual ~IPCAL9535A() = default; + virtual int begin() = 0; + virtual int pinMode(int Pin, uint8_t State) = 0; + virtual int digitalWrite(int Pin, bool State) = 0; + virtual int digitalRead(int Pin) = 0; + virtual void safeMode(int state) = 0; + // Add other required methods +}; +``` + +### 2. LED Driver Interface + +```cpp +// IPCA9634.h +class IPCA9634 { +public: + virtual ~IPCA9634() = default; + virtual int begin() = 0; + virtual int setOutputMode(PCA9634::OutputMode State) = 0; + virtual int setGroupMode(PCA9634::GroupMode State) = 0; + virtual int setOutputArray(PCA9634::PortState Val) = 0; + virtual int setBrightnessArray(float Brightness) = 0; + virtual int setGroupBlinkPeriod(uint16_t Period) = 0; + virtual int setGroupOnTime(uint16_t Period) = 0; + // Add other required methods +}; +``` + +### 3. RTC Interface + +```cpp +// IMCP79412.h +class IMCP79412 { +public: + virtual ~IMCP79412() = default; + virtual int begin(bool exOsc) = 0; + virtual time_t getTimeUnix() = 0; + virtual String getUUIDString() = 0; + virtual int setMode(MCP79412::Mode mode) = 0; + virtual int enableAlarm(bool enable, uint8_t alarmNum) = 0; + // Add other required methods +}; +``` + +### 4. Current Sensor Interface + +```cpp +// IPAC1934.h +class IPAC1934 { +public: + virtual ~IPAC1934() = default; + virtual bool begin() = 0; + virtual void setAddress(uint8_t addr) = 0; + virtual void setFrequency(PAC1934::Frequency freq) = 0; + // Add other required methods +}; +``` + +### 5. GPS Interface + +```cpp +// ISFE_UBLOX_GNSS.h +class ISFE_UBLOX_GNSS { +public: + virtual ~ISFE_UBLOX_GNSS() = default; + virtual bool begin() = 0; + virtual void setI2COutput(uint8_t comType) = 0; + virtual bool setNavigationFrequency(uint8_t navFreq) = 0; + virtual void setAutoPVT(bool autoPVT) = 0; + virtual uint8_t getNavigationFrequency() = 0; + virtual uint8_t getMeasurementRate() = 0; + virtual uint8_t getNavigationRate() = 0; + virtual int16_t getATTroll() = 0; + virtual int16_t getATTpitch() = 0; + virtual int16_t getATTheading() = 0; + // Add other required methods +}; +``` + +## Implementation Strategy + +### Step 1: Create Interface Files + +Create interface files for each hardware component in a central location: +- `/lib/FlightControl-hardware-dependencies/src/` + +### Step 2: Modify Hardware Components + +Make each hardware class implement its corresponding interface: + +```cpp +// Existing class modifications +class PCAL9535A : public IPCAL9535A { + // Implementation remains unchanged +}; +``` + +### Step 3: Refactor Kestrel + +Update Kestrel's constructor to use interfaces instead of concrete implementations: + +```cpp +class Kestrel: public Sensor { +private: + IPCAL9535A& ioOB; + IPCAL9535A& ioTalon; + IPCA9634& led; + IPAC1934& csaAlpha; + IPAC1934& csaBeta; + IMCP79412& rtc; + ISFE_UBLOX_GNSS& gps; + // etc. + +public: + Kestrel(ITimeProvider& timeProvider, + IGpio& gpio, + ISystem& system, + IWire& wire, + ICloud& cloud, + ISerial& serialDebug, + ISerial& serialSdi12, + IPCAL9535A& ioOB, + IPCAL9535A& ioTalon, + IPCA9634& led, + IPAC1934& csaAlpha, + IPAC1934& csaBeta, + IMCP79412& rtc, + ISFE_UBLOX_GNSS& gps, + // etc. + bool useSensors = false); +}; +``` + +### Step 4: Create Factory Function + +To keep backward compatibility, provide a factory function: + +```cpp +// In Kestrel.cpp +Kestrel* createDefaultKestrel(ITimeProvider& timeProvider, + IGpio& gpio, + ISystem& system, + IWire& wire, + ICloud& cloud, + ISerial& serialDebug, + ISerial& serialSdi12, + bool useSensors = false) { + static PCAL9535A ioOB(0x20); + static PCAL9535A ioTalon(0x21); + static PCA9634 led(0x52); + // etc. + + return new Kestrel(timeProvider, gpio, system, wire, cloud, + serialDebug, serialSdi12, + ioOB, ioTalon, led, csaAlpha, csaBeta, rtc, gps, + useSensors); +} +``` + +### Step 5: Update Tests + +Modify the test file to use the interfaces: + +```cpp +TEST_F(KestrelTest, TestKestrelBegin) { + // Create Kestrel with all mocked dependencies + Kestrel kestrel(mockTimeProvider, mockGpio, mockSystem, mockWire, mockCloud, + mockSerialDebug, mockSerialSdi12, + mockIoOB, mockIoTalon, mockLed, mockCsaAlpha, mockCsaBeta, + mockRtc, mockGps, false); + + // Now you can test the full begin() method + bool criticalFault = false; + bool fault = false; + kestrel.begin(0, criticalFault, fault); + + // Assert expectations + EXPECT_FALSE(criticalFault); +} +``` + +## Benefits of This Approach + +1. **Full Unit Testing**: Enables testing the entire Kestrel class with mocked dependencies +2. **Isolation**: Tests become deterministic, not dependent on hardware +3. **Test Coverage**: Increases test coverage to include hardware interactions +4. **Maintainability**: Makes code more modular and easier to extend + +## Incremental Implementation + +This refactoring can be implemented incrementally: + +1. Start with the most critical components (PCAL9535A, MCP79412) +2. Add interfaces one at a time to limit disruption +3. Update tests progressively as interfaces are added + +## Conclusion + +By implementing interfaces for hardware components, we can achieve comprehensive unit testing for Kestrel. The platform dependency interfaces already demonstrate the value of this approach, and extending it to hardware components is a logical next step for maintaining a robust, testable codebase. \ No newline at end of file diff --git a/test/mocks/MockAdafruit_SHT4X.h b/test/mocks/MockAdafruit_SHT4X.h new file mode 100644 index 0000000..bc73d57 --- /dev/null +++ b/test/mocks/MockAdafruit_SHT4X.h @@ -0,0 +1,33 @@ +/** + * @file MockAdafruit_SHT4X.h + * @brief Mock implementation of IHumidityTemperature for testing + * + * Provides a mock implementation of the IHumidityTemperature interface + * that can be used for unit testing Kestrel without hardware dependencies. + * + * © 2025 Regents of the University of Minnesota. All rights reserved. + */ + + #ifndef MOCK_ADAFRUIT_SHT4X_H + #define MOCK_ADAFRUIT_SHT4X_H + + #include "IHumidityTemperature.h" + #include + + /** + * @brief Mock implementation of IHumidityTemperature for testing + */ + class MockAdafruit_SHT4X : public IHumidityTemperature { + public: + // Default constructor and destructor + MockAdafruit_SHT4X() = default; + ~MockAdafruit_SHT4X() override = default; + + // Mock methods + MOCK_METHOD(bool, begin, (), (override)); + MOCK_METHOD(void, setPrecision, (Iht_precision_t prec), (override)); + MOCK_METHOD(Iht_precision_t, getPrecision, (), (override)); + MOCK_METHOD(bool, getEvent, (Isensors_event_t *humidity, Isensors_event_t *temp), (override)); + }; + + #endif // MOCK_ADAFRUIT_SHT4X_H \ No newline at end of file diff --git a/test/mocks/MockBMA456.h b/test/mocks/MockBMA456.h new file mode 100644 index 0000000..16bf8aa --- /dev/null +++ b/test/mocks/MockBMA456.h @@ -0,0 +1,36 @@ +/** + * @file MockBMA456.h + * @brief Mock implementation of IAccelerometer for testing + * + * Provides a mock implementation of the IAccelerometer interface + * that can be used for unit testing without hardware dependencies. + * + * © 2025 Regents of the University of Minnesota. All rights reserved. + */ + +#ifndef MOCK_BMA456_H +#define MOCK_BMA456_H + +#include +#include "IAccelerometer.h" + +/** + * @brief Google Mock implementation of IAccelerometer for testing + */ +class MockBMA456 : public IAccelerometer { +public: + // Default constructor and destructor + MockBMA456() = default; + ~MockBMA456() override = default; + + // Mock methods + MOCK_METHOD(int, begin, (), (override)); + MOCK_METHOD(float, getAccel, (uint8_t axis, uint8_t range), (override)); + MOCK_METHOD(int, updateAccelAll, (), (override)); + MOCK_METHOD(float, getTemp, (), (override)); + MOCK_METHOD(float*, getData, (), (override)); + MOCK_METHOD(float*, getOffset, (), (override)); + MOCK_METHOD(void, setOffset, (float offsetX, float offsetY, float offsetZ), (override)); +}; + +#endif // MOCK_BMA456_H \ No newline at end of file diff --git a/test/mocks/MockCloud.h b/test/mocks/MockCloud.h new file mode 100644 index 0000000..a1c6d94 --- /dev/null +++ b/test/mocks/MockCloud.h @@ -0,0 +1,22 @@ +#ifndef MOCK_CLOUD_H +#define MOCK_CLOUD_H + +#include +#include "ICloud.h" // Include the interface definition + +/** + * @brief Google Mock implementation of ICloud for testing. + */ +class MockCloud : public ICloud { +public: + // Mock all methods defined in the interface + MOCK_METHOD(void, connect, (), (override)); + MOCK_METHOD(void, disconnect, (const ICloudDisconnectOptions& options), (override)); + MOCK_METHOD(bool, connected, (), (override)); + MOCK_METHOD(bool, syncTime, (), (override)); + MOCK_METHOD(bool, syncTimePending, (), (override)); + MOCK_METHOD(bool, syncTimeDone, (), (override)); + MOCK_METHOD(bool, process, (), (override)); +}; + +#endif // MOCK_CLOUD_H \ No newline at end of file diff --git a/test/mocks/MockGpio.h b/test/mocks/MockGpio.h new file mode 100644 index 0000000..61f0c04 --- /dev/null +++ b/test/mocks/MockGpio.h @@ -0,0 +1,18 @@ +#ifndef MOCK_GPIO_H +#define MOCK_GPIO_H + +#include +#include "IGpio.h" // Include the interface definition + +/** + * @brief Google Mock implementation of IGpio for testing. + */ +class MockGpio : public IGpio { +public: + // Mock all methods defined in the interface + MOCK_METHOD(void, pinMode, (uint16_t pin, IPinMode mode), (override)); + MOCK_METHOD(void, digitalWrite, (uint16_t pin, uint8_t value), (override)); + MOCK_METHOD(int32_t, digitalRead, (uint16_t pin), (override)); +}; + +#endif // MOCK_GPIO_H \ No newline at end of file diff --git a/test/mocks/MockMCP79412.h b/test/mocks/MockMCP79412.h new file mode 100644 index 0000000..cb69736 --- /dev/null +++ b/test/mocks/MockMCP79412.h @@ -0,0 +1,41 @@ +/** + * @file MockMCP79412.h + * @brief Mock implementation of IRtc for testing. + * + * This class uses Google Mock to create a testable version of the RTC interface. + * + * © 2025 Regents of the University of Minnesota. All rights reserved. + */ + + #ifndef MOCK_MCP79412_H + #define MOCK_MCP79412_H + + #include + #include "IRtc.h" + + /** + * @brief Google Mock implementation of IRtc for testing. + */ + class MockMCP79412 : public IRtc { + public: + // Mock all methods defined in the interface + MOCK_METHOD(int, begin, (bool UseExtOsc), (override)); + MOCK_METHOD(int, setTime, (int Year, int Month, int Day, int DoW, int Hour, int Min, int Sec), (override)); + MOCK_METHOD(int, setTime, (int Year, int Month, int Day, int Hour, int Min, int Sec), (override)); + MOCK_METHOD(Timestamp, getRawTime, (), (override)); + MOCK_METHOD(time_t, getTimeUnix, (), (override)); + MOCK_METHOD(int, setMode, (Mode Val), (override)); + MOCK_METHOD(int, setAlarm, (unsigned int Seconds, bool AlarmNum), (override)); + MOCK_METHOD(int, setMinuteAlarm, (unsigned int Offset, bool AlarmNum), (override)); + MOCK_METHOD(int, setHourAlarm, (unsigned int Offset, bool AlarmNum), (override)); + MOCK_METHOD(int, setDayAlarm, (unsigned int Offset, bool AlarmNum), (override)); + MOCK_METHOD(int, enableAlarm, (bool State, bool AlarmNum), (override)); + MOCK_METHOD(int, clearAlarm, (bool AlarmNum), (override)); + MOCK_METHOD(bool, readAlarm, (bool AlarmNum), (override)); + MOCK_METHOD(String, getUUIDString, (), (override)); + MOCK_METHOD(uint8_t, readByte, (int Reg), (override)); + MOCK_METHOD(uint8_t, getErrorsArray, (uint32_t errors[]), (override)); + MOCK_METHOD(int, throwError, (uint32_t error), (override)); + }; + + #endif // MOCK_MCP79412_H \ No newline at end of file diff --git a/test/mocks/MockMXC6655.h b/test/mocks/MockMXC6655.h new file mode 100644 index 0000000..c81c052 --- /dev/null +++ b/test/mocks/MockMXC6655.h @@ -0,0 +1,31 @@ +/** + * @file MockAccelerometer.h + * @brief Mock implementation of IAccelerometer for testing + * + * Provides a mock accelerometer implementation for unit testing + * without requiring hardware. + * + * © 2025 Regents of the University of Minnesota. All rights reserved. + */ + + #ifndef MOCK_MXC6655_H + #define MOCK_MXC6655_H + + #include "IAccelerometer.h" + #include + + /** + * @brief Mock implementation of IAccelerometer for testing + */ + class MockMXC6655 : public IAccelerometer { + public: + MOCK_METHOD(int, begin, (), (override)); + MOCK_METHOD(float, getAccel, (uint8_t axis, uint8_t range), (override)); + MOCK_METHOD(int, updateAccelAll, (), (override)); + MOCK_METHOD(float, getTemp, (), (override)); + MOCK_METHOD(float*, getData, (), (override)); + MOCK_METHOD(float*, getOffset, (), (override)); + MOCK_METHOD(void, setOffset, (float offsetX, float offsetY, float offsetZ), (override)); + }; + + #endif // MOCK_MXC6655_H \ No newline at end of file diff --git a/test/mocks/MockPAC1934.h b/test/mocks/MockPAC1934.h new file mode 100644 index 0000000..65a613d --- /dev/null +++ b/test/mocks/MockPAC1934.h @@ -0,0 +1,47 @@ +// test/mocks/MockPAC1934.h + +#ifndef MOCK_PAC1934_H +#define MOCK_PAC1934_H + +#include +#include "ICurrentSenseAmplifier.h" + +/** + * @brief Google Mock implementation of ICurrentSenseAmplifier for testing. + * + * This mock allows for unit testing of code that depends on ICurrentSenseAmplifier + * without requiring actual hardware. + */ +class MockPAC1934 : public ICurrentSenseAmplifier { +public: + // Mock all methods defined in the interface + + // Configuration methods + MOCK_METHOD(bool, begin, (), (override)); + MOCK_METHOD(bool, setAddress, (uint8_t addr), (override)); + MOCK_METHOD(bool, enableChannel, (uint8_t channel, bool state), (override)); + MOCK_METHOD(bool, setFrequency, (uint16_t frequency), (override)); + MOCK_METHOD(int, getFrequency, (), (override)); + + // Measurement direction + MOCK_METHOD(void, setVoltageDirection, (uint8_t channel, bool bidirectional), (override)); + MOCK_METHOD(void, setCurrentDirection, (uint8_t channel, bool bidirectional), (override)); + MOCK_METHOD(bool, getVoltageDirection, (uint8_t channel), (override)); + MOCK_METHOD(bool, getCurrentDirection, (uint8_t channel), (override)); + + // Measurement methods - overload versions + MOCK_METHOD(float, getBusVoltage, (uint8_t channel, bool average, bool& status), (override)); + MOCK_METHOD(float, getBusVoltage, (uint8_t channel, bool average), (override)); + MOCK_METHOD(float, getSenseVoltage, (uint8_t channel, bool average, bool& status), (override)); + MOCK_METHOD(float, getSenseVoltage, (uint8_t channel, bool average), (override)); + MOCK_METHOD(float, getCurrent, (uint8_t channel, bool average, bool& status), (override)); + MOCK_METHOD(float, getCurrent, (uint8_t channel, bool average), (override)); + MOCK_METHOD(float, getPowerAvg, (uint8_t channel, bool& status), (override)); + MOCK_METHOD(float, getPowerAvg, (uint8_t channel), (override)); + + // Status and control + MOCK_METHOD(uint8_t, update, (uint8_t clear), (override)); + MOCK_METHOD(bool, testOverflow, (), (override)); +}; + +#endif // MOCK_PAC1934_H \ No newline at end of file diff --git a/test/mocks/MockPCA9634.h b/test/mocks/MockPCA9634.h new file mode 100644 index 0000000..936eaca --- /dev/null +++ b/test/mocks/MockPCA9634.h @@ -0,0 +1,26 @@ +// test/mocks/MockPCA9634.h +#ifndef MOCK_PCA9634_H +#define MOCK_PCA9634_H + +#include +#include "ILed.h" // Include the interface definition + +/** + * @brief Google Mock implementation of ILed for testing + */ +class MockPCA9634 : public ILed { +public: + // Mock all methods defined in the interface + MOCK_METHOD(int, begin, (), (override)); + MOCK_METHOD(int, sleep, (bool State), (override)); + MOCK_METHOD(int, setOutputMode, (IOutputMode State), (override)); + MOCK_METHOD(int, setGroupMode, (IGroupMode State), (override)); + MOCK_METHOD(int, setGroupBlinkPeriod, (uint16_t Period), (override)); + MOCK_METHOD(int, setGroupOnTime, (uint16_t Period), (override)); + MOCK_METHOD(int, setBrightness, (uint8_t Pos, float Brightness), (override)); + MOCK_METHOD(int, setBrightnessArray, (float Brightness), (override)); + MOCK_METHOD(int, setOutput, (uint8_t Pos, IPortState State), (override)); + MOCK_METHOD(int, setOutputArray, (IPortState Val), (override)); +}; + +#endif // MOCK_PCA9634_H \ No newline at end of file diff --git a/test/mocks/MockPCAL9535A.h b/test/mocks/MockPCAL9535A.h new file mode 100644 index 0000000..3a31316 --- /dev/null +++ b/test/mocks/MockPCAL9535A.h @@ -0,0 +1,62 @@ +#ifndef MOCK_PCAL9535A_H +#define MOCK_PCAL9535A_H + +#include +#include "IIOExpander.h" +#include "IWire.h" + +class MockPCAL9535A : public IIOExpander { +public: + // Core functionality + MOCK_METHOD(int, begin, (), (override)); + + // Pin control methods + MOCK_METHOD(int, pinMode, (int Pin, uint8_t State, bool Port), (override)); + MOCK_METHOD(int, pinMode, (int Pin, uint8_t State), (override)); + MOCK_METHOD(int, digitalWrite, (int Pin, bool State, bool Port), (override)); + MOCK_METHOD(int, digitalWrite, (int Pin, bool State), (override)); + MOCK_METHOD(int, digitalRead, (int Pin, bool Port), (override)); + MOCK_METHOD(int, digitalRead, (int Pin), (override)); + + // Drive strength methods + MOCK_METHOD(int, pinSetDriveStrength, (int Pin, IDriveStrength State, bool Port), (override)); + MOCK_METHOD(int, pinSetDriveStrength, (int Pin, IDriveStrength State), (override)); + + // Interrupt methods + MOCK_METHOD(int, setInterrupt, (int Pin, bool State, bool Port), (override)); + MOCK_METHOD(int, setInterrupt, (int Pin, bool State), (override)); + MOCK_METHOD(int, getInterrupt, (int Pin), (override)); + MOCK_METHOD(uint16_t, getAllInterrupts, (uint8_t Option), (override)); + MOCK_METHOD(uint16_t, getInterruptMask, (), (override)); + MOCK_METHOD(unsigned int, clearInterrupt, (uint8_t age), (override)); + MOCK_METHOD(bool, isInterrupt, (uint8_t age), (override)); + + // Latch methods + MOCK_METHOD(int, setLatch, (int Pin, bool State, bool Port), (override)); + MOCK_METHOD(int, setLatch, (int Pin, bool State), (override)); + MOCK_METHOD(uint16_t, getLatch, (), (override)); + + // Input polarity methods + MOCK_METHOD(int, setInputPolarity, (int Pin, bool State, bool Port), (override)); + MOCK_METHOD(int, setInputPolarity, (int Pin, bool State), (override)); + MOCK_METHOD(bool, getInputPolarity, (int Pin, bool Port), (override)); + MOCK_METHOD(bool, getInputPolarity, (int Pin), (override)); + + // Configuration methods + MOCK_METHOD(int, setIntPinConfig, (int Pin, bool Latch), (override)); + MOCK_METHOD(int, setBusOutput, (uint8_t mode, bool Port), (override)); + MOCK_METHOD(uint8_t, getBusOutput, (), (override)); + + // Bus read method + MOCK_METHOD(uint16_t, readBus, (), (override)); + + // Error handling methods + MOCK_METHOD(uint16_t, getError, (), (override)); + MOCK_METHOD(uint16_t, clearError, (), (override)); + MOCK_METHOD(void, safeMode, (int state), (override)); + + // Additional methods + MOCK_METHOD(uint16_t, readWord, (int Pos, int &Error), (override)); +}; + +#endif // MOCK_PCAL9535A_H \ No newline at end of file diff --git a/test/mocks/MockSFE_UBLOX_GNSS.h b/test/mocks/MockSFE_UBLOX_GNSS.h new file mode 100644 index 0000000..0461751 --- /dev/null +++ b/test/mocks/MockSFE_UBLOX_GNSS.h @@ -0,0 +1,55 @@ +/** + * @file MockSFE_UBLOX_GNSS.h + * @brief Mock implementation of IGPS for testing + * + * This class uses Google Mock to create a testable version of the GPS interface. + * + * © 2025 Regents of the University of Minnesota. All rights reserved. + */ + + #ifndef MOCK_SFE_UBLOX_GNSS_H + #define MOCK_SFE_UBLOX_GNSS_H + + #include + // Use the correct relative path to your IGps.h header + #include "../../lib/FlightControl-hardware-dependencies/src/IGps.h" // Assuming this path is correct + + /** + * @brief Google Mock implementation of IGPS for testing + */ + class MockSFE_UBLOX_GNSS : public IGps { // Ensure IGps is the correct base class name + public: + // Make sure the base class destructor is virtual if you derive from it + virtual ~MockSFE_UBLOX_GNSS() = default; + + // Mock all methods defined in the interface + MOCK_METHOD(bool, begin, (), (override)); + MOCK_METHOD(void, setI2COutput, (uint8_t comType), (override)); + MOCK_METHOD(bool, setNavigationFrequency, (uint8_t navFreq), (override)); + MOCK_METHOD(void, setAutoPVT, (bool autoPVT), (override)); + MOCK_METHOD(uint8_t, getNavigationFrequency, (), (override)); + MOCK_METHOD(uint8_t, getMeasurementRate, (), (override)); + MOCK_METHOD(uint8_t, getNavigationRate, (), (override)); + MOCK_METHOD(int16_t, getATTroll, (), (override)); + MOCK_METHOD(int16_t, getATTpitch, (), (override)); + MOCK_METHOD(int16_t, getATTheading, (), (override)); + MOCK_METHOD(void, setPacketCfgPayloadSize, (uint16_t payloadSize), (override)); + MOCK_METHOD(uint8_t, getSIV, (), (override)); + MOCK_METHOD(uint8_t, getFixType, (), (override)); + MOCK_METHOD(bool, getPVT, (), (override)); + MOCK_METHOD(bool, getGnssFixOk, (), (override)); + MOCK_METHOD(long, getAltitude, (), (override)); + MOCK_METHOD(long, getLongitude, (), (override)); + MOCK_METHOD(long, getLatitude, (), (override)); + MOCK_METHOD(uint8_t, getHour, (), (override)); + MOCK_METHOD(uint8_t, getMinute, (), (override)); + MOCK_METHOD(uint8_t, getSecond, (), (override)); + MOCK_METHOD(bool, getDateValid, (), (override)); + MOCK_METHOD(bool, getTimeValid, (), (override)); + MOCK_METHOD(bool, getTimeFullyResolved, (), (override)); + MOCK_METHOD(bool, powerOffWithInterrupt, (uint32_t durationInMs, uint32_t wakeupSources, bool forceWhileUsb), (override)); + MOCK_METHOD(Isfe_ublox_status_e, sendCommand, (IUbxPacket *outgoingUBX, uint16_t maxWait), (override)); + + }; + + #endif // MOCK_SFE_UBLOX_GNSS_H \ No newline at end of file diff --git a/test/mocks/MockSensor.h b/test/mocks/MockSensor.h new file mode 100644 index 0000000..82f8359 --- /dev/null +++ b/test/mocks/MockSensor.h @@ -0,0 +1,19 @@ +#include +#include "Sensor.h" + +class MockSensor : public Sensor { + public: + MOCK_METHOD(String, begin, (time_t time, bool &criticalFault, bool &fault)); + MOCK_METHOD(String, getErrors, (), (override)); + MOCK_METHOD(uint8_t, totalErrors, (), (override)); + MOCK_METHOD(String, getData, (time_t time), (override)); + MOCK_METHOD(String, getMetadata, (), (override)); + MOCK_METHOD(String, selfDiagnostic, (uint8_t diagnosticLevel, time_t time), (override)); + MOCK_METHOD(uint8_t, getTalonPort, ()); + MOCK_METHOD(uint8_t, getSensorPort, ()); + MOCK_METHOD(void, setTalonPort, (uint8_t port)); + MOCK_METHOD(void, setSensorPort, (uint8_t port)); + MOCK_METHOD(bool, isPresent, (), (override)); + MOCK_METHOD(int, sleep, (), (override)); + MOCK_METHOD(int, wake, (ITimeProvider& timeProvider), (override)); + }; \ No newline at end of file diff --git a/test/mocks/MockSerial.h b/test/mocks/MockSerial.h new file mode 100644 index 0000000..5261dd3 --- /dev/null +++ b/test/mocks/MockSerial.h @@ -0,0 +1,31 @@ +#ifndef MOCK_SERIAL_H +#define MOCK_SERIAL_H + +#include +#include "ISerial.h" // Include the interface definition + +/** + * @brief Google Mock implementation of ISerial for testing. + */ +class MockSerial : public ISerial { +public: + // Mock all methods defined in the interface + MOCK_METHOD(void, begin, (long speed), (override)); + MOCK_METHOD(void, begin, (unsigned long speed, uint32_t config), (override)); + MOCK_METHOD(size_t, print, (const char* str), (override)); + MOCK_METHOD(size_t, print, (int value), (override)); + MOCK_METHOD(size_t, print, (uint32_t value), (override)); + MOCK_METHOD(size_t, print, (time_t value), (override)); + MOCK_METHOD(size_t, print, (unsigned int value, int base), (override)); + MOCK_METHOD(size_t, print, (float value), (override)); + MOCK_METHOD(size_t, print, (double value), (override)); + MOCK_METHOD(size_t, println, (), (override)); + MOCK_METHOD(size_t, println, (const char* str), (override)); + MOCK_METHOD(size_t, println, (int value), (override)); + MOCK_METHOD(size_t, println, (uint32_t value), (override)); + MOCK_METHOD(size_t, println, (time_t value), (override)); + MOCK_METHOD(size_t, println, (unsigned int value, int base), (override)); + MOCK_METHOD(void, flush, (), (override)); +}; + +#endif // MOCK_SERIAL_H \ No newline at end of file diff --git a/test/mocks/MockSystem.h b/test/mocks/MockSystem.h new file mode 100644 index 0000000..9831d94 --- /dev/null +++ b/test/mocks/MockSystem.h @@ -0,0 +1,20 @@ +#ifndef MOCK_SYSTEM_H +#define MOCK_SYSTEM_H + +#include +#include "ISystem.h" // Include the interface definition + +/** + * @brief Google Mock implementation of ISystem for testing. + */ +class MockSystem : public ISystem { +public: + // Mock all methods defined in the interface + MOCK_METHOD(void, on, (IEventType event, SystemEventHandler handler), (override)); + MOCK_METHOD(IResetReason, resetReason, (), (override)); + MOCK_METHOD(uint32_t, freeMemory, (), (override)); + MOCK_METHOD(bool, waitForCondition, (std::function condition, std::chrono::milliseconds timeout), (override)); + MOCK_METHOD(IWakeupReason, sleep, (const ISleepConfig& config), (override)); +}; + +#endif // MOCK_SYSTEM_H \ No newline at end of file diff --git a/test/mocks/MockVEML3328.h b/test/mocks/MockVEML3328.h new file mode 100644 index 0000000..116ad5e --- /dev/null +++ b/test/mocks/MockVEML3328.h @@ -0,0 +1,29 @@ +/** + * @file MockVEML3328.h + * @brief Mock implementation of IAmbientLight for testing. + * + * This class uses Google Mock to create a testable version of the ambient light sensor interface. + * + * © 2025 Regents of the University of Minnesota. All rights reserved. + */ + + #ifndef MOCK_VEML3328_H + #define MOCK_VEML3328_H + + #include + #include "IAmbientLight.h" + + /** + * @brief Google Mock implementation of IAmbientLight for testing. + */ + class MockVEML3328 : public IAmbientLight { + public: + // Mock all methods defined in the interface + MOCK_METHOD(int, begin, (), (override)); + MOCK_METHOD(float, getValue, (Channel channel), (override)); + MOCK_METHOD(float, getValue, (Channel channel, bool &state), (override)); + MOCK_METHOD(float, getLux, (), (override)); + MOCK_METHOD(int, autoRange, (), (override)); + }; + + #endif // MOCK_VEML3328_H \ No newline at end of file diff --git a/test/mocks/MockWire.h b/test/mocks/MockWire.h new file mode 100644 index 0000000..7462f9a --- /dev/null +++ b/test/mocks/MockWire.h @@ -0,0 +1,22 @@ +#ifndef MOCK_WIRE_H +#define MOCK_WIRE_H + +#include +#include "IWire.h" // Include the interface definition + +/** + * @brief Google Mock implementation of IWire for testing. + */ +class MockWire : public IWire { +public: + // Mock all methods defined in the interface + MOCK_METHOD(void, begin, (), (override)); + MOCK_METHOD(void, setClock, (uint32_t speed), (override)); + MOCK_METHOD(bool, isEnabled, (), (override)); + MOCK_METHOD(void, beginTransmission, (int), (override)); + MOCK_METHOD(uint8_t, endTransmission, (), (override)); + MOCK_METHOD(size_t, write, (uint8_t), (override)); + MOCK_METHOD(int, reset, (), (override)); +}; + +#endif // MOCK_WIRE_H \ No newline at end of file diff --git a/test/mocks/Particle.h b/test/mocks/Particle.h index 03ef082..1cc9e41 100644 --- a/test/mocks/Particle.h +++ b/test/mocks/Particle.h @@ -9,6 +9,36 @@ #include #include #include // For std::min and std::max +#include // For isnan +#include // For time literals + +using namespace std::chrono_literals; // For 20min, 30s literals + +#define D2 2 +#define D8 8 +#define D22 22 +#define A3 3 +#define D7 7 +#define A2 2 +#define D6 6 +#define A1 1 +#define D5 5 +#define D23 23 +#define A6 6 + +// Hex formatting +#define HEX (unsigned char)16 +// Make min and isnan available in global namespace for compatibility +using std::min; +using std::isnan; + +// Time change event values +#define time_changed_sync 1 +#define time_changed_manually 2 + +#define PLATFORM_BSOM 0 +#define PLATFORM_B5SOM 1 +#define PLATFORM_ID 0 // Forward declaration class StringSumHelper; @@ -50,12 +80,53 @@ class String { *this = String(buf); } + // Make these unambiguous by ensuring the second parameter type is always distinct explicit String(float value, int decimalPlaces = 2) { char buf[33]; snprintf(buf, sizeof(buf), "%.*f", decimalPlaces, value); *this = String(buf); } + // Add constructor for double + explicit String(double value, int decimalPlaces = 2) { + char buf[33]; + snprintf(buf, sizeof(buf), "%.*f", decimalPlaces, value); + *this = String(buf); + } + + // Add constructor for unsigned long + explicit String(unsigned long value, unsigned char base = 10) { + char buf[33]; + if (base == 16) { + snprintf(buf, sizeof(buf), "%lx", value); + } else { + snprintf(buf, sizeof(buf), "%lu", value); + } + *this = String(buf); + } + + // Add constructor for long + explicit String(long value, unsigned char base = 10) { + char buf[33]; + if (base == 16) { + snprintf(buf, sizeof(buf), "%lx", value); + } else { + snprintf(buf, sizeof(buf), "%ld", value); + } + *this = String(buf); + } + + // Add constructor for uint32_t explicitly + explicit String(uint32_t value, unsigned char base = 10) { + char buf[33]; + if (base == 16) { + snprintf(buf, sizeof(buf), "%x", value); + } else { + snprintf(buf, sizeof(buf), "%u", value); + } + *this = String(buf); + } + ~String() { if (_buffer) free(_buffer); } @@ -240,6 +311,22 @@ class String { if (found == nullptr) return -1; return found - _buffer; } + + // Add endsWith method + bool endsWith(const String &suffix) const { + if (!_buffer || !suffix._buffer) return false; + if (suffix._length > _length) return false; + + return (strcmp(_buffer + (_length - suffix._length), suffix._buffer) == 0); + } + + bool endsWith(const char *suffix) const { + if (!_buffer || !suffix) return false; + size_t suffix_len = strlen(suffix); + if (suffix_len > _length) return false; + + return (strcmp(_buffer + (_length - suffix_len), suffix) == 0); + } void toCharArray(char *buf, unsigned int bufsize, unsigned int index = 0) const { if (buf == nullptr || bufsize == 0) { @@ -386,4 +473,51 @@ inline StringSumHelper operator + (const String &lhs, int num) { return result; } +// Mock EEPROM class +class EEPROMClass { +public: + template + void get(int address, T& value) { + // Simple mock implementation - just provide default values + value = T(); + } + + template + void put(int address, const T& value) { + // Mock implementation - doesn't actually store anything + } +}; + +// Global EEPROM instance - use inline to avoid multiple definition errors +inline EEPROMClass EEPROM; + +// Mock RGB LED control +class RGBClass { +public: + void control(bool controlEnabled) { + // Mock implementation - doesn't do anything + } + + void color(int r, int g, int b) { + // Mock implementation - doesn't do anything + } +}; + +// Global RGB instance - use inline to avoid multiple definition errors +inline RGBClass RGB; + +// Mock HAL functions +inline uint32_t HAL_RNG_GetRandomNumber() { + return rand(); // Simple mock implementation +} + +// Mock functions for floating point control register +inline int __get_FPSCR() { + return 0; // Mock implementation +} + +inline void __set_FPSCR(int value) { + // Mock implementation - doesn't do anything +} + #endif // MOCK_PARTICLE_H diff --git a/test/unit/Driver_-_Kestrel/Driver_-_KestrelFunctionTests.cpp b/test/unit/Driver_-_Kestrel/Driver_-_KestrelFunctionTests.cpp deleted file mode 100644 index 22d31c0..0000000 --- a/test/unit/Driver_-_Kestrel/Driver_-_KestrelFunctionTests.cpp +++ /dev/null @@ -1,151 +0,0 @@ -// FlightControl_Demo/test/unit/Driver-_-Kestrel/KestrelFunctionTests.cpp -// Tests for Kestrel's public functions - -#include "gtest/gtest.h" -#include "fff.h" -#include "TestKestrel.h" - -// Test fixture for Kestrel public function tests -class KestrelPublicTest : public ::testing::Test { -protected: - Kestrel* kestrel; - - void SetUp() override { - // Reset all mocks before each test - KestrelTest::resetAllMocks(); - - // Set default mock behaviors - KestrelTest::setDefaultMockBehavior(); - - // Create a Kestrel instance with properly configured mocks - kestrel = KestrelTest::createKestrel(); - } - - void TearDown() override { - // Clean up - delete kestrel; - } -}; - -// Test Kestrel initialization -TEST_F(KestrelPublicTest, BeginTest) { - // Set up additional mock behaviors if needed - bool criticalFault = false; - bool fault = false; - - // Call Kestrel's begin method - std::string result = kestrel->begin(1616161616, criticalFault, fault); - - // Verify begin was called on all dependent hardware components - EXPECT_EQ(PCAL9535A_begin_fake.call_count, 2); // 2 I/O expanders - EXPECT_EQ(MCP79412_begin_fake.call_count, 1); // RTC - EXPECT_EQ(PCA9634_begin_fake.call_count, 1); // LED controller - - // Verify no critical faults occurred - EXPECT_FALSE(criticalFault); - EXPECT_FALSE(fault); - - // Verify result contains expected success message - EXPECT_TRUE(result.find("Kestrel") != std::string::npos); -} - -// Test port power control -TEST_F(KestrelPublicTest, EnablePowerTest) { - // Set up mock behavior for I/O expanders - PCAL9535A_digitalWrite_fake.return_val = true; - - // Test enabling power on port 1 - bool result = kestrel->enablePower(1, true); - - // Verify the result and calls - EXPECT_TRUE(result); - EXPECT_EQ(PCAL9535A_digitalWrite_fake.call_count, 1); - - // Test disabling power - RESET_FAKE(PCAL9535A_digitalWrite); - PCAL9535A_digitalWrite_fake.return_val = true; - - result = kestrel->enablePower(1, false); - - EXPECT_TRUE(result); - EXPECT_EQ(PCAL9535A_digitalWrite_fake.call_count, 1); - - // Test with invalid port (should return false) - result = kestrel->enablePower(10, true); // Port 10 is out of range - EXPECT_FALSE(result); -} - -// Test data port control -TEST_F(KestrelPublicTest, EnableDataTest) { - // Set up mock behavior for I/O expanders - PCAL9535A_digitalWrite_fake.return_val = true; - - // Test enabling data on port 1 - bool result = kestrel->enableData(1, true); - - // Verify the result and calls - EXPECT_TRUE(result); - EXPECT_EQ(PCAL9535A_digitalWrite_fake.call_count, 1); - - // Test with invalid port (should return false) - result = kestrel->enableData(10, true); // Port 10 is out of range - EXPECT_FALSE(result); -} - -// Test time retrieval -TEST_F(KestrelPublicTest, GetTimeTest) { - // Set up mock behavior for time retrieval - MCP79412_getTime_fake.return_val = 1616161616; - - // Call the method under test - time_t time = kestrel->getTime(); - - // Verify the result matches what we expect - EXPECT_EQ(time, 1616161616); - EXPECT_EQ(MCP79412_getTime_fake.call_count, 1); -} - -// Test I2C bus control -TEST_F(KestrelPublicTest, I2CControlTest) { - // Set up mock behavior - PCAL9535A_digitalWrite_fake.return_val = true; - - // Test enabling I2C buses - EXPECT_TRUE(kestrel->enableI2C_Global(true)); - EXPECT_TRUE(kestrel->enableI2C_OB(true)); - EXPECT_TRUE(kestrel->enableI2C_External(true)); - - // Verify the calls occurred - // Note: Our simplified test implementation uses digitalWrite for Global, not PCAL9535A - EXPECT_EQ(digitalWrite_fake.call_count, 1); - EXPECT_EQ(PCAL9535A_digitalWrite_fake.call_count, 2); - - // Reset the fakes for the next series of tests - RESET_FAKE(PCAL9535A_digitalWrite); - RESET_FAKE(digitalWrite); - PCAL9535A_digitalWrite_fake.return_val = true; - - // Test disabling I2C buses - EXPECT_TRUE(kestrel->enableI2C_Global(false)); - EXPECT_TRUE(kestrel->enableI2C_OB(false)); - EXPECT_TRUE(kestrel->enableI2C_External(false)); - - // Verify the calls occurred - EXPECT_EQ(digitalWrite_fake.call_count, 1); - EXPECT_EQ(PCAL9535A_digitalWrite_fake.call_count, 2); -} - -// Test indicator light control -TEST_F(KestrelPublicTest, IndicatorLightTest) { - // Set up mock behavior - PCA9634_setBrightness_fake.return_val = true; - - // Test setting lights to different states - EXPECT_TRUE(kestrel->setIndicatorState(IndicatorLight::SENSORS, IndicatorMode::PASS)); - EXPECT_TRUE(kestrel->setIndicatorState(IndicatorLight::GPS, IndicatorMode::ERROR)); - - // Verify the right calls were made - EXPECT_EQ(PCA9634_setBrightness_fake.call_count, 2); -} - -// Add more tests for other public Kestrel functions as needed \ No newline at end of file diff --git a/test/unit/Driver_-_Kestrel/Driver_-_KestrelSetupTests.cpp b/test/unit/Driver_-_Kestrel/Driver_-_KestrelSetupTests.cpp deleted file mode 100644 index 87430fa..0000000 --- a/test/unit/Driver_-_Kestrel/Driver_-_KestrelSetupTests.cpp +++ /dev/null @@ -1,317 +0,0 @@ -// FlightControl_Demo/test/unit/Driver-_-Kestrel/Driver-_-KestrelTest.cpp -#include "gtest/gtest.h" -#include "fff.h" -#include "MockWireDeclare.h" -#include "MockArduino.h" -#include "MockPCAL9535A.h" -#include "MockMCP79412.h" -#include "MockPCA9634.h" -#include "MockVEML3328.h" -#include "MockPAC1934.h" -#include "MockSHT4x.h" -#include "MockMXC6655.h" -#include "MockBMA456.h" -#include "MockGNSS.h" -#include "MockSensor.h" - -// Test fixture for basic mock testing -class KestrelBasicTest : public ::testing::Test { -protected: - void SetUp() override { - // Reset all Wire fakes before each test - RESET_FAKE(Wire_begin); - RESET_FAKE(Wire_setClock); - RESET_FAKE(Wire_beginTransmission); - RESET_FAKE(Wire_endTransmission); - RESET_FAKE(Wire_requestFrom_3args); - RESET_FAKE(Wire_requestFrom_2args); - RESET_FAKE(Wire_available); - RESET_FAKE(Wire_read); - RESET_FAKE(Wire_write_uint8); - RESET_FAKE(Wire_write_buffer); - - // Reset Arduino fakes - RESET_FAKE(pinMode); - RESET_FAKE(digitalWrite); - RESET_FAKE(digitalRead); - RESET_FAKE(millis); - RESET_FAKE(delay); - - // Reset PCAL9535A fakes - RESET_FAKE(PCAL9535A_begin); - RESET_FAKE(PCAL9535A_pinMode); - RESET_FAKE(PCAL9535A_digitalWrite); - RESET_FAKE(PCAL9535A_digitalRead); - - // Reset MCP79412 fakes - RESET_FAKE(MCP79412_begin); - RESET_FAKE(MCP79412_getTime); - RESET_FAKE(MCP79412_setTime); - - // Reset PCA9634 fakes - RESET_FAKE(PCA9634_begin); - RESET_FAKE(PCA9634_setBrightness); - RESET_FAKE(PCA9634_setLEDOutputMode); - - // Reset VEML3328 fakes - RESET_FAKE(VEML3328_begin); - RESET_FAKE(VEML3328_readRed); - RESET_FAKE(VEML3328_readGreen); - RESET_FAKE(VEML3328_readBlue); - - // Reset PAC1934 fakes - RESET_FAKE(PAC1934_begin); - RESET_FAKE(PAC1934_readVoltage); - RESET_FAKE(PAC1934_readCurrent); - - // Reset SHT4x fakes - RESET_FAKE(SHT4x_begin); - RESET_FAKE(SHT4x_readTemperature); - RESET_FAKE(SHT4x_readHumidity); - - // Reset MXC6655 fakes - RESET_FAKE(MXC6655_begin); - RESET_FAKE(MXC6655_readAcceleration); - - // Reset BMA456 fakes - RESET_FAKE(BMA456_begin); - RESET_FAKE(BMA456_readAcceleration); - RESET_FAKE(BMA456_getStepCount); - - // Reset GNSS fakes - RESET_FAKE(GNSS_begin); - RESET_FAKE(GNSS_getLatitude); - RESET_FAKE(GNSS_getLongitude); - RESET_FAKE(GNSS_getAltitude); - - // Set default mock behavior - PCAL9535A_begin_fake.return_val = true; - MCP79412_begin_fake.return_val = true; - MCP79412_getTime_fake.return_val = 1616161616; // Fixed timestamp for testing - Wire_endTransmission_fake.return_val = 0; // Success - Wire_available_fake.return_val = 1; // Data available - - PCA9634_begin_fake.return_val = true; - VEML3328_begin_fake.return_val = true; - PAC1934_begin_fake.return_val = true; - SHT4x_begin_fake.return_val = true; - MXC6655_begin_fake.return_val = true; - BMA456_begin_fake.return_val = true; - GNSS_begin_fake.return_val = true; - - // Set up return values for common functions - VEML3328_readRed_fake.return_val = 500; - VEML3328_readGreen_fake.return_val = 600; - VEML3328_readBlue_fake.return_val = 400; - - PAC1934_readVoltage_fake.return_val = 3.3f; - PAC1934_readCurrent_fake.return_val = 0.1f; - - GNSS_getLatitude_fake.return_val = 449673925; // Minneapolis ~44.96°N - GNSS_getLongitude_fake.return_val = -932838386; // Minneapolis ~-93.28°E - GNSS_getAltitude_fake.return_val = 25000; // 250m above MSL - } -}; - -// A simple test to verify that Google Test is working -TEST_F(KestrelBasicTest, GoogleTestWorks) { - EXPECT_TRUE(true); -} - -// A test to verify that FFF is working with our mocks -TEST_F(KestrelBasicTest, FFFWorks) { - // Call a mocked function - Wire.begin(); - - // Verify it was called - EXPECT_EQ(Wire_begin_fake.call_count, 1); -} - -// A test to verify PCAL9535A mock -TEST_F(KestrelBasicTest, PCAL9535AMockWorks) { - // Create a mock object - PCAL9535A io; - - // Use the mock - bool result = io.begin(); - io.pinMode(0, OUTPUT); - io.digitalWrite(0, HIGH); - - // Verify calls - EXPECT_TRUE(result); - EXPECT_EQ(PCAL9535A_begin_fake.call_count, 1); - EXPECT_EQ(PCAL9535A_pinMode_fake.call_count, 1); - EXPECT_EQ(PCAL9535A_digitalWrite_fake.call_count, 1); -} - -// A test to verify MCP79412 mock -TEST_F(KestrelBasicTest, MCP79412MockWorks) { - // Create a mock object - MCP79412 rtc; - - // Use the mock - bool beginResult = rtc.begin(); - time_t time = rtc.getTime(); - - // Verify calls - EXPECT_TRUE(beginResult); - EXPECT_EQ(MCP79412_begin_fake.call_count, 1); - EXPECT_EQ(MCP79412_getTime_fake.call_count, 1); - EXPECT_EQ(time, 1616161616); -} - -// Tests for the PCA9634 mock -TEST_F(KestrelBasicTest, PCA9634MockWorks) { - // Create a mock object - PCA9634 led; - - // Use the mock - bool result = led.begin(); - led.setLEDOutputMode(1, 0); - led.setBrightness(1, 100); - - // Verify calls - EXPECT_TRUE(result); - EXPECT_EQ(PCA9634_begin_fake.call_count, 1); - EXPECT_EQ(PCA9634_setLEDOutputMode_fake.call_count, 1); - EXPECT_EQ(PCA9634_setBrightness_fake.call_count, 1); -} - -// Tests for the VEML3328 mock -TEST_F(KestrelBasicTest, VEML3328MockWorks) { - // Create a mock object - VEML3328 als; - - // Use the mock - bool result = als.begin(); - uint16_t red = als.readRed(); - uint16_t green = als.readGreen(); - uint16_t blue = als.readBlue(); - - // Verify calls - EXPECT_TRUE(result); - EXPECT_EQ(VEML3328_begin_fake.call_count, 1); - EXPECT_EQ(VEML3328_readRed_fake.call_count, 1); - EXPECT_EQ(VEML3328_readGreen_fake.call_count, 1); - EXPECT_EQ(VEML3328_readBlue_fake.call_count, 1); - EXPECT_EQ(red, 500); - EXPECT_EQ(green, 600); - EXPECT_EQ(blue, 400); -} - -// Tests for the PAC1934 mock -TEST_F(KestrelBasicTest, PAC1934MockWorks) { - // Create a mock object - PAC1934 csa; - - // Use the mock - bool result = csa.begin(); - float voltage = csa.readVoltage(0); - float current = csa.readCurrent(0); - - // Verify calls - EXPECT_TRUE(result); - EXPECT_EQ(PAC1934_begin_fake.call_count, 1); - EXPECT_EQ(PAC1934_readVoltage_fake.call_count, 1); - EXPECT_EQ(PAC1934_readCurrent_fake.call_count, 1); - EXPECT_FLOAT_EQ(voltage, 3.3f); - EXPECT_FLOAT_EQ(current, 0.1f); -} - -// Tests for the SHT4x mock -TEST_F(KestrelBasicTest, SHT4xMockWorks) { - // Create a mock object - Adafruit_SHT4x sht; - - // Set test values - sht.temperature = 22.5f; - sht.humidity = 45.0f; - - // Use the mock - bool result = sht.begin(); - float temp = sht.readTemperature(); - float humid = sht.readHumidity(); - - // Verify calls - EXPECT_TRUE(result); - EXPECT_EQ(SHT4x_begin_fake.call_count, 1); - EXPECT_EQ(SHT4x_readTemperature_fake.call_count, 1); - EXPECT_EQ(SHT4x_readHumidity_fake.call_count, 1); - EXPECT_FLOAT_EQ(temp, 22.5f); - EXPECT_FLOAT_EQ(humid, 45.0f); -} - -// Tests for the MXC6655 mock -TEST_F(KestrelBasicTest, MXC6655MockWorks) { - // Create a mock object - MXC6655 accel; - - // Set test values in mock object - accel.x_acceleration = 0.1f; - accel.y_acceleration = -0.2f; - accel.z_acceleration = 0.98f; - - // Use the mock - bool result = accel.begin(); - float x, y, z; - bool readResult = accel.readAcceleration(&x, &y, &z); - - // Verify calls - EXPECT_TRUE(result); - EXPECT_EQ(MXC6655_begin_fake.call_count, 1); - EXPECT_EQ(MXC6655_readAcceleration_fake.call_count, 1); - EXPECT_FLOAT_EQ(x, 0.1f); - EXPECT_FLOAT_EQ(y, -0.2f); - EXPECT_FLOAT_EQ(z, 0.98f); -} - -// Tests for the BMA456 mock -TEST_F(KestrelBasicTest, BMA456MockWorks) { - // Access the global mock object - BMA456 accel = accel_bma456; - - // Set test values - accel.x_acceleration = 0.05f; - accel.y_acceleration = 0.1f; - accel.z_acceleration = 0.95f; - accel.step_count = 1234; - BMA456_getStepCount_fake.return_val = 1234; // Set the return value for the fake function - - // Use the mock - bool result = accel.begin(); - float x, y, z; - bool readResult = accel.readAcceleration(&x, &y, &z); - uint32_t steps = accel.getStepCount(); - - // Verify calls - EXPECT_TRUE(result); - EXPECT_EQ(BMA456_begin_fake.call_count, 1); - EXPECT_EQ(BMA456_readAcceleration_fake.call_count, 1); - EXPECT_EQ(BMA456_getStepCount_fake.call_count, 1); - EXPECT_FLOAT_EQ(x, 0.05f); - EXPECT_FLOAT_EQ(y, 0.1f); - EXPECT_FLOAT_EQ(z, 0.95f); - EXPECT_EQ(steps, 1234); -} - -// Tests for the GNSS mock -TEST_F(KestrelBasicTest, GNSSMockWorks) { - // Create a mock object - SFE_UBLOX_GNSS gps; - - // Use the mock - bool result = gps.begin(); - long lat = gps.getLatitude(); - long lon = gps.getLongitude(); - long alt = gps.getAltitude(); - - // Verify calls - EXPECT_TRUE(result); - EXPECT_EQ(GNSS_begin_fake.call_count, 1); - EXPECT_EQ(GNSS_getLatitude_fake.call_count, 1); - EXPECT_EQ(GNSS_getLongitude_fake.call_count, 1); - EXPECT_EQ(GNSS_getAltitude_fake.call_count, 1); - EXPECT_EQ(lat, 449673925); - EXPECT_EQ(lon, -932838386); - EXPECT_EQ(alt, 25000); -} \ No newline at end of file diff --git a/test/unit/Driver_-_Kestrel/KestrelTest.cpp b/test/unit/Driver_-_Kestrel/KestrelTest.cpp new file mode 100644 index 0000000..388476e --- /dev/null +++ b/test/unit/Driver_-_Kestrel/KestrelTest.cpp @@ -0,0 +1,1417 @@ +#include +#include + +// Include our mock headers first +#include "Particle.h" +#include "MockSensor.h" +#include "MockPCAL9535A.h" +#include "MockPCA9634.h" +#include "MockMCP79412.h" +#include "MockSFE_UBLOX_GNSS.h" +#include "MockVEML3328.h" +#include "MockMXC6655.h" +#include "MockAdafruit_SHT4X.h" +#include "MockPAC1934.h" + +// Include platform interface mocks +#include "MockTimeProvider.h" +#include "MockGpio.h" +#include "MockSystem.h" +#include "MockWire.h" +#include "MockCloud.h" +#include "MockSerial.h" + +// This must be included AFTER mocks to ensure the mocks are used +// instead of actual hardware implementations +#include "Kestrel.h" + +// Test fixture class for Kestrel tests +class KestrelTest : public ::testing::Test { +protected: + // Our platform interface mocks + MockTimeProvider mockTimeProvider; + MockGpio mockGpio; + MockSystem mockSystem; + MockWire mockWire; + MockCloud mockCloud; + MockSerial mockSerialDebug; + MockSerial mockSerialSdi12; + + // Additional hardware component mocks that would need injection + MockPCAL9535A mockIoOB; + MockPCAL9535A mockIoTalon; + MockAdafruit_SHT4X mockTempHumidity; + MockMXC6655 mockAccel; + MockMXC6655 mockBackupAccel; + MockPCA9634 mockLed; + MockPAC1934 mockCsaAlpha; + MockPAC1934 mockCsaBeta; + MockMCP79412 mockRtc; + MockSFE_UBLOX_GNSS mockGps; + MockVEML3328 mockAls; + + // Set up mocks and test objects + void SetUp() override { + + } + + void TearDown() override { + // Any test cleanup code goes here + } + + // Helper method to create a Kestrel instance with mocks + Kestrel createFullyMockedKestrel(bool useSensors = false) { + return Kestrel( + mockTimeProvider, + mockGpio, + mockSystem, + mockWire, + mockCloud, + mockSerialDebug, + mockSerialSdi12, + mockIoOB, + mockIoTalon, + mockCsaAlpha, + mockCsaBeta, + mockLed, + mockRtc, + mockAls, + mockGps, + mockTempHumidity, + mockAccel, + mockBackupAccel, + useSensors + ); + } +}; + +// Constructor Tests +TEST_F(KestrelTest, ConstructorDefaultUseSensors) { + EXPECT_NO_THROW({ + Kestrel kestrel = createFullyMockedKestrel(false); + // Constructor should set reportSensors to false by default + }); +} + +TEST_F(KestrelTest, ConstructorWithUseSensorsTrue) { + EXPECT_NO_THROW({ + Kestrel kestrel = createFullyMockedKestrel(true); + // Constructor should set reportSensors to true + // We can test this indirectly through getData() + }); +} + +////////////////////////////////////////////////////////////////////////////// +//BEGIN TESTS +////////////////////////////////////////////////////////////////////////////// +// verify critical fault is set rue if ioOB begin fails +TEST_F(KestrelTest, BeginIOBBeginFail) { + Kestrel kestrel = createFullyMockedKestrel(); + bool criticalFault = false; + bool fault = false; + float data[3] = {0.0, 0.0, 0.0}; + + EXPECT_CALL(mockSystem, resetReason()) + .WillOnce(::testing::Return(IResetReason::WATCHDOG)); + + EXPECT_CALL(mockAccel, getData()) + .WillRepeatedly(::testing::Return(data)); + + EXPECT_CALL(mockAccel, getOffset()) + .WillRepeatedly(::testing::Return(data)); + + EXPECT_CALL(mockIoOB, begin()) + .WillOnce(::testing::Return(1)); + + EXPECT_CALL(mockIoTalon, begin()) + .WillOnce(::testing::Return(0)); + + EXPECT_CALL(mockRtc, begin(true)) + .WillOnce(::testing::Return(true)); + + EXPECT_CALL(mockGps, begin()) + .WillRepeatedly(::testing::Return(true)); + + // We would need to verify throwError is called, but it's private + // This tests the overall begin() behavior + String result = kestrel.begin(0, criticalFault, fault); + + // Check that we get through initialization + EXPECT_TRUE(criticalFault); + EXPECT_FALSE(fault); + EXPECT_EQ(result, ""); +} + +// verify critical fault is set if ioTalon begin fails +TEST_F(KestrelTest, BeginIOTalonBeginFail) { + Kestrel kestrel = createFullyMockedKestrel(); + bool criticalFault = false; + bool fault = false; + float data[3] = {0.0, 0.0, 0.0}; + + EXPECT_CALL(mockSystem, resetReason()) + .WillOnce(::testing::Return(IResetReason::WATCHDOG)); + + EXPECT_CALL(mockAccel, getData()) + .WillRepeatedly(::testing::Return(data)); + + EXPECT_CALL(mockAccel, getOffset()) + .WillRepeatedly(::testing::Return(data)); + + EXPECT_CALL(mockIoOB, begin()) + .WillOnce(::testing::Return(0)); + + EXPECT_CALL(mockIoTalon, begin()) + .WillOnce(::testing::Return(1)); + + EXPECT_CALL(mockRtc, begin(true)) + .WillOnce(::testing::Return(true)); + + EXPECT_CALL(mockGps, begin()) + .WillRepeatedly(::testing::Return(true)); + + // We would need to verify throwError is called, but it's private + // This tests the overall begin() behavior + String result = kestrel.begin(0, criticalFault, fault); + + // Check that we get through initialization + EXPECT_TRUE(criticalFault); + EXPECT_FALSE(fault); + EXPECT_EQ(result, ""); +} + +// verify that led setOupput is only called when initDone is false +TEST_F(KestrelTest, BeginLEDsetOutputOnlyCalledWhenInitDoneFalse) { +Kestrel kestrel = createFullyMockedKestrel(); +bool criticalFault = false; +bool fault = false; +float data[3] = {0.0, 0.0, 0.0}; + +EXPECT_CALL(mockSystem, resetReason()) + .WillOnce(::testing::Return(IResetReason::WATCHDOG)); + +EXPECT_CALL(mockAccel, getData()) + .WillRepeatedly(::testing::Return(data)); + +EXPECT_CALL(mockAccel, getOffset()) + .WillRepeatedly(::testing::Return(data)); + +EXPECT_CALL(mockIoOB, begin()) + .WillRepeatedly(::testing::Return(0)); + +EXPECT_CALL(mockIoTalon, begin()) + .WillRepeatedly(::testing::Return(0)); + +EXPECT_CALL(mockRtc, begin(true)) + .WillRepeatedly(::testing::Return(true)); + +EXPECT_CALL(mockGps, begin()) + .WillRepeatedly(::testing::Return(true)); + +EXPECT_CALL(mockLed, setOutputMode(ILed::IOutputMode::OpenDrain)) + .Times(1); + +// We would need to verify throwError is called, but it's private +// This tests the overall begin() behavior +String result = kestrel.begin(0, criticalFault, fault); + +// Check that we get through initialization +EXPECT_FALSE(criticalFault); +EXPECT_FALSE(fault); +EXPECT_EQ(result, ""); + +result = kestrel.begin(0, criticalFault, fault); + +// Check that we get through initialization +EXPECT_FALSE(criticalFault); +EXPECT_FALSE(fault); +EXPECT_EQ(result, ""); + +} + +//verify that critical fault is set if rtc.begin fails +TEST_F(KestrelTest, BeginRTCFail) { + Kestrel kestrel = createFullyMockedKestrel(); + bool criticalFault = false; + bool fault = false; + float data[3] = {0.0, 0.0, 0.0}; + + EXPECT_CALL(mockSystem, resetReason()) + .WillOnce(::testing::Return(IResetReason::WATCHDOG)); + + EXPECT_CALL(mockAccel, getData()) + .WillRepeatedly(::testing::Return(data)); + + EXPECT_CALL(mockAccel, getOffset()) + .WillRepeatedly(::testing::Return(data)); + + EXPECT_CALL(mockIoOB, begin()) + .WillOnce(::testing::Return(0)); + + EXPECT_CALL(mockIoTalon, begin()) + .WillOnce(::testing::Return(0)); + + EXPECT_CALL(mockRtc, begin(true)) + .WillOnce(::testing::Return(false)); + + EXPECT_CALL(mockGps, begin()) + .WillRepeatedly(::testing::Return(true)); + + // We would need to verify throwError is called, but it's private + // This tests the overall begin() behavior + String result = kestrel.begin(0, criticalFault, fault); + + // Check that we get through initialization + EXPECT_TRUE(criticalFault); + EXPECT_FALSE(fault); + EXPECT_EQ(result, ""); +} + +//verify that critical fault is set if gps.begin fails +TEST_F(KestrelTest, BeginGPSFail) { + Kestrel kestrel = createFullyMockedKestrel(); + bool criticalFault = false; + bool fault = false; + float data[3] = {0.0, 0.0, 0.0}; + + EXPECT_CALL(mockSystem, resetReason()) + .WillOnce(::testing::Return(IResetReason::WATCHDOG)); + + EXPECT_CALL(mockAccel, getData()) + .WillRepeatedly(::testing::Return(data)); + + EXPECT_CALL(mockAccel, getOffset()) + .WillRepeatedly(::testing::Return(data)); + + EXPECT_CALL(mockIoOB, begin()) + .WillOnce(::testing::Return(0)); + + EXPECT_CALL(mockIoTalon, begin()) + .WillOnce(::testing::Return(0)); + + EXPECT_CALL(mockRtc, begin(true)) + .WillOnce(::testing::Return(true)); + + EXPECT_CALL(mockGps, begin()) + .WillRepeatedly(::testing::Return(false)); + + // We would need to verify throwError is called, but it's private + // This tests the overall begin() behavior + String result = kestrel.begin(0, criticalFault, fault); + + // Check that we get through initialization + EXPECT_TRUE(criticalFault); + EXPECT_FALSE(fault); + EXPECT_EQ(result, ""); +} + +//verify that critical fault and fault are false when all begin calls are successul +TEST_F(KestrelTest, BeginAllSuccess) { + Kestrel kestrel = createFullyMockedKestrel(); + bool criticalFault = false; + bool fault = false; + float data[3] = {0.0, 0.0, 0.0}; + + EXPECT_CALL(mockSystem, resetReason()) + .WillOnce(::testing::Return(IResetReason::WATCHDOG)); + + EXPECT_CALL(mockAccel, getData()) + .WillRepeatedly(::testing::Return(data)); + + EXPECT_CALL(mockAccel, getOffset()) + .WillRepeatedly(::testing::Return(data)); + + EXPECT_CALL(mockIoOB, begin()) + .WillOnce(::testing::Return(0)); + + EXPECT_CALL(mockIoTalon, begin()) + .WillOnce(::testing::Return(0)); + + EXPECT_CALL(mockRtc, begin(true)) + .WillOnce(::testing::Return(true)); + + EXPECT_CALL(mockGps, begin()) + .WillRepeatedly(::testing::Return(true)); + + // We would need to verify throwError is called, but it's private + // This tests the overall begin() behavior + String result = kestrel.begin(0, criticalFault, fault); + + // Check that we get through initialization + EXPECT_FALSE(criticalFault); + EXPECT_FALSE(fault); + EXPECT_EQ(result, ""); +} +////////////////////////////////////////////////////////////////////////////// +//END BEGIN TESTS +////////////////////////////////////////////////////////////////////////////// + +////////////////////////////////////////////////////////////////////////////// +// enablePower() Tests +////////////////////////////////////////////////////////////////////////////// +TEST_F(KestrelTest, EnablePowerPort5ReturnsImmediately) { + Kestrel kestrel = createFullyMockedKestrel(); + + EXPECT_CALL(mockIoTalon, pinMode(5, ::testing::_)) + .Times(0); // Should not be called for port 5 + + // Port 5 is a special case - should return false + bool result = kestrel.enablePower(5, true); + EXPECT_FALSE(result); +} + +TEST_F(KestrelTest, EnablePowerInvalidPortThrowsError) { + Kestrel kestrel = createFullyMockedKestrel(); + + EXPECT_CALL(mockIoTalon, pinMode(0, ::testing::_)) + .Times(0); // Should not be called for invalid ports + + // Test port 0 and port > 4 + kestrel.enablePower(0, true); + kestrel.enablePower(10, true); + + // Would need to check if throwError was called + // This is limited since throwError is private +} + +TEST_F(KestrelTest, EnablePowerValidPortOperation) { + Kestrel kestrel = createFullyMockedKestrel(); + + // Set up expectations for enabling power on port 1 + EXPECT_CALL(mockGpio, digitalRead(Pins::I2C_GLOBAL_EN)) + .Times(2) + .WillRepeatedly(::testing::Return(0)); + EXPECT_CALL(mockGpio, digitalRead(Pins::I2C_OB_EN)) + .Times(2) + .WillRepeatedly(::testing::Return(0)); + + EXPECT_CALL(mockIoTalon, pinMode(3, IIOExpander::IPinMode::OUTPUT)) // EN[0] for port 1 + .Times(1); + EXPECT_CALL(mockIoTalon, digitalWrite(3, true)) + .Times(1); + + bool result = kestrel.enablePower(1, true); + EXPECT_FALSE(result); // Always returns false for debugging +} +//////////////////////////////////////////////////////////////////////////////// +// End ebalePower() Tests +//////////////////////////////////////////////////////////////////////////////// + +//////////////////////////////////////////////////////////////////////////////// +// enableData() Tests +//////////////////////////////////////////////////////////////////////////////// +TEST_F(KestrelTest, EnableDataPort5CallsExternalI2C) { + Kestrel kestrel = createFullyMockedKestrel(); + + EXPECT_CALL(mockIoTalon, pinMode(5, ::testing::_)) + .Times(0); // Should not be called for port 5 + // Port 5 calls enableI2C_External + // We'd need to mock the enableI2C_External behavior + bool result = kestrel.enableData(5, true); + EXPECT_FALSE(result); +} + +TEST_F(KestrelTest, EnableDataValidPortOperation) { + Kestrel kestrel = createFullyMockedKestrel(); + + // Set up expectations for enabling power on port 1 + EXPECT_CALL(mockGpio, digitalRead(Pins::I2C_GLOBAL_EN)) + .Times(2) + .WillRepeatedly(::testing::Return(0)); + EXPECT_CALL(mockGpio, digitalRead(Pins::I2C_OB_EN)) + .Times(2) + .WillRepeatedly(::testing::Return(0)); + + EXPECT_CALL(mockIoTalon, pinMode(3, IIOExpander::IPinMode::OUTPUT)) // EN[0] for port 1 + .Times(1); + EXPECT_CALL(mockIoTalon, digitalWrite(3, true)) + .Times(1); + + bool result = kestrel.enablePower(1, true); + EXPECT_FALSE(result); // Always returns false for debugging +} +////////////////////////////////////////////////////////////////////////////////// +// End enableData() Tests +////////////////////////////////////////////////////////////////////////////////// + + +///////////////////////////////////////////////////////////////////////////////// +// feedWDT() Tests +///////////////////////////////////////////////////////////////////////////////// +TEST_F(KestrelTest, FeedWDTNormalOperation) { + Kestrel kestrel = createFullyMockedKestrel(); + + // Set up expectations for normal WDT feeding + EXPECT_CALL(mockGpio, pinMode(Pins::WD_HOLD, IPinMode::OUTPUT)) + .Times(1); + EXPECT_CALL(mockGpio, digitalWrite(Pins::WD_HOLD, 0)) + .Times(2); + EXPECT_CALL(mockGpio, digitalWrite(Pins::WD_HOLD, 1)) + .Times(1); + EXPECT_CALL(mockTimeProvider, delay(1)) + .Times(2); + + bool result = kestrel.feedWDT(); + EXPECT_TRUE(result); +} + +// Test for WDT not being fed +TEST_F(KestrelTest, FeedWDTCriticalFault) { + Kestrel kestrel = createFullyMockedKestrel(); + bool criticalFault = false; + bool fault = false; + float data[3] = {0.0, 0.0, 0.0}; + + EXPECT_CALL(mockSystem, resetReason()) + .WillOnce(::testing::Return(IResetReason::WATCHDOG)); + + EXPECT_CALL(mockAccel, getData()) + .WillRepeatedly(::testing::Return(data)); + + EXPECT_CALL(mockAccel, getOffset()) + .WillRepeatedly(::testing::Return(data)); + + EXPECT_CALL(mockIoOB, begin()) + .WillOnce(::testing::Return(0)); + + EXPECT_CALL(mockIoTalon, begin()) + .WillOnce(::testing::Return(0)); + + EXPECT_CALL(mockRtc, begin(true)) + .WillOnce(::testing::Return(true)); + + EXPECT_CALL(mockGps, begin()) + .WillRepeatedly(::testing::Return(false)); + + // We would need to verify throwError is called, but it's private + // This tests the overall begin() behavior + kestrel.begin(0, criticalFault, fault); + + bool result = kestrel.feedWDT(); + EXPECT_FALSE(result); // Should return false if critical fault is set +} + +//////////////////////////////////////////////////////////////////////////////////////// +// getTime() Tests +//////////////////////////////////////////////////////////////////////////////////////// +TEST_F(KestrelTest, GetTimeValidTimeProvider) { + Kestrel kestrel = createFullyMockedKestrel(); + + // Set up a valid time condition + EXPECT_CALL(mockTimeProvider, isValid()) + .WillRepeatedly(::testing::Return(true)); + EXPECT_CALL(mockTimeProvider, now()) + .WillRepeatedly(::testing::Return(1585699200)); // April 1, 2020 + + time_t time = kestrel.getTime(); + EXPECT_EQ(time, 1585699200); +} + +TEST_F(KestrelTest, GetTimeInvalidTimeProvider) { + Kestrel kestrel = createFullyMockedKestrel(); + + // First call: time is invalid + // Second call (after sync): time is valid + EXPECT_CALL(mockTimeProvider, isValid()) + .WillRepeatedly(::testing::Return(false)); + + EXPECT_CALL(mockTimeProvider, now()) + .WillRepeatedly(::testing::Return(1585699200)); + + // This should trigger a sync and return valid time + time_t time = kestrel.getTime(); + EXPECT_EQ(time, 0); +} +//////////////////////////////////////////////////////////////////////////////////////// +//End getTime() tests +//////////////////////////////////////////////////////////////////////////////////////// + +// // getTimeString() Tests +// TEST_F(KestrelTest, GetTimeStringValidTime) { +// Kestrel kestrel = createFullyMockedKestrel(); + +// EXPECT_CALL(mockTimeProvider, isValid()) +// .WillRepeatedly(::testing::Return(true)); +// EXPECT_CALL(mockTimeProvider, now()) +// .WillOnce(::testing::Return(1585699200)); + +// String result = kestrel.getTimeString(); +// EXPECT_EQ(result, "1585699200"); +// } + +// TEST_F(KestrelTest, TestTimeStringInvalidTime) { +// Kestrel kestrel = createFullyMockedKestrel(); + +// // Force getTime() to return 0 +// EXPECT_CALL(mockTimeProvider, isValid()) +// .WillRepeatedly(::testing::Return(false)); + +// String result = kestrel.getTimeString(); +// EXPECT_EQ(result, "null"); +// } + +// // setIndicatorState() Tests +// TEST_F(KestrelTest, SetIndicatorStateSensorsPass) { +// Kestrel kestrel = createFullyMockedKestrel(); + +// // Test SENSORS bank with PASS mode +// EXPECT_CALL(mockLed, setOutput(0, ILed::IPortState::PWM)) // Green on +// .Times(1); +// EXPECT_CALL(mockLed, setOutput(1, ILed::IPortState::Off)) // Amber off +// .Times(1); +// EXPECT_CALL(mockLed, setOutput(2, ILed::IPortState::Off)) // Red off +// .Times(1); + +// bool result = kestrel.setIndicatorState(IndicatorLight::SENSORS, IndicatorMode::PASS); +// EXPECT_EQ(result, 0); +// } + +// TEST_F(KestrelTest, SetIndicatorStateAllInit) { +// Kestrel kestrel = createFullyMockedKestrel(); + +// // Test ALL bank with INIT mode - should set all to group blink +// EXPECT_CALL(mockLed, setOutputArray(ILed::IPortState::Group)) +// .Times(1); +// EXPECT_CALL(mockLed, setGroupBlinkPeriod(250)) +// .Times(1); +// EXPECT_CALL(mockLed, setGroupOnTime(25)) +// .Times(1); + +// bool result = kestrel.setIndicatorState(IndicatorLight::ALL, IndicatorMode::INIT); +// EXPECT_EQ(result, 0); +// } + +// // updateLocation() Tests +// TEST_F(KestrelTest, UpdateLocationForceUpdate) { +// Kestrel kestrel = createFullyMockedKestrel(); + +// // Set up GPS to have a valid fix +// EXPECT_CALL(mockGps, getPVT()) +// .WillOnce(::testing::Return(true)); +// EXPECT_CALL(mockGps, getFixType()) +// .WillOnce(::testing::Return(3)); // 3D fix +// EXPECT_CALL(mockGps, getGnssFixOk()) +// .WillOnce(::testing::Return(true)); + +// EXPECT_CALL(mockGps, getLongitude()) +// .WillOnce(::testing::Return(1000000)); // Example value +// EXPECT_CALL(mockGps, getLatitude()) +// .WillOnce(::testing::Return(2000000)); // Example value +// EXPECT_CALL(mockGps, getAltitude()) +// .WillOnce(::testing::Return(3000)); // Example value + +// EXPECT_CALL(mockTimeProvider, now()) +// .WillOnce(::testing::Return(1585699200)); + +// bool result = kestrel.updateLocation(true); +// EXPECT_TRUE(result); +// } + +// TEST_F(KestrelTest, UpdateLocationNoFix) { +// Kestrel kestrel = createFullyMockedKestrel(); + +// // Set up GPS to have no fix +// EXPECT_CALL(mockGps, getPVT()) +// .WillOnce(::testing::Return(false)); + +// bool result = kestrel.updateLocation(true); +// EXPECT_FALSE(result); +// } + +// // startTimer() Tests +// TEST_F(KestrelTest, StartTimerDefaultPeriod) { +// Kestrel kestrel = createFullyMockedKestrel(); + +// // Test with period = 0 should use defaultPeriod +// EXPECT_CALL(mockRtc, setAlarm(300, true)) // defaultPeriod is 300 +// .Times(1); + +// bool result = kestrel.startTimer(0); +// EXPECT_FALSE(result); +// } + +// TEST_F(KestrelTest, StartTimerCustomPeriod) { +// Kestrel kestrel = createFullyMockedKestrel(); + +// EXPECT_CALL(mockRtc, setAlarm(600, true)) +// .Times(1); + +// bool result = kestrel.startTimer(600); +// EXPECT_FALSE(result); +// } + +// // waitUntilTimerDone() Tests +// TEST_F(KestrelTest, WaitUntilTimerDoneUnitialized) { +// Kestrel kestrel = createFullyMockedKestrel(); + +// // Without calling startTimer(), logPeriod should be 0 +// bool result = kestrel.waitUntilTimerDone(); +// EXPECT_FALSE(result); +// } + +// TEST_F(KestrelTest, WaitUntilTimerDoneSuccess) { +// Kestrel kestrel = createFullyMockedKestrel(); + +// // Start a timer first +// kestrel.startTimer(300); + +// // Set up GPIO to show clock interrupt triggered +// EXPECT_CALL(mockGpio, digitalRead(Pins::Clock_INT)) +// .WillOnce(::testing::Return(0)); // LOW = interrupt triggered + +// bool result = kestrel.waitUntilTimerDone(); +// EXPECT_TRUE(result); +// } + +// // getSensorPortString() Tests +// TEST_F(KestrelTest, GetPosLatValidLocation) { +// Kestrel kestrel = createFullyMockedKestrel(); + +// // First call should not trigger GPS update +// String result = kestrel.getPosLat(); +// EXPECT_EQ(result, "null"); // No location set yet + +// // Now set a location through updateLocation +// kestrel.updateLocation(true); // This would set latitude +// // Test requires internal state which is hard to verify +// } + +// // testForBat() Tests +// TEST_F(KestrelTest, TestForBatValidBattery) { +// Kestrel kestrel = createFullyMockedKestrel(); + +// // Set up voltage reading to indicate valid battery +// EXPECT_CALL(mockCsaAlpha, getBusVoltage(IChannel::CSA_CH1, false)) +// .WillOnce(::testing::Return(3.7f)); // Valid battery voltage + +// bool result = kestrel.testForBat(); +// EXPECT_TRUE(result); +// } + +// TEST_F(KestrelTest, TestForBatLowBattery) { +// Kestrel kestrel = createFullyMockedKestrel(); + +// // Set up voltage reading to indicate low/no battery +// EXPECT_CALL(mockCsaAlpha, getBusVoltage(IChannel::CSA_CH1, false)) +// .WillOnce(::testing::Return(1.5f)); // Low voltage + +// bool result = kestrel.testForBat(); +// EXPECT_FALSE(result); +// } + +// // getMessageID() Tests +// TEST_F(KestrelTest, GetMessageIDValidTime) { +// Kestrel kestrel = createFullyMockedKestrel(); + +// EXPECT_CALL(mockTimeProvider, now()) +// .WillOnce(::testing::Return(1000000)); +// EXPECT_CALL(mockTimeProvider, millis()) +// .WillOnce(::testing::Return(5000)); // 5 seconds + +// unsigned long id = kestrel.getMessageID(); +// EXPECT_EQ(id, 0); // 1000000 % 5 = 0 +// } + +// TEST_F(KestrelTest, GetMessageIDInvalidTime) { +// Kestrel kestrel = createFullyMockedKestrel(); + +// // When time is invalid (0), should use random number +// EXPECT_CALL(mockTimeProvider, now()) +// .WillOnce(::testing::Return(0)); + +// // Can't really test the random value, just ensure it doesn't crash +// unsigned long id = kestrel.getMessageID(); +// // Any value is acceptable for random +// } + +// // Additional edge case tests +// TEST_F(KestrelTest, EnablePowerAndDataAllPorts) { +// Kestrel kestrel = createFullyMockedKestrel(); + +// // Test enabling all ports +// for(int i = 1; i <= 5; i++) { +// kestrel.enablePower(i, true); +// kestrel.enableData(i, true); +// } + +// // Test disabling all ports +// kestrel.disablePowerAll(); +// kestrel.disableDataAll(); +// } + +// TEST_F(KestrelTest, GetDataWithSensorsEnabled) { +// Kestrel kestrel = createFullyMockedKestrel(true); // Enable sensors + +// // Set up ALS expectations +// EXPECT_CALL(mockAls, begin()).WillOnce(::testing::Return(0)); +// EXPECT_CALL(mockAls, autoRange()).WillOnce(::testing::Return(1)); + +// bool readState = false; +// EXPECT_CALL(mockAls, getValue(::testing::_, ::testing::Ref(readState))) +// .WillRepeatedly(::testing::DoAll( +// ::testing::SetArgReferee<1>(false), +// ::testing::Return(100.0f) +// )); + +// String result = kestrel.getData(0); +// EXPECT_NE(result.indexOf("\"ALS\""), -1); // Should contain ALS data +// } + +// TEST_F(KestrelTest, SelfDiagnosticLevel5Memory) { +// Kestrel kestrel = createFullyMockedKestrel(); + +// // Test low memory warning (75% used) +// EXPECT_CALL(mockSystem, freeMemory()) +// .WillOnce(::testing::Return(20000)); // Below 46800 threshold + +// String result = kestrel.selfDiagnostic(5, 0); +// // Would need to check if RAM_LOW error was thrown +// } + +// // Add tests for sleep modes +// TEST_F(KestrelTest, SleepPerformanceMode) { +// Kestrel kestrel = createFullyMockedKestrel(); + +// // Performance mode should return immediately +// int result = kestrel.sleep(); +// EXPECT_EQ(result, 0); +// } + +// TEST_F(KestrelTest, WakePerformanceMode) { +// Kestrel kestrel = createFullyMockedKestrel(); + +// // Performance mode should return immediately +// int result = kestrel.wake(); +// EXPECT_EQ(result, 0); +// } + +// // Tests for zero accelerometer +// TEST_F(KestrelTest, ZeroAccelReset) { +// Kestrel kestrel = createFullyMockedKestrel(); + +// // Test reset mode +// bool result = kestrel.zeroAccel(true); +// EXPECT_TRUE(result); +// } + +// TEST_F(KestrelTest, ZeroAccelCalibrate) { +// Kestrel kestrel = createFullyMockedKestrel(); + +// // Set up accelerometer expectations +// EXPECT_CALL(mockAccel, begin()).WillOnce(::testing::Return(0)); +// EXPECT_CALL(mockAccel, getAccel(2, ::testing::_)).WillOnce(::testing::Return(1.0f)); + +// bool result = kestrel.zeroAccel(false); +// EXPECT_FALSE(result); +// } + +// // Test I2C enable/disable functions +// TEST_F(KestrelTest, EnableI2COperations) { +// Kestrel kestrel = createFullyMockedKestrel(); + +// // Test OB I2C +// EXPECT_CALL(mockGpio, digitalRead(Pins::I2C_OB_EN)).WillOnce(::testing::Return(0)); +// EXPECT_CALL(mockGpio, pinMode(Pins::I2C_OB_EN, IPinMode::OUTPUT)); +// EXPECT_CALL(mockGpio, digitalWrite(Pins::I2C_OB_EN, true)); + +// bool prevState = kestrel.enableI2C_OB(true); +// EXPECT_FALSE(prevState); + +// // Test Global I2C +// EXPECT_CALL(mockGpio, digitalRead(Pins::I2C_GLOBAL_EN)).WillOnce(::testing::Return(1)); +// EXPECT_CALL(mockGpio, pinMode(Pins::I2C_GLOBAL_EN, IPinMode::OUTPUT)); +// EXPECT_CALL(mockGpio, digitalWrite(Pins::I2C_GLOBAL_EN, false)); + +// prevState = kestrel.enableI2C_Global(false); +// EXPECT_TRUE(prevState); +// } + +// // Test SD card operations +// TEST_F(KestrelTest, SDCardOperations) { +// Kestrel kestrel = createFullyMockedKestrel(); + +// // Test SD enable +// EXPECT_CALL(mockIoOB, digitalRead(PinsOB::SD_EN)).WillOnce(::testing::Return(0)); +// EXPECT_CALL(mockIoOB, pinMode(PinsOB::SD_EN, ::testing::_)); +// EXPECT_CALL(mockIoOB, digitalWrite(PinsOB::SD_EN, 1)); + +// bool prevState = kestrel.enableSD(true); +// EXPECT_FALSE(prevState); + +// // Test SD card detection +// EXPECT_CALL(mockIoOB, pinMode(PinsOB::SD_CD, ::testing::_)); +// EXPECT_CALL(mockIoOB, digitalRead(PinsOB::SD_CD)).WillOnce(::testing::Return(0)); + +// bool inserted = kestrel.sdInserted(); +// EXPECT_TRUE(inserted); +// } + +// // Test aux power control +// TEST_F(KestrelTest, AuxPowerControl) { +// Kestrel kestrel = createFullyMockedKestrel(); + +// EXPECT_CALL(mockIoOB, digitalRead(PinsOB::AUX_EN)).WillOnce(::testing::Return(1)); +// EXPECT_CALL(mockIoOB, pinMode(PinsOB::AUX_EN, ::testing::_)); +// EXPECT_CALL(mockIoOB, digitalWrite(PinsOB::AUX_EN, false)); + +// bool prevState = kestrel.enableAuxPower(false); +// EXPECT_TRUE(prevState); +// } + +// // Test total errors function +// TEST_F(KestrelTest, TotalErrors) { +// Kestrel kestrel = createFullyMockedKestrel(); + +// // Since we can't directly set errors, we can only test the getter +// uint8_t total = kestrel.totalErrors(); +// // Default should be 0 + 0 +// EXPECT_EQ(total, 0); +// } + +// // Test fault detection +// TEST_F(KestrelTest, GetFaultValidPort) { +// Kestrel kestrel = createFullyMockedKestrel(); + +// // Test fault present (pin LOW) +// EXPECT_CALL(mockIoTalon, digitalRead(2)).WillOnce(::testing::Return(0)); // FAULT[0] for port 1 + +// bool fault = kestrel.getFault(1); +// EXPECT_TRUE(fault); + +// // Test no fault (pin HIGH) +// EXPECT_CALL(mockIoTalon, digitalRead(2)).WillOnce(::testing::Return(1)); + +// fault = kestrel.getFault(1); +// EXPECT_FALSE(fault); +// } + +// // Test statLED function +// TEST_F(KestrelTest, StatLEDControl) { +// Kestrel kestrel = createFullyMockedKestrel(); + +// // Test LED on (state = true) +// bool result = kestrel.statLED(true); +// EXPECT_FALSE(result); // Always returns false + +// // Test LED off (state = false) +// result = kestrel.statLED(false); +// EXPECT_FALSE(result); // Always returns false +// } + +// // Test connectToCell function +// TEST_F(KestrelTest, ConnectToCellSuccess) { +// Kestrel kestrel = createFullyMockedKestrel(); + +// // Test successful connection +// EXPECT_CALL(mockCloud, connect()).Times(1); +// EXPECT_CALL(mockCloud, connected()) +// .WillRepeatedly(::testing::Return(true)); + +// bool result = kestrel.connectToCell(); +// EXPECT_TRUE(result); +// } + +// TEST_F(KestrelTest, ConnectToCellFailure) { +// Kestrel kestrel = createFullyMockedKestrel(); + +// // Test failed connection (timeout) +// EXPECT_CALL(mockCloud, connect()).Times(1); +// EXPECT_CALL(mockCloud, connected()) +// .WillRepeatedly(::testing::Return(false)); + +// bool result = kestrel.connectToCell(); +// EXPECT_FALSE(result); +// } + +// // Test releaseWDT function +// TEST_F(KestrelTest, ReleaseWDTToggle) { +// Kestrel kestrel = createFullyMockedKestrel(); + +// // First call should return false (default) and set to true +// bool result = kestrel.releaseWDT(); +// EXPECT_FALSE(result); + +// // Second call should return true (previous state) +// result = kestrel.releaseWDT(); +// EXPECT_TRUE(result); +// } + +// // Test syncTime function - limited test due to complexity +// TEST_F(KestrelTest, SyncTimeBasicOperation) { +// Kestrel kestrel = createFullyMockedKestrel(); + +// // Set up mock behavior for minimal sync time test +// EXPECT_CALL(mockRtc, getTimeUnix()) +// .WillOnce(::testing::Return(1585699200)); + +// EXPECT_CALL(mockTimeProvider, isValid()) +// .WillRepeatedly(::testing::Return(true)); + +// EXPECT_CALL(mockTimeProvider, now()) +// .WillRepeatedly(::testing::Return(1585699200)); + +// uint8_t source = kestrel.syncTime(false); +// // Hard to test specific source without more detailed setup +// EXPECT_LE(source, TimeSource::NONE); +// } + +// // Test configTalonSense function +// TEST_F(KestrelTest, ConfigTalonSense) { +// Kestrel kestrel = createFullyMockedKestrel(); + +// // Test CSA Beta configuration +// EXPECT_CALL(mockCsaBeta, setCurrentDirection(IChannel::CSA_CH4, 0)) +// .Times(1); +// EXPECT_CALL(mockCsaBeta, enableChannel(IChannel::CSA_CH1, false)) +// .Times(1); +// EXPECT_CALL(mockCsaBeta, enableChannel(IChannel::CSA_CH2, false)) +// .Times(1); +// EXPECT_CALL(mockCsaBeta, enableChannel(IChannel::CSA_CH3, false)) +// .Times(1); +// EXPECT_CALL(mockCsaBeta, enableChannel(IChannel::CSA_CH4, true)) +// .Times(1); + +// bool result = kestrel.configTalonSense(); +// EXPECT_FALSE(result); +// } + +// // Test the updateTime function +// TEST_F(KestrelTest, UpdateTimeSuccess) { +// Kestrel kestrel = createFullyMockedKestrel(); + +// // Set up time provider expectations +// EXPECT_CALL(mockTimeProvider, year()) +// .WillOnce(::testing::Return(2023)); +// EXPECT_CALL(mockTimeProvider, month()) +// .WillOnce(::testing::Return(5)); +// EXPECT_CALL(mockTimeProvider, day()) +// .WillOnce(::testing::Return(15)); +// EXPECT_CALL(mockTimeProvider, hour()) +// .WillOnce(::testing::Return(10)); +// EXPECT_CALL(mockTimeProvider, minute()) +// .WillOnce(::testing::Return(30)); +// EXPECT_CALL(mockTimeProvider, second()) +// .WillOnce(::testing::Return(45)); + +// uint8_t source = kestrel.updateTime(); +// // Hard to test specific source in isolated test +// EXPECT_LE(source, TimeSource::NONE); +// } + +// // Test getData for metadata gathering +// TEST_F(KestrelTest, GetMetadataBasicInfo) { +// Kestrel kestrel = createFullyMockedKestrel(); + +// // Set up time provider for metadata timestamp +// EXPECT_CALL(mockTimeProvider, isValid()) +// .WillRepeatedly(::testing::Return(true)); +// EXPECT_CALL(mockTimeProvider, now()) +// .WillRepeatedly(::testing::Return(1585699200)); + +// // Set up RTC UUID for metadata +// EXPECT_CALL(mockRtc, getUUIDString()) +// .WillOnce(::testing::Return("test-uuid-1234")); + +// String result = kestrel.getMetadata(); +// EXPECT_NE(result.indexOf("\"RTC UUID\":\"test-uuid-1234\""), -1); +// EXPECT_NE(result.indexOf("\"Time\":1585699200"), -1); +// } + +// // Test selfDiagnostic at different levels +// TEST_F(KestrelTest, SelfDiagnosticLevel2) { +// Kestrel kestrel = createFullyMockedKestrel(); + +// // Test with level 2 diagnostics - should include accelerometer offsets +// EXPECT_CALL(mockAccel, begin()) +// .WillOnce(::testing::Return(0)); + +// // Set up expectations for RTC register reads +// EXPECT_CALL(mockRtc, readByte(0)) +// .WillOnce(::testing::Return(0x80)); +// EXPECT_CALL(mockRtc, readByte(3)) +// .WillOnce(::testing::Return(0x38)); +// EXPECT_CALL(mockRtc, readByte(7)) +// .WillOnce(::testing::Return(0x12)); +// EXPECT_CALL(mockRtc, readByte(8)) +// .WillOnce(::testing::Return(0x34)); +// EXPECT_CALL(mockRtc, readByte(0x0D)) +// .WillOnce(::testing::Return(0x56)); +// EXPECT_CALL(mockRtc, readByte(0x14)) +// .WillOnce(::testing::Return(0x78)); + +// String result = kestrel.selfDiagnostic(2, 0); +// EXPECT_NE(result.indexOf("\"RTC_Config\""), -1); +// } + +// TEST_F(KestrelTest, SelfDiagnosticLevel3) { +// Kestrel kestrel = createFullyMockedKestrel(); + +// // Test RTC oscillator validation +// EXPECT_CALL(mockWire, beginTransmission(0x6F)) +// .Times(1); +// EXPECT_CALL(mockWire, endTransmission()) +// .WillOnce(::testing::Return(0)); + +// EXPECT_CALL(mockRtc, getTimeUnix()) +// .WillOnce(::testing::Return(1585699200)) +// .WillOnce(::testing::Return(1585699201)); // Should increment + +// EXPECT_CALL(mockTimeProvider, delay(1200)) +// .Times(1); + +// String result = kestrel.selfDiagnostic(3, 0); +// // Hard to verify all content in a simplified test +// } + +// TEST_F(KestrelTest, SelfDiagnosticLevel4) { +// Kestrel kestrel = createFullyMockedKestrel(); + +// // Test CSA setup and port readings +// EXPECT_CALL(mockIoOB, digitalWrite(PinsOB::CSA_EN, 1)) +// .Times(1); + +// EXPECT_CALL(mockCsaAlpha, begin()) +// .WillOnce(::testing::Return(true)); +// EXPECT_CALL(mockCsaBeta, begin()) +// .WillOnce(::testing::Return(true)); + +// // Setup for bus voltage readings - simplified +// bool err = false; +// EXPECT_CALL(mockCsaAlpha, getBusVoltage(::testing::_, true, ::testing::_)) +// .WillRepeatedly(::testing::DoAll( +// ::testing::SetArgReferee<2>(false), +// ::testing::Return(3.3f) +// )); + +// EXPECT_CALL(mockCsaBeta, getBusVoltage(::testing::_, true, ::testing::_)) +// .WillRepeatedly(::testing::DoAll( +// ::testing::SetArgReferee<2>(false), +// ::testing::Return(5.0f) +// )); + +// String result = kestrel.selfDiagnostic(4, 0); +// EXPECT_NE(result.indexOf("\"PORT_V\""), -1); +// } + +// // Test GPS position getters +// TEST_F(KestrelTest, PositionGetters) { +// Kestrel kestrel = createFullyMockedKestrel(); + +// // Manually set position data +// kestrel.updateLocation(true); + +// // Test position getters +// String latitude = kestrel.getPosLat(); +// String longitude = kestrel.getPosLong(); +// String altitude = kestrel.getPosAlt(); +// time_t posTime = kestrel.getPosTime(); +// String posTimeStr = kestrel.getPosTimeString(); + +// // We can't easily verify values in isolation without injection ability +// } + +// // Test error handling and reporting +// TEST_F(KestrelTest, GetErrorsFormatting) { +// Kestrel kestrel = createFullyMockedKestrel(); + +// EXPECT_CALL(mockTimeProvider, now()) +// .WillRepeatedly(::testing::Return(1585699200)); + +// // There are no errors yet, so this should return an empty string +// String errors = kestrel.getErrors(); +// // We'd need to inject errors to test this fully +// } + +// // Test enableI2C_External with proper dependencies +// TEST_F(KestrelTest, EnableI2CExternalIntegration) { +// Kestrel kestrel = createFullyMockedKestrel(); + +// // Test setup for external I2C enable +// EXPECT_CALL(mockGpio, digitalRead(Pins::I2C_GLOBAL_EN)) +// .WillOnce(::testing::Return(1)); +// EXPECT_CALL(mockGpio, digitalRead(Pins::I2C_OB_EN)) +// .WillOnce(::testing::Return(0)); + +// EXPECT_CALL(mockIoOB, digitalRead(PinsOB::I2C_EXT_EN)) +// .WillOnce(::testing::Return(0)); +// EXPECT_CALL(mockIoOB, pinMode(PinsOB::I2C_EXT_EN, ::testing::_)); +// EXPECT_CALL(mockIoOB, digitalWrite(PinsOB::I2C_EXT_EN, true)); + +// bool result = kestrel.enableI2C_External(true); +// EXPECT_FALSE(result); +// } + +// // Enhanced sleep tests with mode configuration +// TEST_F(KestrelTest, SleepBalancedMode) { +// Kestrel kestrel = createFullyMockedKestrel(); + +// // Setup for Balanced mode sleep +// // We would need to set powerSaveMode, but it's private +// // This is a limitation of the current design + +// // Set up mock for Clock_INT pin check +// EXPECT_CALL(mockGpio, digitalRead(Pins::Clock_INT)) +// .WillOnce(::testing::Return(1)); // Not triggered yet + +// // We have limited ability to test internal state changes +// int result = kestrel.sleep(); +// // Can't verify result without knowing the mode +// } + +// // Test the GPS wake path in the wake function +// TEST_F(KestrelTest, WakeWithGPSUpdate) { +// Kestrel kestrel = createFullyMockedKestrel(); + +// // Setup for GPS wake test +// // We would need to set powerSaveMode and posTime, but they're private + +// // Set up basic I2C management for wake +// EXPECT_CALL(mockGpio, digitalWrite(Pins::I2C_GLOBAL_EN, true)); +// EXPECT_CALL(mockGpio, digitalWrite(Pins::I2C_OB_EN, false)); + +// int result = kestrel.wake(); +// // Can't verify result without knowing the mode +// } + +// // Test critical fault detection in selfDiagnostic +// TEST_F(KestrelTest, SelfDiagnosticMemoryCritical) { +// Kestrel kestrel = createFullyMockedKestrel(); + +// // Test critical memory condition (90% used) +// EXPECT_CALL(mockSystem, freeMemory()) +// .WillOnce(::testing::Return(10000)); // Below 15600 threshold + +// String result = kestrel.selfDiagnostic(5, 0); +// // Would need to check if RAM_CRITICAL error was thrown +// } + +// // Test WDT feeding when there's a critical fault +// TEST_F(KestrelTest, FeedWDTWithCriticalFault) { +// Kestrel kestrel = createFullyMockedKestrel(); + +// // Set up a critical fault condition +// // We'd need a way to set criticalFault to true + +// // For now, we can only test the normal path +// bool result = kestrel.feedWDT(); +// EXPECT_TRUE(result); +// } + +// // Test accelerometer initialization fallback +// TEST_F(KestrelTest, BeginAccelerometerFallback) { +// Kestrel kestrel = createFullyMockedKestrel(); +// bool criticalFault = false; +// bool fault = false; + +// // Set up MXC6655 to fail and BMA456 to succeed +// EXPECT_CALL(mockAccel, begin()) +// .WillOnce(::testing::Return(-1)); // Fail + +// // We'd need a way to test the BMA456 fallback + +// String result = kestrel.begin(0, criticalFault, fault); +// // Hard to test fallback mechanism in isolation +// } + +// // Test the entire diagnostic sequence +// TEST_F(KestrelTest, FullDiagnosticSequence) { +// Kestrel kestrel = createFullyMockedKestrel(); + +// // Test with all diagnostic levels +// for (int level = 0; level <= 5; level++) { +// String result = kestrel.selfDiagnostic(level, 0); +// EXPECT_GT(result.length(), 0); // Check that result is not empty +// } +// } + +// // Test getData with different reportSensors settings +// TEST_F(KestrelTest, GetDataWithReportSensorsToggle) { +// // Test with sensors disabled +// { +// Kestrel kestrel = createFullyMockedKestrel(false); +// String result = kestrel.getData(0); +// EXPECT_GT(result.length(), 0); // Check that result is not empty +// } + +// // Test with sensors enabled +// { +// Kestrel kestrel = createFullyMockedKestrel(true); + +// EXPECT_CALL(mockAls, begin()) +// .WillOnce(::testing::Return(0)); +// EXPECT_CALL(mockAls, autoRange()) +// .WillOnce(::testing::Return(0)); + +// bool readState = false; +// EXPECT_CALL(mockAls, getValue(::testing::_, ::testing::Ref(readState))) +// .WillRepeatedly(::testing::DoAll( +// ::testing::SetArgReferee<1>(false), +// ::testing::Return(100.0f) +// )); + +// String result = kestrel.getData(0); +// EXPECT_GT(result.length(), 0); // Check that result is not empty +// } +// } + +// // Test time validity check in getTime +// TEST_F(KestrelTest, GetTimeWithInvalidTime) { +// Kestrel kestrel = createFullyMockedKestrel(); + +// // Setup timeProvider to report invalid time +// EXPECT_CALL(mockTimeProvider, isValid()) +// .WillRepeatedly(::testing::Return(false)); + +// // Time value should be 0 for invalid time +// time_t result = kestrel.getTime(); +// EXPECT_EQ(result, 0); +// } + +// // Test getTimeString with valid/invalid times +// TEST_F(KestrelTest, GetTimeStringValidation) { +// { +// // Test valid time +// Kestrel kestrel = createFullyMockedKestrel(); + +// EXPECT_CALL(mockTimeProvider, isValid()) +// .WillRepeatedly(::testing::Return(true)); +// EXPECT_CALL(mockTimeProvider, now()) +// .WillOnce(::testing::Return(1585699200)); + +// String result = kestrel.getTimeString(); +// EXPECT_EQ(result, "1585699200"); +// } + +// { +// // Test invalid time +// Kestrel kestrel = createFullyMockedKestrel(); + +// EXPECT_CALL(mockTimeProvider, isValid()) +// .WillRepeatedly(::testing::Return(false)); + +// String result = kestrel.getTimeString(); +// EXPECT_EQ(result, "null"); +// } +// } + +// // Test sdInserted with different card states +// TEST_F(KestrelTest, SDInsertedStates) { +// { +// // Test card inserted +// Kestrel kestrel = createFullyMockedKestrel(); + +// EXPECT_CALL(mockIoOB, pinMode(PinsOB::SD_CD, ::testing::_)); +// EXPECT_CALL(mockIoOB, digitalRead(PinsOB::SD_CD)) +// .WillOnce(::testing::Return(0)); // LOW = inserted + +// bool result = kestrel.sdInserted(); +// EXPECT_TRUE(result); +// } + +// { +// // Test card not inserted +// Kestrel kestrel = createFullyMockedKestrel(); + +// EXPECT_CALL(mockIoOB, pinMode(PinsOB::SD_CD, ::testing::_)); +// EXPECT_CALL(mockIoOB, digitalRead(PinsOB::SD_CD)) +// .WillOnce(::testing::Return(1)); // HIGH = not inserted + +// bool result = kestrel.sdInserted(); +// EXPECT_FALSE(result); +// } +// } + +// // Test setDirection function +// TEST_F(KestrelTest, SetDirectionValidPort) { +// Kestrel kestrel = createFullyMockedKestrel(); + +// // Test setting direction for port 1 +// EXPECT_CALL(mockIoTalon, pinMode(0, ::testing::_)); // SEL[0] for port 1 +// EXPECT_CALL(mockIoTalon, digitalWrite(0, true)); + +// bool result = kestrel.setDirection(1, true); +// EXPECT_FALSE(result); // Always returns false +// } + +// // Final integration test +// TEST_F(KestrelTest, CompleteLifecycleTest) { +// Kestrel kestrel = createFullyMockedKestrel(); +// bool criticalFault = false; +// bool fault = false; + +// // Set up minimal begin expectations +// EXPECT_CALL(mockSystem, on(::testing::_, ::testing::_)) +// .Times(::testing::AtLeast(1)); +// EXPECT_CALL(mockWire, isEnabled()) +// .WillRepeatedly(::testing::Return(false)); +// EXPECT_CALL(mockWire, begin()) +// .Times(::testing::AtLeast(1)); + +// // Begin the Kestrel +// kestrel.begin(0, criticalFault, fault); + +// // Test timer start/wait cycle +// kestrel.startTimer(10); // Short period for test +// bool timerResult = kestrel.waitUntilTimerDone(); + +// // Test sleep and wake cycle +// kestrel.sleep(); +// kestrel.wake(); + +// // Test WDT feeding +// bool wdtResult = kestrel.feedWDT(); + +// // Test data collection +// String data = kestrel.getData(0); +// String metadata = kestrel.getMetadata(); +// String diagnostic = kestrel.selfDiagnostic(3, 0); +// String errors = kestrel.getErrors(); + +// // Overall lifecycle test is primarily checking for crashes +// } +// // Verify Kestrel begin sets criticalFault true if ioOb.begin() fails +// // Verify Kestrel begin sets criticalFault true if ioTalon.begin() fails +// // Verify Kestrel begin sets criticalFault true if csaAlpha.begin() fails +// // Verify Kestrel begin sets criticalFault true if csaBeta.begin() fails +// // Verify Kestrel begin sets criticalFault true if led.begin() fails +// // Verify Kestrel Begin sets led functions if init is not done +// // Verify Kestrel begin sets criticalFault true if rtc.begin() fails +// // Verify Kestel begin sets criticalFault true if gps.begin() fails +// // Verify Kestrel begin sets initDone true if init is done + +// // Kestrel getErrors tests +// // Kestrel getData tests +// // Kestrel getMetadata tests +// // Kestrel selfDiagnostic tests +// // Kestrel updateLocation tests +// // Kestrel connectToCell tests +// // Kestrel enablePower tests +// // Kestrel enableData tests +// // Kestrel setDirection tests +// // Kestrel getFault tests +// // Kestrel enableI2C_OB tests +// // Kestrel enableI2C_Global tests +// // Kestrel enableI2C_External tests +// // Kestrel enableSD tests +// // Kestrel sdInserted tests +// // Kestrel enableAuxPower tests +// // Kestrel getTime tests +// // Kestrel syncTime tests +// // Kestrel startTimer tests +// // Kestrel waitUntilTimerDone tests +// // Kestrel getTimeString tests +// // Kestrel totalErrors tests +// // Kestrel statLED tests +// // Kestrel setIndicatorState tests +// // Kestrel updateTime tests +// // Kestrel feedWDT tests +// // Kestrel releaseWDT tests +// // Kestrel getPosLat tests +// // Kestrel getPosLong tests +// // Kestrel getPosAlt tests +// // Kestrel getPosTime tests +// // Kestrel getPosTimeString tests +// // Kestrel configTalonSense tests +// // Kestrel getMessageID tests +// // Kestrel testForBat tests +// // Kestrel zeroAccel tests \ No newline at end of file diff --git a/test/unit/FlightControl_Demo/FlightControl_DemoTest.cpp b/test/unit/FlightControl_Demo/FlightControl_DemoTest.cpp deleted file mode 100644 index 9c230f4..0000000 --- a/test/unit/FlightControl_Demo/FlightControl_DemoTest.cpp +++ /dev/null @@ -1,48 +0,0 @@ -// FlightControl_Demo/test/unit/Driver-_-Kestrel/kestrel_basic_test.cpp -#include "gtest/gtest.h" -#include "fff.h" -#include "MockWireDeclare.h" -#include "FlightControl_DemoTestHarness.h" - -// Test fixture -class FlightControlBasicTest : public ::testing::Test { -protected: - void SetUp() override { - // Reset all fakes before each test - RESET_FAKE(Wire_begin); - RESET_FAKE(Wire_setClock); - RESET_FAKE(Wire_beginTransmission); - RESET_FAKE(Wire_endTransmission); - RESET_FAKE(Wire_requestFrom_3args); - RESET_FAKE(Wire_requestFrom_2args); - RESET_FAKE(Wire_available); - RESET_FAKE(Wire_read); - RESET_FAKE(Wire_write_uint8); - RESET_FAKE(Wire_write_buffer); - } -}; - -// A simple test to verify that Google Test is working -TEST_F(FlightControlBasicTest, GoogleTestWorks) { - EXPECT_TRUE(true); -} - -// A test to verify that FFF is working with our mocks -TEST_F(FlightControlBasicTest, FFFWorks) { - // Call a mocked function - Wire.begin(); - - // Verify it was called - EXPECT_EQ(Wire_begin_fake.call_count, 1); -} - -TEST_F(FlightControlBasicTest, GetDataStringFormat) { - // Setup any necessary state first - - // Call the function through the harness - String result = test_harness::callGetDataString(); - - // Assert on expected format - EXPECT_TRUE(result.startsWith("{\"Data\":{")); - // More assertions -} \ No newline at end of file diff --git a/test/unit/FlightControl_Demo/FlightControl_DemoTestHarness.cpp b/test/unit/FlightControl_Demo/FlightControl_DemoTestHarness.cpp deleted file mode 100644 index 3ac3246..0000000 --- a/test/unit/FlightControl_Demo/FlightControl_DemoTestHarness.cpp +++ /dev/null @@ -1,14 +0,0 @@ -#include "FlightControl_DemoTestHarness.h" - -// Declare the functions from the original file -extern String getDataString(); -extern String getErrorString(); -extern String getDiagnosticString(uint8_t level); -extern void logEvents(uint8_t type, uint8_t destination); - -namespace FlightControl_DemoTestHarness { - String callGetDataString() { - return getDataString(); - } - // Other functions -} \ No newline at end of file diff --git a/test/unit/FlightControl_Demo/FlightControl_DemoTestHarness.h b/test/unit/FlightControl_Demo/FlightControl_DemoTestHarness.h deleted file mode 100644 index beeefff..0000000 --- a/test/unit/FlightControl_Demo/FlightControl_DemoTestHarness.h +++ /dev/null @@ -1,12 +0,0 @@ -// test/unit/FlightControl_Demo/test_harness.h -#pragma once - -#include "../../mocks/MockParticle.h" - -namespace test_harness { - String callGetDataString(); - String callGetErrorString(); - String callGetDiagnosticString(uint8_t level); - void callLogEvents(uint8_t type, uint8_t destination); - // Add more as needed -} \ No newline at end of file