Heater Handling #325

Merged
muellerr merged 78 commits from heater_handling into develop 2023-02-08 21:35:05 +01:00
49 changed files with 1099 additions and 275 deletions

View File

@ -10,10 +10,8 @@
#include "OBSWConfig.h" #include "OBSWConfig.h"
#include "devConf.h" #include "devConf.h"
#include "eive/definitions.h"
#include "fsfw/platform.h" #include "fsfw/platform.h"
#include "fsfw_tests/integration/task/TestTask.h" #include "fsfw_tests/integration/task/TestTask.h"
#include "tmtc/pusIds.h"
#if OBSW_ADD_TMTC_UDP_SERVER == 1 #if OBSW_ADD_TMTC_UDP_SERVER == 1
#include "fsfw/osal/common/UdpTcPollingTask.h" #include "fsfw/osal/common/UdpTcPollingTask.h"
@ -46,8 +44,8 @@
#include <dummies/StarTrackerDummy.h> #include <dummies/StarTrackerDummy.h>
#include <dummies/SusDummy.h> #include <dummies/SusDummy.h>
#include <dummies/SyrlinksDummy.h> #include <dummies/SyrlinksDummy.h>
#include <dummies/TemperatureSensorsDummy.h>
#include "../dummies/TemperatureSensorInserter.h"
#include "dummies/helpers.h" #include "dummies/helpers.h"
#include "mission/utility/GlobalConfigHandler.h" #include "mission/utility/GlobalConfigHandler.h"
@ -80,7 +78,7 @@ void ObjectFactory::produce(void* args) {
CfdpTmFunnel* cfdpFunnel; CfdpTmFunnel* cfdpFunnel;
ObjectFactory::produceGenericObjects(nullptr, &pusFunnel, &cfdpFunnel); ObjectFactory::produceGenericObjects(nullptr, &pusFunnel, &cfdpFunnel);
DummyGpioIF* dummyGpioIF = new DummyGpioIF(); auto* dummyGpioIF = new DummyGpioIF();
auto* dummySwitcher = new DummyPowerSwitcher(objects::PCDU_HANDLER, 18, 0); auto* dummySwitcher = new DummyPowerSwitcher(objects::PCDU_HANDLER, 18, 0);
static_cast<void>(dummyGpioIF); static_cast<void>(dummyGpioIF);
#ifdef PLATFORM_UNIX #ifdef PLATFORM_UNIX
@ -110,6 +108,14 @@ void ObjectFactory::produce(void* args) {
dummy::DummyCfg cfg; dummy::DummyCfg cfg;
dummy::createDummies(cfg, *dummySwitcher); dummy::createDummies(cfg, *dummySwitcher);
new ThermalController(objects::THERMAL_CONTROLLER);
HeaterHandler* heaterHandler = nullptr;
// new ThermalController(objects::THERMAL_CONTROLLER);
ObjectFactory::createGenericHeaterComponents(*dummyGpioIF, *dummySwitcher, heaterHandler);
if (heaterHandler == nullptr) {
sif::error << "HeaterHandler could not be created" << std::endl;
} else {
ObjectFactory::createThermalController(*heaterHandler);
}
new TestTask(objects::TEST_TASK); new TestTask(objects::TEST_TASK);
} }

View File

@ -24,7 +24,7 @@ enum sourceObjects : uint32_t {
/* 0x49 ('I') for Communication Interfaces **/ /* 0x49 ('I') for Communication Interfaces **/
ARDUINO_COM_IF = 0x49000001, ARDUINO_COM_IF = 0x49000001,
DUMMY_COM_IF = 0x49000002 DUMMY_COM_IF = 0x49000002,
}; };
} }

View File

@ -14,6 +14,7 @@
#include "OBSWConfig.h" #include "OBSWConfig.h"
#include "ObjectFactory.h" #include "ObjectFactory.h"
#include "mission/core/scheduling.h"
#include "scheduling.h" #include "scheduling.h"
#ifdef LINUX #ifdef LINUX
@ -186,6 +187,8 @@ void scheduling::initTasks() {
PeriodicTaskIF* dummyTask = factory->createPeriodicTask( PeriodicTaskIF* dummyTask = factory->createPeriodicTask(
"DUMMY_TASK", 30, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.0, missedDeadlineFunc); "DUMMY_TASK", 30, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.0, missedDeadlineFunc);
scheduling::scheduleTmpTempSensors(dummyTask);
scheduling::scheduleRtdSensors(dummyTask);
dummyTask->addComponent(objects::SUS_0_N_LOC_XFYFZM_PT_XF); dummyTask->addComponent(objects::SUS_0_N_LOC_XFYFZM_PT_XF);
dummyTask->addComponent(objects::SUS_1_N_LOC_XBYFZM_PT_XB); dummyTask->addComponent(objects::SUS_1_N_LOC_XBYFZM_PT_XB);
dummyTask->addComponent(objects::SUS_2_N_LOC_XFYBZB_PT_YB); dummyTask->addComponent(objects::SUS_2_N_LOC_XFYBZB_PT_YB);
@ -198,22 +201,6 @@ void scheduling::initTasks() {
dummyTask->addComponent(objects::SUS_9_R_LOC_XBYBZB_PT_YF); dummyTask->addComponent(objects::SUS_9_R_LOC_XBYBZB_PT_YF);
dummyTask->addComponent(objects::SUS_10_N_LOC_XMYBZF_PT_ZF); dummyTask->addComponent(objects::SUS_10_N_LOC_XMYBZF_PT_ZF);
dummyTask->addComponent(objects::SUS_11_R_LOC_XBYMZB_PT_ZB); dummyTask->addComponent(objects::SUS_11_R_LOC_XBYMZB_PT_ZB);
dummyTask->addComponent(objects::RTD_0_IC3_PLOC_HEATSPREADER);
dummyTask->addComponent(objects::RTD_1_IC4_PLOC_MISSIONBOARD);
dummyTask->addComponent(objects::RTD_2_IC5_4K_CAMERA);
dummyTask->addComponent(objects::RTD_3_IC6_DAC_HEATSPREADER);
dummyTask->addComponent(objects::RTD_4_IC7_STARTRACKER);
dummyTask->addComponent(objects::RTD_5_IC8_RW1_MX_MY);
dummyTask->addComponent(objects::RTD_6_IC9_DRO);
dummyTask->addComponent(objects::RTD_7_IC10_SCEX);
dummyTask->addComponent(objects::RTD_8_IC11_X8);
dummyTask->addComponent(objects::RTD_9_IC12_HPA);
dummyTask->addComponent(objects::RTD_10_IC13_PL_TX);
dummyTask->addComponent(objects::RTD_11_IC14_MPA);
dummyTask->addComponent(objects::RTD_12_IC15_ACU);
dummyTask->addComponent(objects::RTD_13_IC16_PLPCDU_HEATSPREADER);
dummyTask->addComponent(objects::RTD_14_IC17_TCS_BOARD);
dummyTask->addComponent(objects::RTD_15_IC18_IMTQ);
sif::info << "Starting tasks.." << std::endl; sif::info << "Starting tasks.." << std::endl;
tmtcDistributor->startTask(); tmtcDistributor->startTask();

View File

@ -3,7 +3,7 @@
#include <libgpsmm.h> #include <libgpsmm.h>
#include "test/testtasks/TestTask.h" #include "test/TestTask.h"
class CoreController; class CoreController;

View File

@ -497,7 +497,8 @@ void ObjectFactory::createAcsBoardComponents(LinuxLibgpioIF* gpioComIF, SerialCo
} }
void ObjectFactory::createHeaterComponents(GpioIF* gpioIF, PowerSwitchIF* pwrSwitcher, void ObjectFactory::createHeaterComponents(GpioIF* gpioIF, PowerSwitchIF* pwrSwitcher,
HealthTableIF* healthTable) { HealthTableIF* healthTable,
HeaterHandler*& heaterHandler) {
using namespace gpio; using namespace gpio;
GpioCookie* heaterGpiosCookie = new GpioCookie; GpioCookie* heaterGpiosCookie = new GpioCookie;
GpiodRegularByLineName* gpio = nullptr; GpiodRegularByLineName* gpio = nullptr;
@ -540,19 +541,7 @@ void ObjectFactory::createHeaterComponents(GpioIF* gpioIF, PowerSwitchIF* pwrSwi
gpioIF->addGpios(heaterGpiosCookie); gpioIF->addGpios(heaterGpiosCookie);
HeaterHelper helper({{ ObjectFactory::createGenericHeaterComponents(*gpioIF, *pwrSwitcher, heaterHandler);
{new HealthDevice(objects::HEATER_0_PLOC_PROC_BRD, MessageQueueIF::NO_QUEUE),
gpioIds::HEATER_0},
{new HealthDevice(objects::HEATER_1_PCDU_BRD, MessageQueueIF::NO_QUEUE), gpioIds::HEATER_1},
{new HealthDevice(objects::HEATER_2_ACS_BRD, MessageQueueIF::NO_QUEUE), gpioIds::HEATER_2},
{new HealthDevice(objects::HEATER_3_OBC_BRD, MessageQueueIF::NO_QUEUE), gpioIds::HEATER_3},
{new HealthDevice(objects::HEATER_4_CAMERA, MessageQueueIF::NO_QUEUE), gpioIds::HEATER_4},
{new HealthDevice(objects::HEATER_5_STR, MessageQueueIF::NO_QUEUE), gpioIds::HEATER_5},
{new HealthDevice(objects::HEATER_6_DRO, MessageQueueIF::NO_QUEUE), gpioIds::HEATER_6},
{new HealthDevice(objects::HEATER_7_HPA, MessageQueueIF::NO_QUEUE), gpioIds::HEATER_7},
}});
new HeaterHandler(objects::HEATER_HANDLER, gpioIF, helper, pwrSwitcher,
pcdu::Switches::PDU2_CH3_TCS_BOARD_HEATER_IN_8V);
} }
void ObjectFactory::createSolarArrayDeploymentComponents(PowerSwitchIF& pwrSwitcher, void ObjectFactory::createSolarArrayDeploymentComponents(PowerSwitchIF& pwrSwitcher,
@ -937,6 +926,7 @@ void ObjectFactory::createImtqComponents(PowerSwitchIF* pwrSwitcher) {
I2cCookie* imtqI2cCookie = new I2cCookie(addresses::IMTQ, IMTQ::MAX_REPLY_SIZE, q7s::I2C_PL_EIVE); I2cCookie* imtqI2cCookie = new I2cCookie(addresses::IMTQ, IMTQ::MAX_REPLY_SIZE, q7s::I2C_PL_EIVE);
auto imtqHandler = new ImtqHandler(objects::IMTQ_HANDLER, objects::I2C_COM_IF, imtqI2cCookie, auto imtqHandler = new ImtqHandler(objects::IMTQ_HANDLER, objects::I2C_COM_IF, imtqI2cCookie,
pcdu::Switches::PDU1_CH3_MGT_5V); pcdu::Switches::PDU1_CH3_MGT_5V);
imtqHandler->setThermalStateRequestPoolIds();
imtqHandler->setPowerSwitcher(pwrSwitcher); imtqHandler->setPowerSwitcher(pwrSwitcher);
imtqHandler->connectModeTreeParent(satsystem::acs::ACS_SUBSYSTEM); imtqHandler->connectModeTreeParent(satsystem::acs::ACS_SUBSYSTEM);
static_cast<void>(imtqHandler); static_cast<void>(imtqHandler);

View File

@ -2,6 +2,7 @@
#define BSP_Q7S_OBJECTFACTORY_H_ #define BSP_Q7S_OBJECTFACTORY_H_
#include <fsfw/returnvalues/returnvalue.h> #include <fsfw/returnvalues/returnvalue.h>
#include <mission/devices/HeaterHandler.h>
#include <mission/system/objects/Stack5VHandler.h> #include <mission/system/objects/Stack5VHandler.h>
#include <mission/tmtc/CcsdsIpCoreHandler.h> #include <mission/tmtc/CcsdsIpCoreHandler.h>
#include <mission/tmtc/CfdpTmFunnel.h> #include <mission/tmtc/CfdpTmFunnel.h>
@ -33,7 +34,8 @@ void createTmpComponents();
ReturnValue_t createRadSensorComponent(LinuxLibgpioIF* gpioComIF, Stack5VHandler& handler); ReturnValue_t createRadSensorComponent(LinuxLibgpioIF* gpioComIF, Stack5VHandler& handler);
void createAcsBoardComponents(LinuxLibgpioIF* gpioComIF, SerialComIF* uartComIF, void createAcsBoardComponents(LinuxLibgpioIF* gpioComIF, SerialComIF* uartComIF,
PowerSwitchIF* pwrSwitcher); PowerSwitchIF* pwrSwitcher);
void createHeaterComponents(GpioIF* gpioIF, PowerSwitchIF* pwrSwitcher, HealthTableIF* healthTable); void createHeaterComponents(GpioIF* gpioIF, PowerSwitchIF* pwrSwitcher, HealthTableIF* healthTable,
HeaterHandler*& heaterHandler);
void createImtqComponents(PowerSwitchIF* pwrSwitcher); void createImtqComponents(PowerSwitchIF* pwrSwitcher);
void createBpxBatteryComponent(); void createBpxBatteryComponent();
void createStrComponents(PowerSwitchIF* pwrSwitcher); void createStrComponents(PowerSwitchIF* pwrSwitcher);

View File

@ -17,6 +17,7 @@
#include "fsfw/tasks/FixedTimeslotTaskIF.h" #include "fsfw/tasks/FixedTimeslotTaskIF.h"
#include "fsfw/tasks/PeriodicTaskIF.h" #include "fsfw/tasks/PeriodicTaskIF.h"
#include "fsfw/tasks/TaskFactory.h" #include "fsfw/tasks/TaskFactory.h"
#include "mission/core/scheduling.h"
#include "mission/devices/devicedefinitions/Max31865Definitions.h" #include "mission/devices/devicedefinitions/Max31865Definitions.h"
#include "mission/utility/InitMission.h" #include "mission/utility/InitMission.h"
#include "pollingsequence/pollingSequenceFactory.h" #include "pollingsequence/pollingSequenceFactory.h"
@ -219,32 +220,7 @@ void scheduling::initTasks() {
PeriodicTaskIF* tcsTask = factory->createPeriodicTask( PeriodicTaskIF* tcsTask = factory->createPeriodicTask(
"TCS_TASK", 45, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.8, missedDeadlineFunc); "TCS_TASK", 45, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.8, missedDeadlineFunc);
std::array<object_id_t, EiveMax31855::NUM_RTDS> rtdIds = { scheduling::scheduleRtdSensors(tcsTask);
objects::RTD_0_IC3_PLOC_HEATSPREADER,
objects::RTD_1_IC4_PLOC_MISSIONBOARD,
objects::RTD_2_IC5_4K_CAMERA,
objects::RTD_3_IC6_DAC_HEATSPREADER,
objects::RTD_4_IC7_STARTRACKER,
objects::RTD_5_IC8_RW1_MX_MY,
objects::RTD_6_IC9_DRO,
objects::RTD_7_IC10_SCEX,
objects::RTD_8_IC11_X8,
objects::RTD_9_IC12_HPA,
objects::RTD_10_IC13_PL_TX,
objects::RTD_11_IC14_MPA,
objects::RTD_12_IC15_ACU,
objects::RTD_13_IC16_PLPCDU_HEATSPREADER,
objects::RTD_14_IC17_TCS_BOARD,
objects::RTD_15_IC18_IMTQ,
};
for (const auto& rtd : rtdIds) {
tcsTask->addComponent(rtd, DeviceHandlerIF::PERFORM_OPERATION);
tcsTask->addComponent(rtd, DeviceHandlerIF::SEND_WRITE);
tcsTask->addComponent(rtd, DeviceHandlerIF::GET_WRITE);
tcsTask->addComponent(rtd, DeviceHandlerIF::SEND_READ);
tcsTask->addComponent(rtd, DeviceHandlerIF::GET_READ);
}
#endif #endif
PeriodicTaskIF* tcsSystemTask = factory->createPeriodicTask( PeriodicTaskIF* tcsSystemTask = factory->createPeriodicTask(

View File

@ -45,7 +45,8 @@ void ObjectFactory::produce(void* args) {
#if OBSW_ADD_ACS_BOARD == 1 #if OBSW_ADD_ACS_BOARD == 1
createAcsBoardComponents(gpioComIF, uartComIF, pwrSwitcher); createAcsBoardComponents(gpioComIF, uartComIF, pwrSwitcher);
#endif #endif
createHeaterComponents(gpioComIF, pwrSwitcher, healthTable); HeaterHandler* heaterHandler;
createHeaterComponents(gpioComIF, pwrSwitcher, healthTable, heaterHandler);
#if OBSW_ADD_TMP_DEVICES == 1 #if OBSW_ADD_TMP_DEVICES == 1
createTmpComponents(); createTmpComponents();
#endif #endif
@ -87,7 +88,7 @@ void ObjectFactory::produce(void* args) {
#endif /* OBSW_ADD_TEST_CODE == 1 */ #endif /* OBSW_ADD_TEST_CODE == 1 */
createMiscComponents(); createMiscComponents();
createThermalController(); createThermalController(*heaterHandler);
createAcsController(true); createAcsController(true);
satsystem::init(); satsystem::init();
} }

View File

@ -12,7 +12,7 @@ enum Switchers : uint8_t {
HEATER_4_CAMERA, HEATER_4_CAMERA,
HEATER_5_STR, HEATER_5_STR,
HEATER_6_DRO, HEATER_6_DRO,
HEATER_7_HPA, HEATER_7_S_BAND,
NUMBER_OF_SWITCHES NUMBER_OF_SWITCHES
}; };
} }

View File

@ -36,6 +36,7 @@ enum : uint8_t {
SCEX_HANDLER = 138, SCEX_HANDLER = 138,
CONFIGHANDLER = 139, CONFIGHANDLER = 139,
CORE = 140, CORE = 140,
TCS_CONTROLLER = 141,
COMMON_SUBSYSTEM_ID_END COMMON_SUBSYSTEM_ID_END
}; };

View File

@ -50,8 +50,7 @@ enum commonObjects : uint32_t {
TMP1075_HANDLER_PLPCDU_0 = 0x44420006, TMP1075_HANDLER_PLPCDU_0 = 0x44420006,
TMP1075_HANDLER_PLPCDU_1 = 0x44420007, TMP1075_HANDLER_PLPCDU_1 = 0x44420007,
TMP1075_HANDLER_IF_BOARD = 0x44420008, TMP1075_HANDLER_IF_BOARD = 0x44420008,
// Does not exist anymore
// TMP1075_HANDLER_OBC_IF_BOARD = 0x44420009,
PCDU_HANDLER = 0x442000A1, PCDU_HANDLER = 0x442000A1,
P60DOCK_HANDLER = 0x44250000, P60DOCK_HANDLER = 0x44250000,
PDU1_HANDLER = 0x44250001, PDU1_HANDLER = 0x44250001,
@ -152,6 +151,9 @@ enum commonObjects : uint32_t {
CFDP_TM_FUNNEL = 0x73000102, CFDP_TM_FUNNEL = 0x73000102,
CFDP_HANDLER = 0x73000205, CFDP_HANDLER = 0x73000205,
CFDP_DISTRIBUTOR = 0x73000206, CFDP_DISTRIBUTOR = 0x73000206,
// Other stuff
THERMAL_TEMP_INSERTER = 0x90000003,
}; };
} }

View File

@ -1,11 +1,12 @@
target_sources( target_sources(
${LIB_DUMMIES} ${LIB_DUMMIES}
PUBLIC TemperatureSensorsDummy.cpp PUBLIC TemperatureSensorInserter.cpp
SusDummy.cpp SusDummy.cpp
BpxDummy.cpp BpxDummy.cpp
ComIFDummy.cpp ComIFDummy.cpp
ComCookieDummy.cpp ComCookieDummy.cpp
RwDummy.cpp RwDummy.cpp
Max31865Dummy.cpp
StarTrackerDummy.cpp StarTrackerDummy.cpp
SyrlinksDummy.cpp SyrlinksDummy.cpp
ImtqDummy.cpp ImtqDummy.cpp
@ -20,4 +21,5 @@ target_sources(
PlPcduDummy.cpp PlPcduDummy.cpp
CoreControllerDummy.cpp CoreControllerDummy.cpp
helpers.cpp helpers.cpp
MgmRm3100Dummy.cpp) MgmRm3100Dummy.cpp
Tmp1075Dummy.cpp)

View File

@ -5,7 +5,7 @@
ImtqDummy::ImtqDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie) ImtqDummy::ImtqDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie)
: DeviceHandlerBase(objectId, comif, comCookie) {} : DeviceHandlerBase(objectId, comif, comCookie) {}
ImtqDummy::~ImtqDummy() {} ImtqDummy::~ImtqDummy() = default;
void ImtqDummy::doStartUp() {} void ImtqDummy::doStartUp() {}

View File

@ -12,7 +12,7 @@ class ImtqDummy : public DeviceHandlerBase {
static const uint8_t PERIODIC_REPLY_DATA = 2; static const uint8_t PERIODIC_REPLY_DATA = 2;
ImtqDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie); ImtqDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie);
virtual ~ImtqDummy(); ~ImtqDummy() override;
protected: protected:
void doStartUp() override; void doStartUp() override;

45
dummies/Max31865Dummy.cpp Normal file
View File

@ -0,0 +1,45 @@
#include "Max31865Dummy.h"
using namespace returnvalue;
Max31865Dummy::Max31865Dummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie)
: DeviceHandlerBase(objectId, comif, comCookie), set(this, EiveMax31855::EXCHANGE_SET_ID) {}
void Max31865Dummy::doStartUp() { setMode(MODE_ON); }
void Max31865Dummy::doShutDown() { setMode(_MODE_POWER_DOWN); }
ReturnValue_t Max31865Dummy::buildNormalDeviceCommand(DeviceCommandId_t *id) {
return NOTHING_TO_SEND;
}
ReturnValue_t Max31865Dummy::buildTransitionDeviceCommand(DeviceCommandId_t *id) { return OK; }
ReturnValue_t Max31865Dummy::buildCommandFromCommand(DeviceCommandId_t deviceCommand,
const uint8_t *commandData,
size_t commandDataLen) {
return 0;
}
ReturnValue_t Max31865Dummy::scanForReply(const uint8_t *start, size_t len,
DeviceCommandId_t *foundId, size_t *foundLen) {
return 0;
}
ReturnValue_t Max31865Dummy::interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) {
return 0;
}
void Max31865Dummy::fillCommandAndReplyMap() {}
uint32_t Max31865Dummy::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { return 0; }
ReturnValue_t Max31865Dummy::initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
LocalDataPoolManager &poolManager) {
using namespace MAX31865;
localDataPoolMap.emplace(static_cast<lp_id_t>(PoolIds::RTD_VALUE), new PoolEntry<float>({0}));
localDataPoolMap.emplace(static_cast<lp_id_t>(PoolIds::TEMPERATURE_C), new PoolEntry<float>({0}));
localDataPoolMap.emplace(static_cast<lp_id_t>(PoolIds::LAST_FAULT_BYTE),
new PoolEntry<uint8_t>({0}));
localDataPoolMap.emplace(static_cast<lp_id_t>(PoolIds::FAULT_BYTE), new PoolEntry<uint8_t>({0}));
return OK;
}
void Max31865Dummy::setTemperature(float temperature) {
set.temperatureCelcius.value = temperature;
}
LocalPoolDataSetBase *Max31865Dummy::getDataSetHandle(sid_t sid) { return &set; }
Max31865Dummy::Max31865Dummy(object_id_t objectId, CookieIF *cookie)
: DeviceHandlerBase(objectId, objects::DUMMY_COM_IF, cookie),
set(this, EiveMax31855::EXCHANGE_SET_ID) {}

33
dummies/Max31865Dummy.h Normal file
View File

@ -0,0 +1,33 @@
#ifndef EIVE_OBSW_MAX31865DUMMY_H
#define EIVE_OBSW_MAX31865DUMMY_H
#include "fsfw/devicehandlers/DeviceHandlerBase.h"
#include "mission/devices/devicedefinitions/Max31865Definitions.h"
class Max31865Dummy : public DeviceHandlerBase {
public:
Max31865Dummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie);
Max31865Dummy(object_id_t objectId, CookieIF *comCookie);
void setTemperature(float temperature);
private:
MAX31865::PrimarySet set;
void doStartUp() override;
void doShutDown() override;
ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t *id) override;
ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t *id) override;
ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, const uint8_t *commandData,
size_t commandDataLen) override;
ReturnValue_t scanForReply(const uint8_t *start, size_t len, DeviceCommandId_t *foundId,
size_t *foundLen) override;
ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) override;
void fillCommandAndReplyMap() override;
uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override;
ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
LocalDataPoolManager &poolManager) override;
LocalPoolDataSetBase *getDataSetHandle(sid_t sid) override;
};
#endif // EIVE_OBSW_MAX31865DUMMY_H

View File

@ -0,0 +1,39 @@
#include "TemperatureSensorInserter.h"
#include <objects/systemObjectList.h>
#include <cmath>
#include <cstdlib>
TemperatureSensorInserter::TemperatureSensorInserter(object_id_t objectId,
const Max31865DummyMap& tempSensorDummies_,
const Tmp1075DummyMap& tempTmpSensorDummies_)
: SystemObject(objects::THERMAL_TEMP_INSERTER),
max31865DummyMap(tempSensorDummies_),
tmp1075DummyMap(tempTmpSensorDummies_) {}
ReturnValue_t TemperatureSensorInserter::initialize() {
if (performTest) {
if (testCase == TestCase::COOL_SYRLINKS) {
}
}
return returnvalue::OK;
}
ReturnValue_t TemperatureSensorInserter::performOperation(uint8_t opCode) {
/*
ReturnValue_t result = max31865PlocHeatspreaderSet.read();
if (result != returnvalue::OK) {
sif::warning << "Failed to read temperature from MAX31865 dataset" << std::endl;
}
max31865PlocHeatspreaderSet.rtdValue = value - 5;
max31865PlocHeatspreaderSet.temperatureCelcius = value;
if ((iteration % 100) < 20) {
max31865PlocHeatspreaderSet.setValidity(false, true);
} else {
max31865PlocHeatspreaderSet.setValidity(true, true);
}
max31865PlocHeatspreaderSet.commit();
*/
return returnvalue::OK;
}

View File

@ -0,0 +1,31 @@
#pragma once
#include <fsfw/controller/ExtendedControllerBase.h>
#include <mission/devices/devicedefinitions/Max31865Definitions.h>
#include "Max31865Dummy.h"
#include "Tmp1075Dummy.h"
class TemperatureSensorInserter : public ExecutableObjectIF, public SystemObject {
public:
using Max31865DummyMap = std::map<object_id_t, Max31865Dummy*>;
using Tmp1075DummyMap = std::map<object_id_t, Tmp1075Dummy*>;
explicit TemperatureSensorInserter(object_id_t objectId,
const Max31865DummyMap& tempSensorDummies_,
const Tmp1075DummyMap& tempTmpSensorDummies_);
ReturnValue_t initialize() override;
protected:
ReturnValue_t performOperation(uint8_t opCode) override;
private:
Max31865DummyMap max31865DummyMap;
Tmp1075DummyMap tmp1075DummyMap;
enum TestCase { NONE = 0, COOL_SYRLINKS = 1 };
int iteration = 0;
bool performTest = false;
TestCase testCase = TestCase::NONE;
// void noise();
};

View File

@ -1,102 +0,0 @@
#include "TemperatureSensorsDummy.h"
#include <objects/systemObjectList.h>
#include <cmath>
#include <cstdlib>
TemperatureSensorsDummy::TemperatureSensorsDummy()
: ExtendedControllerBase(objects::RTD_0_IC3_PLOC_HEATSPREADER),
max31865Set(this, MAX31865::MAX31865_SET_ID) {
ObjectManager::instance()->insert(objects::RTD_1_IC4_PLOC_MISSIONBOARD, this);
ObjectManager::instance()->insert(objects::RTD_2_IC5_4K_CAMERA, this);
ObjectManager::instance()->insert(objects::RTD_3_IC6_DAC_HEATSPREADER, this);
ObjectManager::instance()->insert(objects::RTD_4_IC7_STARTRACKER, this);
ObjectManager::instance()->insert(objects::RTD_5_IC8_RW1_MX_MY, this);
ObjectManager::instance()->insert(objects::RTD_6_IC9_DRO, this);
ObjectManager::instance()->insert(objects::RTD_7_IC10_SCEX, this);
ObjectManager::instance()->insert(objects::RTD_8_IC11_X8, this);
ObjectManager::instance()->insert(objects::RTD_9_IC12_HPA, this);
ObjectManager::instance()->insert(objects::RTD_10_IC13_PL_TX, this);
ObjectManager::instance()->insert(objects::RTD_11_IC14_MPA, this);
ObjectManager::instance()->insert(objects::RTD_12_IC15_ACU, this);
ObjectManager::instance()->insert(objects::RTD_13_IC16_PLPCDU_HEATSPREADER, this);
ObjectManager::instance()->insert(objects::RTD_14_IC17_TCS_BOARD, this);
ObjectManager::instance()->insert(objects::RTD_15_IC18_IMTQ, this);
ObjectManager::instance()->insert(objects::TMP1075_HANDLER_TCS_0, this);
ObjectManager::instance()->insert(objects::TMP1075_HANDLER_TCS_1, this);
ObjectManager::instance()->insert(objects::TMP1075_HANDLER_PLPCDU_0, this);
ObjectManager::instance()->insert(objects::TMP1075_HANDLER_PLPCDU_1, this);
ObjectManager::instance()->insert(objects::TMP1075_HANDLER_IF_BOARD, this);
}
ReturnValue_t TemperatureSensorsDummy::initialize() {
static bool done = false;
if (not done) {
done = true;
ReturnValue_t result = ExtendedControllerBase::initialize();
if (result != returnvalue::OK) {
return result;
}
}
return returnvalue::OK;
}
ReturnValue_t TemperatureSensorsDummy::handleCommandMessage(CommandMessage* message) {
return returnvalue::FAILED;
}
void TemperatureSensorsDummy::performControlOperation() {
iteration++;
value = sin(iteration / 80. * M_PI) * 10;
ReturnValue_t result = max31865Set.read();
if (result != returnvalue::OK) {
sif::warning << "Failed to read temperature from MAX31865 dataset" << std::endl;
}
max31865Set.rtdValue = value - 5;
max31865Set.temperatureCelcius = value;
if ((iteration % 100) < 20) {
max31865Set.setValidity(false, true);
} else {
max31865Set.setValidity(true, true);
}
max31865Set.commit();
}
ReturnValue_t TemperatureSensorsDummy::initializeLocalDataPool(
localpool::DataPool& localDataPoolMap, LocalDataPoolManager& poolManager) {
localDataPoolMap.emplace(static_cast<lp_id_t>(MAX31865::PoolIds::RTD_VALUE),
new PoolEntry<float>({0}));
localDataPoolMap.emplace(static_cast<lp_id_t>(MAX31865::PoolIds::TEMPERATURE_C),
new PoolEntry<float>({0}));
localDataPoolMap.emplace(static_cast<lp_id_t>(MAX31865::PoolIds::LAST_FAULT_BYTE),
new PoolEntry<uint8_t>({0}));
localDataPoolMap.emplace(static_cast<lp_id_t>(MAX31865::PoolIds::FAULT_BYTE),
new PoolEntry<uint8_t>({0}));
return returnvalue::OK;
}
LocalPoolDataSetBase* TemperatureSensorsDummy::getDataSetHandle(sid_t sid) {
sif::debug << "getHandle" << std::endl;
switch (sid.ownerSetId) {
case MAX31865::MAX31865_SET_ID:
return &max31865Set;
default:
return nullptr;
}
}
ReturnValue_t TemperatureSensorsDummy::checkModeCommand(Mode_t mode, Submode_t submode,
uint32_t* msToReachTheMode) {
if (submode != SUBMODE_NONE) {
return INVALID_SUBMODE;
}
if ((mode != MODE_OFF) && (mode != MODE_ON) && (mode != MODE_NORMAL)) {
return INVALID_MODE;
}
return returnvalue::OK;
}

View File

@ -1,29 +0,0 @@
#pragma once
#include <fsfw/controller/ExtendedControllerBase.h>
#include <mission/devices/devicedefinitions/Max31865Definitions.h>
class TemperatureSensorsDummy : public ExtendedControllerBase {
public:
TemperatureSensorsDummy();
ReturnValue_t initialize() override;
protected:
virtual ReturnValue_t handleCommandMessage(CommandMessage* message) override;
virtual void performControlOperation() override;
virtual ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap,
LocalDataPoolManager& poolManager) override;
virtual LocalPoolDataSetBase* getDataSetHandle(sid_t sid) override;
// Mode abstract functions
virtual ReturnValue_t checkModeCommand(Mode_t mode, Submode_t submode,
uint32_t* msToReachTheMode) override;
private:
int iteration = 0;
float value = 0;
MAX31865::Max31865Set max31865Set;
void noise();
};

34
dummies/Tmp1075Dummy.cpp Normal file
View File

@ -0,0 +1,34 @@
#include "Tmp1075Dummy.h"
#include "mission/devices/devicedefinitions/Tmp1075Definitions.h"
using namespace returnvalue;
Tmp1075Dummy::Tmp1075Dummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie)
: DeviceHandlerBase(objectId, comif, comCookie), set(this) {}
void Tmp1075Dummy::doStartUp() { setMode(MODE_ON); }
void Tmp1075Dummy::doShutDown() { setMode(_MODE_POWER_DOWN); }
ReturnValue_t Tmp1075Dummy::buildNormalDeviceCommand(DeviceCommandId_t *id) {
return NOTHING_TO_SEND;
}
ReturnValue_t Tmp1075Dummy::buildTransitionDeviceCommand(DeviceCommandId_t *id) { return OK; }
ReturnValue_t Tmp1075Dummy::buildCommandFromCommand(DeviceCommandId_t deviceCommand,
const uint8_t *commandData,
size_t commandDataLen) {
return 0;
}
ReturnValue_t Tmp1075Dummy::scanForReply(const uint8_t *start, size_t len,
DeviceCommandId_t *foundId, size_t *foundLen) {
return 0;
}
ReturnValue_t Tmp1075Dummy::interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) {
return 0;
}
void Tmp1075Dummy::fillCommandAndReplyMap() {}
uint32_t Tmp1075Dummy::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { return 1000; }
ReturnValue_t Tmp1075Dummy::initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
LocalDataPoolManager &poolManager) {
localDataPoolMap.emplace(TMP1075::TEMPERATURE_C_TMP1075, new PoolEntry<float>({0.0}));
return OK;
}
LocalPoolDataSetBase *Tmp1075Dummy::getDataSetHandle(sid_t sid) { return &set; }

32
dummies/Tmp1075Dummy.h Normal file
View File

@ -0,0 +1,32 @@
#ifndef EIVE_OBSW_TMP1075DUMMY_H
#define EIVE_OBSW_TMP1075DUMMY_H
#include "fsfw/devicehandlers/DeviceHandlerBase.h"
#include "mission/devices/devicedefinitions/Tmp1075Definitions.h"
class Tmp1075Dummy : public DeviceHandlerBase {
public:
Tmp1075Dummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie);
private:
TMP1075::Tmp1075Dataset set;
void doStartUp() override;
void doShutDown() override;
ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t *id) override;
ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t *id) override;
ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, const uint8_t *commandData,
size_t commandDataLen) override;
ReturnValue_t scanForReply(const uint8_t *start, size_t len, DeviceCommandId_t *foundId,
size_t *foundLen) override;
ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) override;
void fillCommandAndReplyMap() override;
uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override;
ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
LocalDataPoolManager &poolManager) override;
protected:
LocalPoolDataSetBase *getDataSetHandle(sid_t sid) override;
};
#endif // EIVE_OBSW_TMP1075DUMMY_H

View File

@ -19,14 +19,17 @@
#include <dummies/StarTrackerDummy.h> #include <dummies/StarTrackerDummy.h>
#include <dummies/SusDummy.h> #include <dummies/SusDummy.h>
#include <dummies/SyrlinksDummy.h> #include <dummies/SyrlinksDummy.h>
#include <dummies/TemperatureSensorsDummy.h>
#include <mission/system/objects/CamSwitcher.h> #include <mission/system/objects/CamSwitcher.h>
#include "TemperatureSensorInserter.h"
#include "dummies/Max31865Dummy.h"
#include "dummies/Tmp1075Dummy.h"
using namespace dummy; using namespace dummy;
void dummy::createDummies(DummyCfg cfg, PowerSwitchIF& pwrSwitch) { void dummy::createDummies(DummyCfg cfg, PowerSwitchIF& pwrSwitch) {
new ComIFDummy(objects::DUMMY_COM_IF); new ComIFDummy(objects::DUMMY_COM_IF);
ComCookieDummy* comCookieDummy = new ComCookieDummy(); auto* comCookieDummy = new ComCookieDummy();
new BpxDummy(objects::BPX_BATT_HANDLER, objects::DUMMY_COM_IF, comCookieDummy); new BpxDummy(objects::BPX_BATT_HANDLER, objects::DUMMY_COM_IF, comCookieDummy);
if (cfg.addCoreCtrlCfg) { if (cfg.addCoreCtrlCfg) {
new CoreControllerDummy(objects::CORE_CONTROLLER); new CoreControllerDummy(objects::CORE_CONTROLLER);
@ -79,7 +82,75 @@ void dummy::createDummies(DummyCfg cfg, PowerSwitchIF& pwrSwitch) {
} }
if (cfg.addTempSensorDummies) { if (cfg.addTempSensorDummies) {
new TemperatureSensorsDummy(); std::map<object_id_t, Max31865Dummy*> tempSensorDummies;
tempSensorDummies.emplace(objects::RTD_0_IC3_PLOC_HEATSPREADER,
new Max31865Dummy(objects::RTD_0_IC3_PLOC_HEATSPREADER,
objects::DUMMY_COM_IF, comCookieDummy));
tempSensorDummies.emplace(objects::RTD_1_IC4_PLOC_MISSIONBOARD,
new Max31865Dummy(objects::RTD_1_IC4_PLOC_MISSIONBOARD,
objects::DUMMY_COM_IF, comCookieDummy));
tempSensorDummies.emplace(
objects::RTD_2_IC5_4K_CAMERA,
new Max31865Dummy(objects::RTD_2_IC5_4K_CAMERA, objects::DUMMY_COM_IF, comCookieDummy));
tempSensorDummies.emplace(objects::RTD_3_IC6_DAC_HEATSPREADER,
new Max31865Dummy(objects::RTD_3_IC6_DAC_HEATSPREADER,
objects::DUMMY_COM_IF, comCookieDummy));
tempSensorDummies.emplace(
objects::RTD_4_IC7_STARTRACKER,
new Max31865Dummy(objects::RTD_4_IC7_STARTRACKER, objects::DUMMY_COM_IF, comCookieDummy));
tempSensorDummies.emplace(
objects::RTD_5_IC8_RW1_MX_MY,
new Max31865Dummy(objects::RTD_5_IC8_RW1_MX_MY, objects::DUMMY_COM_IF, comCookieDummy));
tempSensorDummies.emplace(
objects::RTD_6_IC9_DRO,
new Max31865Dummy(objects::RTD_6_IC9_DRO, objects::DUMMY_COM_IF, comCookieDummy));
tempSensorDummies.emplace(
objects::RTD_7_IC10_SCEX,
new Max31865Dummy(objects::RTD_7_IC10_SCEX, objects::DUMMY_COM_IF, comCookieDummy));
tempSensorDummies.emplace(
objects::RTD_8_IC11_X8,
new Max31865Dummy(objects::RTD_8_IC11_X8, objects::DUMMY_COM_IF, comCookieDummy));
tempSensorDummies.emplace(
objects::RTD_9_IC12_HPA,
new Max31865Dummy(objects::RTD_9_IC12_HPA, objects::DUMMY_COM_IF, comCookieDummy));
tempSensorDummies.emplace(
objects::RTD_10_IC13_PL_TX,
new Max31865Dummy(objects::RTD_10_IC13_PL_TX, objects::DUMMY_COM_IF, comCookieDummy));
tempSensorDummies.emplace(
objects::RTD_11_IC14_MPA,
new Max31865Dummy(objects::RTD_11_IC14_MPA, objects::DUMMY_COM_IF, comCookieDummy));
tempSensorDummies.emplace(
objects::RTD_12_IC15_ACU,
new Max31865Dummy(objects::RTD_12_IC15_ACU, objects::DUMMY_COM_IF, comCookieDummy));
tempSensorDummies.emplace(objects::RTD_13_IC16_PLPCDU_HEATSPREADER,
new Max31865Dummy(objects::RTD_13_IC16_PLPCDU_HEATSPREADER,
objects::DUMMY_COM_IF, comCookieDummy));
tempSensorDummies.emplace(
objects::RTD_14_IC17_TCS_BOARD,
new Max31865Dummy(objects::RTD_14_IC17_TCS_BOARD, objects::DUMMY_COM_IF, comCookieDummy));
tempSensorDummies.emplace(
objects::RTD_15_IC18_IMTQ,
new Max31865Dummy(objects::RTD_15_IC18_IMTQ, objects::DUMMY_COM_IF, comCookieDummy));
std::map<object_id_t, Tmp1075Dummy*> tempTmpSensorDummies;
tempTmpSensorDummies.emplace(
objects::TMP1075_HANDLER_TCS_0,
new Tmp1075Dummy(objects::TMP1075_HANDLER_TCS_0, objects::DUMMY_COM_IF, comCookieDummy));
tempTmpSensorDummies.emplace(
objects::TMP1075_HANDLER_TCS_1,
new Tmp1075Dummy(objects::TMP1075_HANDLER_TCS_1, objects::DUMMY_COM_IF, comCookieDummy));
tempTmpSensorDummies.emplace(
objects::TMP1075_HANDLER_PLPCDU_0,
new Tmp1075Dummy(objects::TMP1075_HANDLER_PLPCDU_0, objects::DUMMY_COM_IF, comCookieDummy));
tempTmpSensorDummies.emplace(
objects::TMP1075_HANDLER_PLPCDU_1,
new Tmp1075Dummy(objects::TMP1075_HANDLER_PLPCDU_1, objects::DUMMY_COM_IF, comCookieDummy));
tempTmpSensorDummies.emplace(
objects::TMP1075_HANDLER_IF_BOARD,
new Tmp1075Dummy(objects::TMP1075_HANDLER_IF_BOARD, objects::DUMMY_COM_IF, comCookieDummy));
new TemperatureSensorInserter(objects::THERMAL_TEMP_INSERTER, tempSensorDummies,
tempTmpSensorDummies);
} }
new CamSwitcher(objects::CAM_SWITCHER, pwrSwitch, power::NO_SWITCH); new CamSwitcher(objects::CAM_SWITCHER, pwrSwitch, power::NO_SWITCH);
new PlPcduDummy(objects::PLPCDU_HANDLER, objects::DUMMY_COM_IF, comCookieDummy); new PlPcduDummy(objects::PLPCDU_HANDLER, objects::DUMMY_COM_IF, comCookieDummy);

View File

@ -11,21 +11,19 @@
#include <linux/callbacks/gpioCallbacks.h> #include <linux/callbacks/gpioCallbacks.h>
#include <linux/devices/Max31865RtdLowlevelHandler.h> #include <linux/devices/Max31865RtdLowlevelHandler.h>
#include <mission/controller/AcsController.h> #include <mission/controller/AcsController.h>
#include <mission/controller/ThermalController.h>
#include <mission/devices/Max31865EiveHandler.h> #include <mission/devices/Max31865EiveHandler.h>
#include <mission/devices/Max31865PT1000Handler.h>
#include <mission/devices/ScexDeviceHandler.h> #include <mission/devices/ScexDeviceHandler.h>
#include <mission/devices/SusHandler.h> #include <mission/devices/SusHandler.h>
#include <mission/system/fdir/RtdFdir.h> #include <mission/system/fdir/RtdFdir.h>
#include <mission/system/fdir/SusFdir.h> #include <mission/system/fdir/SusFdir.h>
#include <mission/system/objects/SusAssembly.h>
#include <mission/system/objects/TcsBoardAssembly.h>
#include "OBSWConfig.h" #include "OBSWConfig.h"
#include "devConf.h" #include "devConf.h"
#include "devices/addresses.h" #include "devices/addresses.h"
#include "devices/gpioIds.h" #include "devices/gpioIds.h"
#include "eive/definitions.h" #include "eive/definitions.h"
#include "mission/system/objects/SusAssembly.h"
#include "mission/system/objects/TcsBoardAssembly.h"
#include "mission/system/tree/acsModeTree.h" #include "mission/system/tree/acsModeTree.h"
#include "mission/system/tree/payloadModeTree.h" #include "mission/system/tree/payloadModeTree.h"
#include "mission/system/tree/tcsModeTree.h" #include "mission/system/tree/tcsModeTree.h"
@ -342,11 +340,6 @@ void ObjectFactory::createScexComponents(std::string uartDev, PowerSwitchIF* pwr
scexHandler->connectModeTreeParent(satsystem::pl::SUBSYSTEM); scexHandler->connectModeTreeParent(satsystem::pl::SUBSYSTEM);
} }
void ObjectFactory::createThermalController() {
auto* tcsCtrl = new ThermalController(objects::THERMAL_CONTROLLER);
tcsCtrl->connectModeTreeParent(satsystem::tcs::SUBSYSTEM);
}
AcsController* ObjectFactory::createAcsController(bool connectSubsystem) { AcsController* ObjectFactory::createAcsController(bool connectSubsystem) {
auto acsCtrl = new AcsController(objects::ACS_CONTROLLER); auto acsCtrl = new AcsController(objects::ACS_CONTROLLER);
if (connectSubsystem) { if (connectSubsystem) {

View File

@ -11,6 +11,8 @@
#include <optional> #include <optional>
#include <string> #include <string>
#include "mission/devices/HeaterHandler.h"
class GpioIF; class GpioIF;
class SpiComIF; class SpiComIF;
class PowerSwitchIF; class PowerSwitchIF;
@ -29,10 +31,8 @@ void createScexComponents(std::string uartDev, PowerSwitchIF* pwrSwitcher,
void gpioChecker(ReturnValue_t result, std::string output); void gpioChecker(ReturnValue_t result, std::string output);
void createThermalController();
AcsController* createAcsController(bool connectSubsystem); AcsController* createAcsController(bool connectSubsystem);
void addTmtcIpCoresToFunnels(CcsdsIpCoreHandler& ipCoreHandler, PusTmFunnel& pusFunnel, void addTmtcIpCoresToFunnels(CcsdsIpCoreHandler& ipCoreHandler, PusTmFunnel& pusFunnel,
CfdpTmFunnel& cfdpFunnel); CfdpTmFunnel& cfdpFunnel);
} // namespace ObjectFactory } // namespace ObjectFactory

View File

@ -1,7 +1,7 @@
#ifndef LINUX_BOARDTEST_I2CTESTCLASS_H_ #ifndef LINUX_BOARDTEST_I2CTESTCLASS_H_
#define LINUX_BOARDTEST_I2CTESTCLASS_H_ #define LINUX_BOARDTEST_I2CTESTCLASS_H_
#include <test/testtasks/TestTask.h> #include <test/TestTask.h>
#include <array> #include <array>
#include <string> #include <string>

View File

@ -5,7 +5,7 @@
#include <fsfw_hal/common/gpio/GpioCookie.h> #include <fsfw_hal/common/gpio/GpioCookie.h>
#include <fsfw_hal/common/gpio/GpioIF.h> #include <fsfw_hal/common/gpio/GpioIF.h>
#include "TestTask.h" #include "test/TestTask.h"
/** /**
* @brief Test for the GPIO read implementation of the LinuxLibgpioIF. * @brief Test for the GPIO read implementation of the LinuxLibgpioIF.

View File

@ -13,7 +13,7 @@
#include <fsfw_hal/common/gpio/GpioIF.h> #include <fsfw_hal/common/gpio/GpioIF.h>
#include <fsfw_hal/linux/spi/SpiCookie.h> #include <fsfw_hal/linux/spi/SpiCookie.h>
#include <test/testtasks/TestTask.h> #include <test/TestTask.h>
#include <vector> #include <vector>

View File

@ -12,7 +12,7 @@
#include "lwgps/lwgps.h" #include "lwgps/lwgps.h"
#include "mission/devices/devicedefinitions/ScexDefinitions.h" #include "mission/devices/devicedefinitions/ScexDefinitions.h"
#include "test/testtasks/TestTask.h" #include "test/TestTask.h"
class ScexUartReader; class ScexUartReader;
class ScexDleParser; class ScexDleParser;

View File

@ -2,6 +2,7 @@
#include <bsp_q7s/core/CoreDefinitions.h> #include <bsp_q7s/core/CoreDefinitions.h>
#include <fsfw/datapool/PoolReadGuard.h> #include <fsfw/datapool/PoolReadGuard.h>
#include <fsfw/thermal/ThermalComponentIF.h>
#include <fsfw_hal/devicehandlers/devicedefinitions/MgmLIS3HandlerDefs.h> #include <fsfw_hal/devicehandlers/devicedefinitions/MgmLIS3HandlerDefs.h>
#include <linux/devices/devicedefinitions/StarTrackerDefinitions.h> #include <linux/devices/devicedefinitions/StarTrackerDefinitions.h>
#include <mission/devices/devicedefinitions/BpxBatteryDefinitions.h> #include <mission/devices/devicedefinitions/BpxBatteryDefinitions.h>
@ -14,11 +15,13 @@
#include <mission/devices/devicedefinitions/payloadPcduDefinitions.h> #include <mission/devices/devicedefinitions/payloadPcduDefinitions.h>
#include <objects/systemObjectList.h> #include <objects/systemObjectList.h>
ThermalController::ThermalController(object_id_t objectId) ThermalController::ThermalController(object_id_t objectId, HeaterHandler& heater)
: ExtendedControllerBase(objectId), : ExtendedControllerBase(objectId),
heaterHandler(heater),
sensorTemperatures(this), sensorTemperatures(this),
susTemperatures(this), susTemperatures(this),
deviceTemperatures(this), deviceTemperatures(this),
imtqThermalSet(objects::IMTQ_HANDLER),
max31865Set0(objects::RTD_0_IC3_PLOC_HEATSPREADER, max31865Set0(objects::RTD_0_IC3_PLOC_HEATSPREADER,
EiveMax31855::RtdCommands::EXCHANGE_SET_ID), EiveMax31855::RtdCommands::EXCHANGE_SET_ID),
max31865Set1(objects::RTD_1_IC4_PLOC_MISSIONBOARD, max31865Set1(objects::RTD_1_IC4_PLOC_MISSIONBOARD,
@ -55,7 +58,9 @@ ThermalController::ThermalController(object_id_t objectId)
susSet8(objects::SUS_8_R_LOC_XBYBZB_PT_YB), susSet8(objects::SUS_8_R_LOC_XBYBZB_PT_YB),
susSet9(objects::SUS_9_R_LOC_XBYBZB_PT_YF), susSet9(objects::SUS_9_R_LOC_XBYBZB_PT_YF),
susSet10(objects::SUS_10_N_LOC_XMYBZF_PT_ZF), susSet10(objects::SUS_10_N_LOC_XMYBZF_PT_ZF),
susSet11(objects::SUS_11_R_LOC_XBYMZB_PT_ZB) {} susSet11(objects::SUS_11_R_LOC_XBYMZB_PT_ZB) {
resetSensorsArray();
}
ReturnValue_t ThermalController::initialize() { ReturnValue_t ThermalController::initialize() {
auto result = ExtendedControllerBase::initialize(); auto result = ExtendedControllerBase::initialize();
@ -103,6 +108,31 @@ void ThermalController::performControlOperation() {
copyDevices(); copyDevices();
deviceTemperatures.commit(); deviceTemperatures.commit();
} }
ctrlCameraBody();
ctrlAcsBoard();
ctrlMgt();
ctrlRw();
ctrlStr();
ctrlIfBoard();
ctrlAcsBoard();
ctrlObc();
ctrlObcIfBoard();
ctrlSBandTransceiver();
ctrlPcduP60Board();
ctrlPcduAcu();
ctrlPcduPdu();
ctrlPlPcduBoard();
ctrlPlocMissionBoard();
ctrlPlocProcessingBoard();
ctrlDac();
ctrlDro();
ctrlX8();
ctrlHpa();
ctrlTx();
ctrlMpa();
ctrlScexBoard();
} }
ReturnValue_t ThermalController::initializeLocalDataPool(localpool::DataPool& localDataPoolMap, ReturnValue_t ThermalController::initializeLocalDataPool(localpool::DataPool& localDataPoolMap,
@ -952,3 +982,450 @@ void ThermalController::copyDevices() {
} }
} }
} }
void ThermalController::ctrlAcsBoard() {
// TODO: check
heater::Switchers switchNr = heater::HEATER_2_ACS_BRD;
heater::Switchers redSwitchNr = heater::HEATER_0_OBC_BRD;
// A side
sensors[0].first = deviceTemperatures.gyro0SideA.isValid();
sensors[0].second = deviceTemperatures.gyro0SideA.value;
sensors[1].first = deviceTemperatures.mgm0SideA.isValid();
sensors[1].second = deviceTemperatures.mgm0SideA.value;
sensors[2].first = deviceTemperatures.gyro1SideA.isValid();
sensors[2].second = deviceTemperatures.gyro1SideA.value;
sensors[3].first = sensorTemperatures.sensor_tcs_board.isValid();
sensors[3].second = sensorTemperatures.sensor_tcs_board.value;
numSensors = 4;
if (selectAndReadSensorTemp()) {
if (chooseHeater(switchNr, redSwitchNr)) {
ctrlHeater(switchNr, redSwitchNr, acsBoardLimits);
}
resetSensorsArray();
return;
}
// B side
sensors[0].first = deviceTemperatures.gyro2SideB.isValid();
sensors[0].second = deviceTemperatures.gyro2SideB.value;
sensors[1].first = deviceTemperatures.mgm2SideB.isValid();
sensors[1].second = deviceTemperatures.mgm2SideB.value;
sensors[2].first = deviceTemperatures.gyro3SideB.isValid();
sensors[2].second = deviceTemperatures.gyro3SideB.value;
sensors[3].first = sensorTemperatures.sensor_tcs_board.isValid();
sensors[3].second = sensorTemperatures.sensor_tcs_board.value;
if (selectAndReadSensorTemp()) {
if (chooseHeater(switchNr, redSwitchNr)) {
ctrlHeater(switchNr, redSwitchNr, acsBoardLimits);
}
} else {
if (chooseHeater(switchNr, redSwitchNr)) {
if (heaterHandler.checkSwitchState(switchNr)) {
heaterHandler.switchHeater(switchNr, HeaterHandler::SwitchState::OFF);
sif::info << "ThermalController::ctrlHeater: Heater" << switchNr << " OFF" << std::endl;
}
}
}
resetSensorsArray();
}
void ThermalController::ctrlMgt() {
PoolReadGuard pg(&imtqThermalSet);
auto heaterReq =
static_cast<ThermalComponentIF::StateRequest>(imtqThermalSet.heaterRequest.value);
if (heaterReq == ThermalComponentIF::STATE_REQUEST_OPERATIONAL) {
sensors[0].first = sensorTemperatures.sensor_magnettorquer.isValid();
sensors[0].second = sensorTemperatures.sensor_magnettorquer.value;
sensors[1].first = deviceTemperatures.mgt.isValid();
sensors[1].second = deviceTemperatures.mgt.value;
sensors[2].first = sensorTemperatures.sensor_plpcdu_heatspreader.isValid();
sensors[2].second = sensorTemperatures.sensor_plpcdu_heatspreader.value;
numSensors = 3;
ctrlComponentTemperature(heater::HEATER_2_ACS_BRD, heater::HEATER_3_PCDU_PDU, mgtLimits);
}
}
void ThermalController::ctrlRw() {
// TODO: better solution?
// RW1
sensors[0].first = sensorTemperatures.sensor_rw1.isValid();
sensors[0].second = sensorTemperatures.sensor_rw1.value;
sensors[1].first = deviceTemperatures.rw1.isValid();
sensors[1].second = deviceTemperatures.rw1.value;
sensors[2].first = deviceTemperatures.rw4.isValid();
sensors[2].second = deviceTemperatures.rw4.value;
sensors[3].first = sensorTemperatures.sensor_dro.isValid();
sensors[3].second = sensorTemperatures.sensor_dro.value;
numSensors = 4;
ctrlComponentTemperature(heater::HEATER_6_DRO, heater::HEATER_6_DRO, rwLimits);
// RW2
sensors[0].first = deviceTemperatures.rw2.isValid();
sensors[0].second = deviceTemperatures.rw2.value;
sensors[1].first = deviceTemperatures.rw3.isValid();
sensors[1].second = deviceTemperatures.rw3.value;
sensors[2].first = sensorTemperatures.sensor_rw1.isValid();
sensors[2].second = sensorTemperatures.sensor_rw1.value;
sensors[3].first = sensorTemperatures.sensor_dro.isValid();
sensors[3].second = sensorTemperatures.sensor_dro.value;
numSensors = 4;
ctrlComponentTemperature(heater::HEATER_6_DRO, heater::HEATER_6_DRO, rwLimits);
// RW3
sensors[0].first = deviceTemperatures.rw3.isValid();
sensors[0].second = deviceTemperatures.rw3.value;
sensors[1].first = deviceTemperatures.rw4.isValid();
sensors[1].second = deviceTemperatures.rw4.value;
sensors[2].first = sensorTemperatures.sensor_rw1.isValid();
sensors[2].second = sensorTemperatures.sensor_rw1.value;
sensors[3].first = sensorTemperatures.sensor_dro.isValid();
sensors[3].second = sensorTemperatures.sensor_dro.value;
numSensors = 4;
ctrlComponentTemperature(heater::HEATER_6_DRO, heater::HEATER_6_DRO, rwLimits);
// RW4
sensors[0].first = deviceTemperatures.rw4.isValid();
sensors[0].second = deviceTemperatures.rw4.value;
sensors[1].first = deviceTemperatures.rw1.isValid();
sensors[1].second = deviceTemperatures.rw1.value;
sensors[2].first = sensorTemperatures.sensor_rw1.isValid();
sensors[2].second = sensorTemperatures.sensor_rw1.value;
sensors[3].first = sensorTemperatures.sensor_dro.isValid();
sensors[3].second = sensorTemperatures.sensor_dro.value;
numSensors = 4;
ctrlComponentTemperature(heater::HEATER_6_DRO, heater::HEATER_6_DRO, rwLimits);
}
void ThermalController::ctrlStr() {
sensors[0].first = sensorTemperatures.sensor_startracker.isValid();
sensors[0].second = sensorTemperatures.sensor_startracker.value;
sensors[1].first = deviceTemperatures.startracker.isValid();
sensors[1].second = deviceTemperatures.startracker.value;
sensors[2].first = sensorTemperatures.sensor_dro.isValid();
sensors[2].second = sensorTemperatures.sensor_dro.value;
numSensors = 3;
ctrlComponentTemperature(heater::HEATER_5_STR, heater::HEATER_6_DRO, strLimits);
}
void ThermalController::ctrlIfBoard() {
sensors[0].first = sensorTemperatures.tmp1075IfBrd.isValid();
sensors[0].second = sensorTemperatures.tmp1075IfBrd.value;
sensors[1].first = sensorTemperatures.sensor_magnettorquer.isValid();
sensors[1].second = sensorTemperatures.sensor_magnettorquer.value;
sensors[2].first = deviceTemperatures.mgm2SideB.isValid();
sensors[2].second = deviceTemperatures.mgm2SideB.value;
numSensors = 3;
ctrlComponentTemperature(heater::HEATER_2_ACS_BRD, heater::HEATER_3_PCDU_PDU, ifBoardLimits);
}
void ThermalController::ctrlTcsBoard() {
sensors[0].first = sensorTemperatures.sensor_tcs_board.isValid();
sensors[0].second = sensorTemperatures.sensor_tcs_board.value;
sensors[1].first = sensorTemperatures.tmp1075Tcs0.isValid();
sensors[1].second = sensorTemperatures.tmp1075Tcs0.value;
sensors[2].first = sensorTemperatures.tmp1075Tcs1.isValid();
sensors[2].second = sensorTemperatures.tmp1075Tcs1.value;
numSensors = 3;
ctrlComponentTemperature(heater::HEATER_0_OBC_BRD, heater::HEATER_2_ACS_BRD, tcsBoardLimits);
}
void ThermalController::ctrlObc() {
sensors[0].first = deviceTemperatures.q7s.isValid();
sensors[0].second = deviceTemperatures.q7s.value;
sensors[1].first = sensorTemperatures.tmp1075Tcs1.isValid();
sensors[1].second = sensorTemperatures.tmp1075Tcs1.value;
sensors[2].first = sensorTemperatures.tmp1075Tcs0.isValid();
sensors[2].second = sensorTemperatures.tmp1075Tcs0.value;
numSensors = 3;
ctrlComponentTemperature(heater::HEATER_0_OBC_BRD, heater::HEATER_2_ACS_BRD, obcLimits);
if (componentAboveCutOffLimit) {
triggerEvent(OBC_OVERHEATING);
}
}
void ThermalController::ctrlObcIfBoard() {
sensors[0].first = deviceTemperatures.q7s.isValid();
sensors[0].second = deviceTemperatures.q7s.value;
sensors[1].first = sensorTemperatures.tmp1075Tcs0.isValid();
sensors[1].second = sensorTemperatures.tmp1075Tcs0.value;
sensors[2].first = sensorTemperatures.tmp1075Tcs1.isValid();
sensors[2].second = sensorTemperatures.tmp1075Tcs1.value;
numSensors = 3;
ctrlComponentTemperature(heater::HEATER_0_OBC_BRD, heater::HEATER_2_ACS_BRD, obcIfBoardLimits);
}
void ThermalController::ctrlSBandTransceiver() {
sensors[0].first = deviceTemperatures.syrlinksPowerAmplifier.isValid();
sensors[0].second = deviceTemperatures.syrlinksPowerAmplifier.value;
sensors[1].first = deviceTemperatures.syrlinksBasebandBoard.isValid();
sensors[1].second = deviceTemperatures.syrlinksBasebandBoard.value;
sensors[2].first = sensorTemperatures.sensor_4k_camera.isValid();
sensors[2].second = sensorTemperatures.sensor_4k_camera.value;
numSensors = 3;
ctrlComponentTemperature(heater::HEATER_7_S_BAND, heater::HEATER_4_CAMERA,
sBandTransceiverLimits);
if (componentAboveCutOffLimit) {
triggerEvent(SYRLINKS_OVERHEATING);
}
}
void ThermalController::ctrlPcduP60Board() {
sensors[0].first = deviceTemperatures.temp1P60dock.isValid();
sensors[0].second = deviceTemperatures.temp1P60dock.value;
sensors[1].first = deviceTemperatures.temp2P60dock.isValid();
sensors[1].second = deviceTemperatures.temp2P60dock.value;
numSensors = 2;
ctrlComponentTemperature(heater::HEATER_3_PCDU_PDU, heater::HEATER_2_ACS_BRD, pcduP60BoardLimits);
}
void ThermalController::ctrlPcduAcu() {
heater::Switchers switchNr = heater::HEATER_3_PCDU_PDU;
heater::Switchers redSwitchNr = heater::HEATER_2_ACS_BRD;
if (chooseHeater(switchNr, redSwitchNr)) {
bool sensorTempAvailable = true;
if (deviceTemperatures.acu.value[0] != INVALID_TEMPERATURE) {
sensorTemp = deviceTemperatures.acu.value[0];
} else if (deviceTemperatures.acu.value[1] != INVALID_TEMPERATURE) {
sensorTemp = deviceTemperatures.acu.value[1];
} else if (deviceTemperatures.acu.value[2] != INVALID_TEMPERATURE) {
sensorTemp = deviceTemperatures.acu.value[2];
} else if (sensorTemperatures.sensor_acu.isValid()) {
sensorTemp = sensorTemperatures.sensor_acu.value;
} else {
triggerEvent(NO_VALID_SENSOR_TEMPERATURE, switchNr);
sensorTempAvailable = false;
}
if (sensorTempAvailable) {
ctrlHeater(switchNr, redSwitchNr, pcduAcuLimits);
}
}
}
void ThermalController::ctrlPcduPdu() {
sensors[0].first = deviceTemperatures.pdu1.isValid();
sensors[0].second = deviceTemperatures.pdu1.value;
sensors[1].first = deviceTemperatures.pdu2.isValid();
sensors[1].second = deviceTemperatures.pdu2.value;
sensors[2].first = sensorTemperatures.tmp1075Tcs0.isValid();
sensors[2].second = sensorTemperatures.tmp1075Tcs0.value;
numSensors = 2;
ctrlComponentTemperature(heater::HEATER_3_PCDU_PDU, heater::HEATER_2_ACS_BRD, pcduPduLimits);
}
void ThermalController::ctrlPlPcduBoard() {
sensors[0].first = sensorTemperatures.tmp1075PlPcdu0.isValid();
sensors[0].second = sensorTemperatures.tmp1075PlPcdu0.value;
sensors[1].first = sensorTemperatures.tmp1075PlPcdu1.isValid();
sensors[1].second = sensorTemperatures.tmp1075PlPcdu1.value;
sensors[2].first = deviceTemperatures.adcPayloadPcdu.isValid();
sensors[2].second = deviceTemperatures.adcPayloadPcdu.value;
sensors[3].first = sensorTemperatures.sensor_plpcdu_heatspreader.isValid();
sensors[3].second = sensorTemperatures.sensor_plpcdu_heatspreader.value;
numSensors = 4;
ctrlComponentTemperature(heater::HEATER_3_PCDU_PDU, heater::HEATER_2_ACS_BRD, plPcduBoardLimits);
if (componentAboveCutOffLimit) {
triggerEvent(PLPCDU_OVERHEATING);
}
}
void ThermalController::ctrlPlocMissionBoard() {
sensors[0].first = sensorTemperatures.sensor_ploc_heatspreader.isValid();
sensors[0].second = sensorTemperatures.sensor_ploc_heatspreader.value;
sensors[1].first = sensorTemperatures.sensor_ploc_missionboard.isValid();
sensors[1].second = sensorTemperatures.sensor_ploc_missionboard.value;
sensors[2].first = sensorTemperatures.sensor_dac_heatspreader.isValid();
sensors[2].second = sensorTemperatures.sensor_dac_heatspreader.value;
numSensors = 3;
ctrlComponentTemperature(heater::HEATER_1_PLOC_PROC_BRD, heater::HEATER_0_OBC_BRD,
plocMissionBoardLimits);
if (componentAboveCutOffLimit) {
triggerEvent(PLOC_OVERHEATING);
}
}
void ThermalController::ctrlPlocProcessingBoard() {
sensors[0].first = sensorTemperatures.sensor_ploc_missionboard.isValid();
sensors[0].second = sensorTemperatures.sensor_ploc_missionboard.value;
sensors[1].first = sensorTemperatures.sensor_ploc_heatspreader.isValid();
sensors[1].second = sensorTemperatures.sensor_ploc_heatspreader.value;
sensors[2].first = sensorTemperatures.sensor_dac_heatspreader.isValid();
sensors[2].second = sensorTemperatures.sensor_dac_heatspreader.value;
numSensors = 3;
ctrlComponentTemperature(heater::HEATER_1_PLOC_PROC_BRD, heater::HEATER_0_OBC_BRD,
plocProcessingBoardLimits);
}
void ThermalController::ctrlDac() {
sensors[0].first = sensorTemperatures.sensor_dac_heatspreader.isValid();
sensors[0].second = sensorTemperatures.sensor_dac_heatspreader.value;
sensors[1].first = sensorTemperatures.sensor_ploc_missionboard.isValid();
sensors[1].second = sensorTemperatures.sensor_ploc_missionboard.value;
sensors[2].first = sensorTemperatures.sensor_ploc_heatspreader.isValid();
sensors[2].second = sensorTemperatures.sensor_ploc_heatspreader.value;
numSensors = 3;
ctrlComponentTemperature(heater::HEATER_1_PLOC_PROC_BRD, heater::HEATER_0_OBC_BRD, dacLimits);
}
void ThermalController::ctrlCameraBody() {
sensors[0].first = sensorTemperatures.sensor_4k_camera.isValid();
sensors[0].second = sensorTemperatures.sensor_4k_camera.value;
sensors[1].first = sensorTemperatures.sensor_dro.isValid();
sensors[1].second = sensorTemperatures.sensor_dro.value;
sensors[2].first = sensorTemperatures.sensor_mpa.isValid();
sensors[2].second = sensorTemperatures.sensor_mpa.value;
numSensors = 3;
ctrlComponentTemperature(heater::HEATER_4_CAMERA, heater::HEATER_6_DRO, cameraLimits);
}
void ThermalController::ctrlDro() {
sensors[0].first = sensorTemperatures.sensor_dro.isValid();
sensors[0].second = sensorTemperatures.sensor_dro.value;
sensors[1].first = sensorTemperatures.sensor_4k_camera.isValid();
sensors[1].second = sensorTemperatures.sensor_4k_camera.value;
sensors[2].first = sensorTemperatures.sensor_mpa.isValid();
sensors[2].second = sensorTemperatures.sensor_mpa.value;
numSensors = 3;
ctrlComponentTemperature(heater::HEATER_6_DRO, heater::HEATER_4_CAMERA, droLimits);
}
void ThermalController::ctrlX8() {
sensors[0].first = sensorTemperatures.sensor_x8.isValid();
sensors[0].second = sensorTemperatures.sensor_x8.value;
sensors[1].first = sensorTemperatures.sensor_hpa.isValid();
sensors[1].second = sensorTemperatures.sensor_hpa.value;
sensors[2].first = sensorTemperatures.sensor_tx_modul.isValid();
sensors[2].second = sensorTemperatures.sensor_tx_modul.value;
numSensors = 3;
ctrlComponentTemperature(heater::HEATER_6_DRO, heater::HEATER_4_CAMERA, x8Limits);
}
void ThermalController::ctrlTx() {
sensors[0].first = sensorTemperatures.sensor_tx_modul.isValid();
sensors[0].second = sensorTemperatures.sensor_tx_modul.value;
sensors[1].first = sensorTemperatures.sensor_x8.isValid();
sensors[1].second = sensorTemperatures.sensor_x8.value;
sensors[2].first = sensorTemperatures.sensor_mpa.isValid();
sensors[2].second = sensorTemperatures.sensor_mpa.value;
numSensors = 3;
ctrlComponentTemperature(heater::HEATER_6_DRO, heater::HEATER_4_CAMERA, txLimits);
}
void ThermalController::ctrlMpa() {
sensors[0].first = sensorTemperatures.sensor_mpa.isValid();
sensors[0].second = sensorTemperatures.sensor_mpa.value;
sensors[1].first = sensorTemperatures.sensor_hpa.isValid();
sensors[1].second = sensorTemperatures.sensor_hpa.value;
sensors[2].first = sensorTemperatures.sensor_tx_modul.isValid();
sensors[2].second = sensorTemperatures.sensor_tx_modul.value;
numSensors = 3;
ctrlComponentTemperature(heater::HEATER_6_DRO, heater::HEATER_4_CAMERA, mpaLimits);
}
void ThermalController::ctrlHpa() {
sensors[0].first = sensorTemperatures.sensor_hpa.isValid();
sensors[0].second = sensorTemperatures.sensor_hpa.value;
sensors[1].first = sensorTemperatures.sensor_x8.isValid();
sensors[1].second = sensorTemperatures.sensor_x8.value;
sensors[2].first = sensorTemperatures.sensor_mpa.isValid();
sensors[2].second = sensorTemperatures.sensor_mpa.value;
numSensors = 3;
ctrlComponentTemperature(heater::HEATER_6_DRO, heater::HEATER_4_CAMERA, hpaLimits);
if (componentAboveCutOffLimit) {
triggerEvent(HPA_OVERHEATING);
}
}
void ThermalController::ctrlScexBoard() {
sensors[0].first = sensorTemperatures.sensor_scex.isValid();
sensors[0].second = sensorTemperatures.sensor_scex.value;
sensors[1].first = sensorTemperatures.sensor_x8.isValid();
sensors[1].second = sensorTemperatures.sensor_x8.value;
sensors[2].first = sensorTemperatures.sensor_hpa.isValid();
sensors[2].second = sensorTemperatures.sensor_hpa.value;
numSensors = 3;
ctrlComponentTemperature(heater::HEATER_6_DRO, heater::HEATER_5_STR, scexBoardLimits);
}
void ThermalController::ctrlHeater(heater::Switchers switchNr, heater::Switchers redSwitchNr,
struct TempLimits& tempLimit) {
componentAboveCutOffLimit = false;
// Heater off
if (not heaterHandler.checkSwitchState(switchNr)) {
if (sensorTemp < tempLimit.opLowerLimit) {
heaterHandler.switchHeater(switchNr, HeaterHandler::SwitchState::ON);
sif::info << "ThermalController::ctrlHeater: Heater" << switchNr << " ON" << std::endl;
}
// Heater on
} else if (heaterHandler.checkSwitchState(switchNr)) {
if (sensorTemp >= tempLimit.opLowerLimit + TEMP_OFFSET) {
heaterHandler.switchHeater(switchNr, HeaterHandler::SwitchState::OFF);
sif::info << "ThermalController::ctrlHeater: Heater" << switchNr << " OFF" << std::endl;
}
} else if (not redSwitchNrInUse) {
if (heaterHandler.checkSwitchState(redSwitchNr)) {
if (sensorTemp >= tempLimit.cutOffLimit) {
componentAboveCutOffLimit = true;
heaterHandler.switchHeater(redSwitchNr, HeaterHandler::SwitchState::OFF);
sif::info << "ThermalController::ctrlHeater: Heater" << redSwitchNr << " OFF" << std::endl;
}
}
}
}
bool ThermalController::chooseHeater(heater::Switchers& switchNr, heater::Switchers redSwitchNr) {
bool heaterAvailable = true;
if (heaterHandler.getHealth(switchNr) != HasHealthIF::HEALTHY) {
if (heaterHandler.getHealth(redSwitchNr) == HasHealthIF::HEALTHY) {
switchNr = redSwitchNr;
redSwitchNrInUse = true;
} else {
heaterAvailable = false;
triggerEvent(NO_HEALTHY_HEATER_AVAILABLE, switchNr, redSwitchNr);
}
} else {
redSwitchNrInUse = false;
}
return heaterAvailable;
}
bool ThermalController::selectAndReadSensorTemp() {
for (unsigned i = 0; i < numSensors; i++) {
if (sensors[i].first and sensors[i].second != INVALID_TEMPERATURE) {
sensorTemp = sensors[i].second;
return true;
}
}
triggerEvent(NO_VALID_SENSOR_TEMPERATURE);
return false;
}
void ThermalController::ctrlComponentTemperature(heater::Switchers switchNr,
heater::Switchers redSwitchNr,
TempLimits& tempLimit) {
if (selectAndReadSensorTemp()) {
if (chooseHeater(switchNr, redSwitchNr)) {
ctrlHeater(switchNr, redSwitchNr, tempLimit);
}
} else {
if (chooseHeater(switchNr,
redSwitchNr)) { // TODO: muss der Heater dann wirklich abgeschalten werden?
if (heaterHandler.checkSwitchState(switchNr)) {
heaterHandler.switchHeater(switchNr, HeaterHandler::SwitchState::OFF);
sif::info << "ThermalController::ctrlHeater: Heater" << switchNr << " OFF" << std::endl;
}
}
}
resetSensorsArray();
}
void ThermalController::resetSensorsArray() {
//TODO: müssen auch andere Variablen resettet werden? senstemp?
for (auto& validValuePair : sensors) {
validValuePair.first = false;
validValuePair.second = INVALID_TEMPERATURE;
}
}

View File

@ -2,59 +2,101 @@
#define MISSION_CONTROLLER_THERMALCONTROLLER_H_ #define MISSION_CONTROLLER_THERMALCONTROLLER_H_
#include <fsfw/controller/ExtendedControllerBase.h> #include <fsfw/controller/ExtendedControllerBase.h>
#include <fsfw/devicehandlers/DeviceHandlerThermalSet.h>
#include <fsfw/timemanager/Countdown.h> #include <fsfw/timemanager/Countdown.h>
#include <mission/controller/controllerdefinitions/ThermalControllerDefinitions.h> #include <mission/controller/controllerdefinitions/ThermalControllerDefinitions.h>
#include <mission/devices/devicedefinitions/Max31865Definitions.h> #include <mission/devices/devicedefinitions/Max31865Definitions.h>
#include <mission/devices/devicedefinitions/SusDefinitions.h> #include <mission/devices/devicedefinitions/SusDefinitions.h>
#include <mission/devices/devicedefinitions/Tmp1075Definitions.h> #include <mission/devices/devicedefinitions/Tmp1075Definitions.h>
#include <list>
#include "../devices/HeaterHandler.h"
/**
* NOP Limit: Hard limit for device, usually from datasheet. Device damage is possible lif NOP limit
* is exceeded.
* OP Limit: Soft limit. Device should be switched off or TCS controller should take action if the
* limit is exceeded to avoid reaching NOP limit
*/
struct TempLimits {
TempLimits(float nopLowerLimit, float opLowerLimit, float cutOffLimit, float opUpperLimit,
float nopUpperLimit)
: opLowerLimit(opLowerLimit),
opUpperLimit(opUpperLimit),
cutOffLimit(cutOffLimit),
nopLowerLimit(nopLowerLimit),
nopUpperLimit(nopUpperLimit) {}
float opLowerLimit;
float opUpperLimit;
float cutOffLimit;
float nopLowerLimit;
float nopUpperLimit;
};
class ThermalController : public ExtendedControllerBase { class ThermalController : public ExtendedControllerBase {
public: public:
static const uint16_t INVALID_TEMPERATURE = 999; static const uint16_t INVALID_TEMPERATURE = 999;
static const uint8_t NUMBER_OF_SENSORS = 16;
ThermalController(object_id_t objectId); ThermalController(object_id_t objectId, HeaterHandler& heater);
ReturnValue_t initialize() override; ReturnValue_t initialize() override;
protected: protected:
virtual ReturnValue_t handleCommandMessage(CommandMessage* message) override; ReturnValue_t handleCommandMessage(CommandMessage* message) override;
virtual void performControlOperation() override; void performControlOperation() override;
virtual ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap, ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap,
LocalDataPoolManager& poolManager) override; LocalDataPoolManager& poolManager) override;
virtual LocalPoolDataSetBase* getDataSetHandle(sid_t sid) override; LocalPoolDataSetBase* getDataSetHandle(sid_t sid) override;
// Mode abstract functions // Mode abstract functions
virtual ReturnValue_t checkModeCommand(Mode_t mode, Submode_t submode, ReturnValue_t checkModeCommand(Mode_t mode, Submode_t submode,
uint32_t* msToReachTheMode) override; uint32_t* msToReachTheMode) override;
private: private:
static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::TCS_CONTROLLER;
static constexpr Event NO_VALID_SENSOR_TEMPERATURE = MAKE_EVENT(0, severity::MEDIUM);
static constexpr Event NO_HEALTHY_HEATER_AVAILABLE = MAKE_EVENT(1, severity::MEDIUM);
static constexpr Event SYRLINKS_OVERHEATING = MAKE_EVENT(2, severity::HIGH);
static constexpr Event PLOC_OVERHEATING = MAKE_EVENT(3, severity::HIGH);
static constexpr Event OBC_OVERHEATING = MAKE_EVENT(4, severity::HIGH);
static constexpr Event HPA_OVERHEATING = MAKE_EVENT(5, severity::HIGH);
static constexpr Event PLPCDU_OVERHEATING = MAKE_EVENT(6, severity::HIGH);
static const uint32_t DELAY = 500; static const uint32_t DELAY = 500;
static const uint32_t TEMP_OFFSET = 5;
enum class InternalState { STARTUP, INITIAL_DELAY, READY }; enum class InternalState { STARTUP, INITIAL_DELAY, READY };
InternalState internalState = InternalState::STARTUP; InternalState internalState = InternalState::STARTUP;
HeaterHandler& heaterHandler;
thermalControllerDefinitions::SensorTemperatures sensorTemperatures; thermalControllerDefinitions::SensorTemperatures sensorTemperatures;
thermalControllerDefinitions::SusTemperatures susTemperatures; thermalControllerDefinitions::SusTemperatures susTemperatures;
thermalControllerDefinitions::DeviceTemperatures deviceTemperatures; thermalControllerDefinitions::DeviceTemperatures deviceTemperatures;
DeviceHandlerThermalSet imtqThermalSet;
// Temperature Sensors // Temperature Sensors
MAX31865::Max31865Set max31865Set0; MAX31865::PrimarySet max31865Set0;
MAX31865::Max31865Set max31865Set1; MAX31865::PrimarySet max31865Set1;
MAX31865::Max31865Set max31865Set2; MAX31865::PrimarySet max31865Set2;
MAX31865::Max31865Set max31865Set3; MAX31865::PrimarySet max31865Set3;
MAX31865::Max31865Set max31865Set4; MAX31865::PrimarySet max31865Set4;
MAX31865::Max31865Set max31865Set5; MAX31865::PrimarySet max31865Set5;
MAX31865::Max31865Set max31865Set6; MAX31865::PrimarySet max31865Set6;
MAX31865::Max31865Set max31865Set7; MAX31865::PrimarySet max31865Set7;
MAX31865::Max31865Set max31865Set8; MAX31865::PrimarySet max31865Set8;
MAX31865::Max31865Set max31865Set9; MAX31865::PrimarySet max31865Set9;
MAX31865::Max31865Set max31865Set10; MAX31865::PrimarySet max31865Set10;
MAX31865::Max31865Set max31865Set11; MAX31865::PrimarySet max31865Set11;
MAX31865::Max31865Set max31865Set12; MAX31865::PrimarySet max31865Set12;
MAX31865::Max31865Set max31865Set13; MAX31865::PrimarySet max31865Set13;
MAX31865::Max31865Set max31865Set14; MAX31865::PrimarySet max31865Set14;
MAX31865::Max31865Set max31865Set15; MAX31865::PrimarySet max31865Set15;
TMP1075::Tmp1075Dataset tmp1075SetTcs0; TMP1075::Tmp1075Dataset tmp1075SetTcs0;
TMP1075::Tmp1075Dataset tmp1075SetTcs1; TMP1075::Tmp1075Dataset tmp1075SetTcs1;
@ -77,9 +119,41 @@ class ThermalController : public ExtendedControllerBase {
SUS::SusDataset susSet10; SUS::SusDataset susSet10;
SUS::SusDataset susSet11; SUS::SusDataset susSet11;
// TempLimits
TempLimits acsBoardLimits = TempLimits(-40.0, -40.0, 80.0, 85.0, 85.0);
TempLimits mgtLimits = TempLimits(-40.0, -40.0, 65.0, 70.0, 70.0);
TempLimits rwLimits = TempLimits(-40.0, -40.0, 80.0, 85.0, 85.0);
TempLimits strLimits = TempLimits(-30.0, -20.0, 65.0, 70.0, 80.0);
TempLimits ifBoardLimits = TempLimits(-65.0, -40.0, 80.0, 85.0, 150.0);
TempLimits tcsBoardLimits = TempLimits(-60.0, -40.0, 80.0, 85.0, 130.0);
TempLimits obcLimits = TempLimits(-40.0, -40.0, 80.0, 85.0, 85.0);
TempLimits obcIfBoardLimits = TempLimits(-65.0, -40.0, 80.0, 85.0, 125.0);
TempLimits sBandTransceiverLimits = TempLimits(-40.0, -25.0, 35.0, 40.0, 65.0);
TempLimits pcduP60BoardLimits = TempLimits(-35.0, -35.0, 80.0, 85.0, 85.0);
TempLimits pcduAcuLimits = TempLimits(-35.0, -35.0, 80.0, 85.0, 85.0);
TempLimits pcduPduLimits = TempLimits(-35.0, -35.0, 80.0, 85.0, 85.0);
TempLimits plPcduBoardLimits = TempLimits(-55.0, -40.0, 80.0, 85.0, 125.0);
TempLimits plocMissionBoardLimits = TempLimits(-30.0, -10.0, 40.0, 45.0, 60);
TempLimits plocProcessingBoardLimits = TempLimits(-30.0, -10.0, 40.0, 45.0, 60.0);
TempLimits dacLimits = TempLimits(-65.0, -40.0, 113.0, 118.0, 150.0);
TempLimits cameraLimits = TempLimits(-40.0, -30.0, 60.0, 65.0, 85.0);
TempLimits droLimits = TempLimits(-40.0, -30.0, 75.0, 80.0, 90.0);
TempLimits x8Limits = TempLimits(-40.0, -30.0, -75.0, 80.0, 90.0);
TempLimits hpaLimits = TempLimits(-40.0, -30.0, -75.0, 80.0, 90.0);
TempLimits txLimits = TempLimits(-40.0, -30.0, -75.0, 80.0, 90.0);
TempLimits mpaLimits = TempLimits(-40.0, -30.0, -75.0, 80.0, 90.0);
TempLimits scexBoardLimits = TempLimits(-60.0, -40.0, 80.0, 85.0, 150.0);
double sensorTemp = INVALID_TEMPERATURE;
bool redSwitchNrInUse = false;
bool componentAboveCutOffLimit = false;
// Initial delay to make sure all pool variables have been initialized their owners // Initial delay to make sure all pool variables have been initialized their owners
Countdown initialCountdown = Countdown(DELAY); Countdown initialCountdown = Countdown(DELAY);
std::array<std::pair<bool, double>, 5> sensors;
uint8_t numSensors = 0;
PoolEntry<float> tmp1075Tcs0 = PoolEntry<float>(10.0); PoolEntry<float> tmp1075Tcs0 = PoolEntry<float>(10.0);
PoolEntry<float> tmp1075Tcs1 = PoolEntry<float>(10.0); PoolEntry<float> tmp1075Tcs1 = PoolEntry<float>(10.0);
PoolEntry<float> tmp1075PlPcdu0 = PoolEntry<float>(10.0); PoolEntry<float> tmp1075PlPcdu0 = PoolEntry<float>(10.0);
@ -87,9 +161,41 @@ class ThermalController : public ExtendedControllerBase {
PoolEntry<float> tmp1075IfBrd = PoolEntry<float>(10.0); PoolEntry<float> tmp1075IfBrd = PoolEntry<float>(10.0);
static constexpr dur_millis_t MUTEX_TIMEOUT = 50; static constexpr dur_millis_t MUTEX_TIMEOUT = 50;
void resetSensorsArray();
void copySensors(); void copySensors();
void copySus(); void copySus();
void copyDevices(); void copyDevices();
void ctrlComponentTemperature(heater::Switchers switchNr, heater::Switchers redSwitchNr,
TempLimits& tempLimit);
void ctrlHeater(heater::Switchers switchNr, heater::Switchers redSwitchNr, TempLimits& tempLimit);
bool chooseHeater(heater::Switchers& switchNr, heater::Switchers redSwitchNr);
bool selectAndReadSensorTemp();
void ctrlAcsBoard();
void ctrlMgt();
void ctrlRw();
void ctrlStr();
void ctrlIfBoard();
void ctrlTcsBoard();
void ctrlObc();
void ctrlObcIfBoard();
void ctrlSBandTransceiver();
void ctrlPcduP60Board();
void ctrlPcduAcu();
void ctrlPcduPdu();
void ctrlPlPcduBoard();
void ctrlPlocMissionBoard();
void ctrlPlocProcessingBoard();
void ctrlDac();
void ctrlCameraBody();
void ctrlDro();
void ctrlX8();
void ctrlHpa();
void ctrlTx();
void ctrlMpa();
void ctrlScexBoard();
}; };
#endif /* MISSION_CONTROLLER_THERMALCONTROLLER_H_ */ #endif /* MISSION_CONTROLLER_THERMALCONTROLLER_H_ */

View File

@ -102,12 +102,13 @@ class SensorTemperatures : public StaticLocalDataSet<ENTRIES_SENSOR_TEMPERATURE_
lp_var_t<float> sensor_startracker = lp_var_t<float> sensor_startracker =
lp_var_t<float>(sid.objectId, PoolIds::SENSOR_STARTRACKER, this); lp_var_t<float>(sid.objectId, PoolIds::SENSOR_STARTRACKER, this);
lp_var_t<float> sensor_rw1 = lp_var_t<float>(sid.objectId, PoolIds::SENSOR_RW1, this); lp_var_t<float> sensor_rw1 = lp_var_t<float>(sid.objectId, PoolIds::SENSOR_RW1, this);
lp_var_t<float> sensor_dro = lp_var_t<float>(sid.objectId, PoolIds::SENSOR_DRO, this);
lp_var_t<float> sensor_scex = lp_var_t<float>(sid.objectId, PoolIds::SENSOR_SCEX, this); lp_var_t<float> sensor_scex = lp_var_t<float>(sid.objectId, PoolIds::SENSOR_SCEX, this);
lp_var_t<float> sensor_tx_modul = lp_var_t<float>(sid.objectId, PoolIds::SENSOR_TX_MODUL, this);
// E-Band module
lp_var_t<float> sensor_dro = lp_var_t<float>(sid.objectId, PoolIds::SENSOR_DRO, this);
lp_var_t<float> sensor_mpa = lp_var_t<float>(sid.objectId, PoolIds::SENSOR_MPA, this);
lp_var_t<float> sensor_x8 = lp_var_t<float>(sid.objectId, PoolIds::SENSOR_X8, this); lp_var_t<float> sensor_x8 = lp_var_t<float>(sid.objectId, PoolIds::SENSOR_X8, this);
lp_var_t<float> sensor_hpa = lp_var_t<float>(sid.objectId, PoolIds::SENSOR_HPA, this); lp_var_t<float> sensor_hpa = lp_var_t<float>(sid.objectId, PoolIds::SENSOR_HPA, this);
lp_var_t<float> sensor_tx_modul = lp_var_t<float>(sid.objectId, PoolIds::SENSOR_TX_MODUL, this);
lp_var_t<float> sensor_mpa = lp_var_t<float>(sid.objectId, PoolIds::SENSOR_MPA, this);
lp_var_t<float> sensor_acu = lp_var_t<float>(sid.objectId, PoolIds::SENSOR_ACU, this); lp_var_t<float> sensor_acu = lp_var_t<float>(sid.objectId, PoolIds::SENSOR_ACU, this);
lp_var_t<float> sensor_plpcdu_heatspreader = lp_var_t<float> sensor_plpcdu_heatspreader =
lp_var_t<float>(sid.objectId, PoolIds::SENSOR_PLPCDU_HEATSPREADER, this); lp_var_t<float>(sid.objectId, PoolIds::SENSOR_PLPCDU_HEATSPREADER, this);

View File

@ -1 +1 @@
target_sources(${LIB_EIVE_MISSION} PRIVATE GenericFactory.cpp) target_sources(${LIB_EIVE_MISSION} PRIVATE GenericFactory.cpp scheduling.cpp)

View File

@ -3,6 +3,7 @@
#include <fsfw/cfdp/CfdpDistributor.h> #include <fsfw/cfdp/CfdpDistributor.h>
#include <fsfw/cfdp/handler/CfdpHandler.h> #include <fsfw/cfdp/handler/CfdpHandler.h>
#include <fsfw/cfdp/handler/RemoteConfigTableIF.h> #include <fsfw/cfdp/handler/RemoteConfigTableIF.h>
#include <fsfw/controller/ControllerBase.h>
#include <fsfw/events/EventManager.h> #include <fsfw/events/EventManager.h>
#include <fsfw/health/HealthTable.h> #include <fsfw/health/HealthTable.h>
#include <fsfw/internalerror/InternalErrorReporter.h> #include <fsfw/internalerror/InternalErrorReporter.h>
@ -22,20 +23,26 @@
#include <fsfw/tcdistribution/PusDistributor.h> #include <fsfw/tcdistribution/PusDistributor.h>
#include <fsfw/timemanager/CdsShortTimeStamper.h> #include <fsfw/timemanager/CdsShortTimeStamper.h>
#include <fsfw_hal/host/HostFilesystem.h> #include <fsfw_hal/host/HostFilesystem.h>
#include <mission/controller/ThermalController.h>
#include <mission/devices/HeaterHandler.h>
#include <mission/devices/devicedefinitions/GomspaceDefinitions.h>
#include <mission/tmtc/CfdpTmFunnel.h> #include <mission/tmtc/CfdpTmFunnel.h>
#include <mission/tmtc/PusTmFunnel.h> #include <mission/tmtc/PusTmFunnel.h>
#include <mission/tmtc/TmFunnelHandler.h> #include <mission/tmtc/TmFunnelHandler.h>
#include "OBSWConfig.h" #include "OBSWConfig.h"
#include "devices/gpioIds.h"
#include "eive/definitions.h" #include "eive/definitions.h"
#include "fsfw/pus/Service11TelecommandScheduling.h" #include "fsfw/pus/Service11TelecommandScheduling.h"
#include "mission/cfdp/Config.h" #include "mission/cfdp/Config.h"
#include "mission/system/tree/tcsModeTree.h"
#include "objects/systemObjectList.h" #include "objects/systemObjectList.h"
#include "tmtc/pusIds.h" #include "tmtc/pusIds.h"
#if OBSW_ADD_TCPIP_SERVERS == 1 #if OBSW_ADD_TCPIP_SERVERS == 1
#if OBSW_ADD_TMTC_UDP_SERVER == 1 #if OBSW_ADD_TMTC_UDP_SERVER == 1
// UDP server includes // UDP server includes
#include "devices/gpioIds.h"
#include "fsfw/osal/common/UdpTcPollingTask.h" #include "fsfw/osal/common/UdpTcPollingTask.h"
#include "fsfw/osal/common/UdpTmTcBridge.h" #include "fsfw/osal/common/UdpTmTcBridge.h"
#endif #endif
@ -188,3 +195,25 @@ void ObjectFactory::produceGenericObjects(HealthTableIF** healthTable_, PusTmFun
ccsdsDistrib->registerApplication(info); ccsdsDistrib->registerApplication(info);
#endif #endif
} }
void ObjectFactory::createGenericHeaterComponents(GpioIF& gpioIF, PowerSwitchIF& pwrSwitcher,
HeaterHandler*& heaterHandler) {
HeaterHelper helper({{
{new HealthDevice(objects::HEATER_0_PLOC_PROC_BRD, MessageQueueIF::NO_QUEUE),
gpioIds::HEATER_0},
{new HealthDevice(objects::HEATER_1_PCDU_BRD, MessageQueueIF::NO_QUEUE), gpioIds::HEATER_1},
{new HealthDevice(objects::HEATER_2_ACS_BRD, MessageQueueIF::NO_QUEUE), gpioIds::HEATER_2},
{new HealthDevice(objects::HEATER_3_OBC_BRD, MessageQueueIF::NO_QUEUE), gpioIds::HEATER_3},
{new HealthDevice(objects::HEATER_4_CAMERA, MessageQueueIF::NO_QUEUE), gpioIds::HEATER_4},
{new HealthDevice(objects::HEATER_5_STR, MessageQueueIF::NO_QUEUE), gpioIds::HEATER_5},
{new HealthDevice(objects::HEATER_6_DRO, MessageQueueIF::NO_QUEUE), gpioIds::HEATER_6},
{new HealthDevice(objects::HEATER_7_HPA, MessageQueueIF::NO_QUEUE), gpioIds::HEATER_7},
}});
heaterHandler = new HeaterHandler(objects::HEATER_HANDLER, &gpioIF, helper, &pwrSwitcher,
pcdu::Switches::PDU2_CH3_TCS_BOARD_HEATER_IN_8V);
}
void ObjectFactory::createThermalController(HeaterHandler& heaterHandler) {
auto* tcsCtrl = new ThermalController(objects::THERMAL_CONTROLLER, heaterHandler);
tcsCtrl->connectModeTreeParent(satsystem::tcs::SUBSYSTEM);
}

View File

@ -1,6 +1,10 @@
#ifndef MISSION_CORE_GENERICFACTORY_H_ #ifndef MISSION_CORE_GENERICFACTORY_H_
#define MISSION_CORE_GENERICFACTORY_H_ #define MISSION_CORE_GENERICFACTORY_H_
#include "fsfw/power/PowerSwitchIF.h"
#include "fsfw_hal/common/gpio/GpioIF.h"
class HeaterHandler;
class HealthTableIF; class HealthTableIF;
class PusTmFunnel; class PusTmFunnel;
class CfdpTmFunnel; class CfdpTmFunnel;
@ -9,7 +13,10 @@ namespace ObjectFactory {
void produceGenericObjects(HealthTableIF** healthTable, PusTmFunnel** pusFunnel, void produceGenericObjects(HealthTableIF** healthTable, PusTmFunnel** pusFunnel,
CfdpTmFunnel** cfdpFunnel); CfdpTmFunnel** cfdpFunnel);
void createGenericHeaterComponents(GpioIF& gpioIF, PowerSwitchIF& pwrSwitcher,
HeaterHandler*& heaterHandler);
} void createThermalController(HeaterHandler& heaterHandler);
} // namespace ObjectFactory
#endif /* MISSION_CORE_GENERICFACTORY_H_ */ #endif /* MISSION_CORE_GENERICFACTORY_H_ */

View File

@ -0,0 +1,47 @@
#include "scheduling.h"
#include "fsfw/tasks/PeriodicTaskIF.h"
#include "mission/devices/devicedefinitions/Max31865Definitions.h"
void scheduling::scheduleTmpTempSensors(PeriodicTaskIF* tmpTask) {
const std::array<object_id_t, 5> tmpIds = {
objects::TMP1075_HANDLER_TCS_0, objects::TMP1075_HANDLER_TCS_1,
objects::TMP1075_HANDLER_PLPCDU_0, objects::TMP1075_HANDLER_PLPCDU_1,
objects::TMP1075_HANDLER_IF_BOARD};
for (const auto& tmpId : tmpIds) {
tmpTask->addComponent(tmpId, DeviceHandlerIF::PERFORM_OPERATION);
tmpTask->addComponent(tmpId, DeviceHandlerIF::SEND_WRITE);
tmpTask->addComponent(tmpId, DeviceHandlerIF::GET_WRITE);
tmpTask->addComponent(tmpId, DeviceHandlerIF::SEND_READ);
tmpTask->addComponent(tmpId, DeviceHandlerIF::GET_READ);
}
}
void scheduling::scheduleRtdSensors(PeriodicTaskIF* tcsTask) {
const std::array<object_id_t, EiveMax31855::NUM_RTDS> rtdIds = {
objects::RTD_0_IC3_PLOC_HEATSPREADER,
objects::RTD_1_IC4_PLOC_MISSIONBOARD,
objects::RTD_2_IC5_4K_CAMERA,
objects::RTD_3_IC6_DAC_HEATSPREADER,
objects::RTD_4_IC7_STARTRACKER,
objects::RTD_5_IC8_RW1_MX_MY,
objects::RTD_6_IC9_DRO,
objects::RTD_7_IC10_SCEX,
objects::RTD_8_IC11_X8,
objects::RTD_9_IC12_HPA,
objects::RTD_10_IC13_PL_TX,
objects::RTD_11_IC14_MPA,
objects::RTD_12_IC15_ACU,
objects::RTD_13_IC16_PLPCDU_HEATSPREADER,
objects::RTD_14_IC17_TCS_BOARD,
objects::RTD_15_IC18_IMTQ,
};
for (const auto& rtd : rtdIds) {
tcsTask->addComponent(rtd, DeviceHandlerIF::PERFORM_OPERATION);
tcsTask->addComponent(rtd, DeviceHandlerIF::SEND_WRITE);
tcsTask->addComponent(rtd, DeviceHandlerIF::GET_WRITE);
tcsTask->addComponent(rtd, DeviceHandlerIF::SEND_READ);
tcsTask->addComponent(rtd, DeviceHandlerIF::GET_READ);
}
}

11
mission/core/scheduling.h Normal file
View File

@ -0,0 +1,11 @@
#ifndef EIVE_OBSW_SCHEDULING_H
#define EIVE_OBSW_SCHEDULING_H
class PeriodicTaskIF;
namespace scheduling {
void scheduleTmpTempSensors(PeriodicTaskIF* tmpSensors);
void scheduleRtdSensors(PeriodicTaskIF* periodicTask);
} // namespace scheduling
#endif // EIVE_OBSW_SCHEDULING_H

View File

@ -7,7 +7,6 @@
#include <stdexcept> #include <stdexcept>
#include "devices/gpioIds.h"
#include "devices/powerSwitcherList.h" #include "devices/powerSwitcherList.h"
HeaterHandler::HeaterHandler(object_id_t setObjectId_, GpioIF* gpioInterface_, HeaterHelper helper, HeaterHandler::HeaterHandler(object_id_t setObjectId_, GpioIF* gpioInterface_, HeaterHelper helper,
@ -321,6 +320,15 @@ HeaterHandler::SwitchState HeaterHandler::checkSwitchState(heater::Switchers swi
return heaterVec.at(switchNr).switchState; return heaterVec.at(switchNr).switchState;
} }
ReturnValue_t HeaterHandler::switchHeater(heater::Switchers heater, SwitchState switchState) {
if (switchState == SwitchState::ON) {
return sendSwitchCommand(heater, PowerSwitchIF::SWITCH_ON);
} else if (switchState == SwitchState::OFF) {
return sendSwitchCommand(heater, PowerSwitchIF::SWITCH_OFF);
}
return returnvalue::FAILED;
}
bool HeaterHandler::allSwitchesOff() { bool HeaterHandler::allSwitchesOff() {
bool allSwitchesOrd = false; bool allSwitchesOrd = false;
MutexGuard mg(heaterMutex); MutexGuard mg(heaterMutex);
@ -352,3 +360,12 @@ ReturnValue_t HeaterHandler::getSwitchState(uint8_t switchNr) const {
ReturnValue_t HeaterHandler::getFuseState(uint8_t fuseNr) const { return 0; } ReturnValue_t HeaterHandler::getFuseState(uint8_t fuseNr) const { return 0; }
uint32_t HeaterHandler::getSwitchDelayMs(void) const { return 2000; } uint32_t HeaterHandler::getSwitchDelayMs(void) const { return 2000; }
HasHealthIF::HealthState HeaterHandler::getHealth(heater::Switchers heater) {
auto* healthDev = heaterVec.at(heater).healthDevice;
if (healthDev != nullptr) {
MutexGuard mg(heaterMutex);
return healthDev->getHealth();
}
return HasHealthIF::HealthState::FAULTY;
}

View File

@ -15,6 +15,7 @@
#include <fsfw_hal/common/gpio/GpioIF.h> #include <fsfw_hal/common/gpio/GpioIF.h>
#include <array> #include <array>
#include <utility>
#include <vector> #include <vector>
#include "devices/heaterSwitcherList.h" #include "devices/heaterSwitcherList.h"
@ -28,7 +29,8 @@ using HeaterPair = std::pair<HealthDevice*, gpioId_t>;
struct HeaterHelper { struct HeaterHelper {
public: public:
HeaterHelper(std::array<HeaterPair, heater::NUMBER_OF_SWITCHES> heaters) : heaters(heaters) {} HeaterHelper(std::array<HeaterPair, heater::NUMBER_OF_SWITCHES> heaters)
: heaters(std::move(heaters)) {}
std::array<HeaterPair, heater::NUMBER_OF_SWITCHES> heaters = {}; std::array<HeaterPair, heater::NUMBER_OF_SWITCHES> heaters = {};
}; };
/** /**
@ -40,6 +42,8 @@ class HeaterHandler : public ExecutableObjectIF,
public PowerSwitchIF, public PowerSwitchIF,
public SystemObject, public SystemObject,
public HasActionsIF { public HasActionsIF {
friend class ThermalController;
public: public:
static const uint8_t INTERFACE_ID = CLASS_ID::HEATER_HANDLER; static const uint8_t INTERFACE_ID = CLASS_ID::HEATER_HANDLER;
@ -59,6 +63,13 @@ class HeaterHandler : public ExecutableObjectIF,
virtual ~HeaterHandler(); virtual ~HeaterHandler();
protected:
enum SwitchState : bool { ON = true, OFF = false };
enum SwitchAction : uint8_t { SET_SWITCH_OFF, SET_SWITCH_ON, NONE };
ReturnValue_t switchHeater(heater::Switchers heater, SwitchState switchState);
HasHealthIF::HealthState getHealth(heater::Switchers heater);
ReturnValue_t performOperation(uint8_t operationCode = 0) override; ReturnValue_t performOperation(uint8_t operationCode = 0) override;
ReturnValue_t sendSwitchCommand(uint8_t switchNr, ReturnValue_t onOff) override; ReturnValue_t sendSwitchCommand(uint8_t switchNr, ReturnValue_t onOff) override;
@ -90,9 +101,6 @@ class HeaterHandler : public ExecutableObjectIF,
static const MessageQueueId_t NO_COMMANDER = 0; static const MessageQueueId_t NO_COMMANDER = 0;
enum SwitchState : bool { ON = true, OFF = false };
enum SwitchAction : uint8_t { SET_SWITCH_OFF, SET_SWITCH_ON, NONE };
/** /**
* @brief Struct holding information about a heater command to execute. * @brief Struct holding information about a heater command to execute.
* *

View File

@ -38,7 +38,7 @@ class Max31865EiveHandler : public DeviceHandlerBase {
bool debugMode = false; bool debugMode = false;
size_t structLen = 0; size_t structLen = 0;
bool instantNormal = false; bool instantNormal = false;
MAX31865::Max31865Set sensorDataset; MAX31865::PrimarySet sensorDataset;
PeriodicOperationDivider debugDivider; PeriodicOperationDivider debugDivider;
enum class InternalState { NONE, ON, ACTIVE, INACTIVE } state = InternalState::NONE; enum class InternalState { NONE, ON, ACTIVE, INACTIVE } state = InternalState::NONE;
bool transitionOk = false; bool transitionOk = false;

View File

@ -114,7 +114,7 @@ class Max31865PT1000Handler : public DeviceHandlerBase {
uint8_t deviceIdx = 0; uint8_t deviceIdx = 0;
std::array<uint8_t, 3> commandBuffer{0}; std::array<uint8_t, 3> commandBuffer{0};
MAX31865::Max31865Set sensorDataset; MAX31865::PrimarySet sensorDataset;
sid_t sensorDatasetSid; sid_t sensorDatasetSid;
#if OBSW_VERBOSE_LEVEL >= 1 #if OBSW_VERBOSE_LEVEL >= 1

View File

@ -56,20 +56,20 @@ static constexpr uint8_t CLEAR_FAULT_BIT_VAL = 0b0000'0010;
static constexpr size_t MAX_REPLY_SIZE = 5; static constexpr size_t MAX_REPLY_SIZE = 5;
class Max31865Set : public StaticLocalDataSet<4> { class PrimarySet : public StaticLocalDataSet<4> {
public: public:
/** /**
* Constructor used by owner and data creators like device handlers. * Constructor used by owner and data creators like device handlers.
* @param owner * @param owner
* @param setId * @param setId
*/ */
Max31865Set(HasLocalDataPoolIF* owner, uint32_t setId) : StaticLocalDataSet(owner, setId) {} PrimarySet(HasLocalDataPoolIF* owner, uint32_t setId) : StaticLocalDataSet(owner, setId) {}
/** /**
* Constructor used by data users like controllers. * Constructor used by data users like controllers.
* @param sid * @param sid
*/ */
Max31865Set(object_id_t objectId, uint32_t setId) : StaticLocalDataSet(sid_t(objectId, setId)) {} PrimarySet(object_id_t objectId, uint32_t setId) : StaticLocalDataSet(sid_t(objectId, setId)) {}
lp_var_t<float> rtdValue = lp_var_t<float> rtdValue =
lp_var_t<float>(sid.objectId, static_cast<lp_id_t>(PoolIds::RTD_VALUE), this); lp_var_t<float>(sid.objectId, static_cast<lp_id_t>(PoolIds::RTD_VALUE), this);

View File

@ -1,7 +1,6 @@
#ifndef MISSION_SYSTEM_TREE_TCSMODETREE_H_ #ifndef MISSION_SYSTEM_TREE_TCSMODETREE_H_
#define MISSION_SYSTEM_TREE_TCSMODETREE_H_ #define MISSION_SYSTEM_TREE_TCSMODETREE_H_
#include <fsfw/subsystem/Subsystem.h>
class Subsystem;
namespace satsystem { namespace satsystem {
namespace tcs { namespace tcs {

View File

@ -1,2 +1,4 @@
add_subdirectory(testtasks) add_subdirectory(testtasks)
add_subdirectory(gpio) add_subdirectory(gpio)
target_sources(${LIB_EIVE_MISSION} PUBLIC TestTask.cpp)

View File

@ -1,3 +1 @@
target_sources(${OBSW_NAME} PUBLIC DummyGpioIF.cpp) target_sources(${LIB_EIVE_MISSION} PUBLIC DummyGpioIF.cpp)
target_include_directories(${OBSW_NAME} PUBLIC ${CMAKE_CURRENT_SOURCE_DIR})

View File

@ -1,3 +1 @@
target_sources(${OBSW_NAME} PUBLIC TestTask.cpp) target_sources(${LIB_EIVE_MISSION} PUBLIC)
target_include_directories(${OBSW_NAME} PUBLIC ${CMAKE_CURRENT_SOURCE_DIR})

View File

@ -1,23 +1,33 @@
#include <dummies/SusDummy.h> #include <dummies/SusDummy.h>
#include <dummies/TemperatureSensorsDummy.h>
#include <fsfw/ipc/QueueFactory.h> #include <fsfw/ipc/QueueFactory.h>
#include <fsfw/power/DummyPowerSwitcher.h>
#include <fsfw/tasks/PeriodicTaskIF.h> #include <fsfw/tasks/PeriodicTaskIF.h>
#include <fsfw/tasks/TaskFactory.h> #include <fsfw/tasks/TaskFactory.h>
#include <mission/controller/ThermalController.h> #include <mission/controller/ThermalController.h>
#include <catch2/catch_test_macros.hpp> #include <catch2/catch_test_macros.hpp>
#include "dummies/TemperatureSensorInserter.h"
#include "../testEnvironment.h" #include "../testEnvironment.h"
#include "mission/core/GenericFactory.h"
#include "test/gpio/DummyGpioIF.h"
TEST_CASE("Thermal Controller", "[ThermalController]") { TEST_CASE("Thermal Controller", "[ThermalController]") {
const object_id_t THERMAL_CONTROLLER_ID = 0x123; const object_id_t THERMAL_CONTROLLER_ID = 0x123;
new TemperatureSensorsDummy(); TemperatureSensorInserter::Max31865DummyMap map0;
// new SusDummy(); TemperatureSensorInserter::Tmp1075DummyMap map1;
new TemperatureSensorInserter(objects::THERMAL_TEMP_INSERTER, map0, map1);
auto dummyGpioIF = new DummyGpioIF();
auto dummySwitcher = new DummyPowerSwitcher(objects::PCDU_HANDLER, 18, 0);
// TODO: Create dummy heater handler
HeaterHandler* heaterHandler = nullptr;
// new ThermalController(objects::THERMAL_CONTROLLER);
ObjectFactory::createGenericHeaterComponents(*dummyGpioIF, *dummySwitcher, heaterHandler);
// testEnvironment::initialize(); // testEnvironment::initialize();
ThermalController controller(THERMAL_CONTROLLER_ID); ThermalController controller(THERMAL_CONTROLLER_ID, *heaterHandler);
ReturnValue_t result = controller.initialize(); ReturnValue_t result = controller.initialize();
REQUIRE(result == returnvalue::OK); REQUIRE(result == returnvalue::OK);