fixed merge conflicts

This commit is contained in:
Jakob Meier
2022-06-05 10:54:46 +02:00
149 changed files with 5366 additions and 2912 deletions

View File

@ -1,3 +1,3 @@
target_sources(${LIB_EIVE_MISSION} PRIVATE
ThermalController.cpp
)
if(TGT_BSP MATCHES "arm/q7s")
target_sources(${LIB_EIVE_MISSION} PRIVATE ThermalController.cpp)
endif()

View File

@ -1,40 +1,212 @@
#include "ThermalController.h"
#include <fsfw/datapool/PoolReadGuard.h>
#include <objects/systemObjectList.h>
#include <mission/devices/devicedefinitions/BpxBatteryDefinitions.h>
#include <mission/devices/devicedefinitions/SyrlinksDefinitions.h>
#include <mission/devices/devicedefinitions/IMTQHandlerDefinitions.h>
#include <mission/devices/devicedefinitions/RwDefinitions.h>
#include <mission/devices/devicedefinitions/GomspaceDefinitions.h>
#include <mission/devices/devicedefinitions/GyroADIS1650XDefinitions.h>
#include <mission/devices/devicedefinitions/GyroL3GD20Definitions.h>
#include <mission/devices/devicedefinitions/payloadPcduDefinitions.h>
#include <linux/devices/devicedefinitions/StarTrackerDefinitions.h>
#include <fsfw_hal/devicehandlers/devicedefinitions/MgmLIS3HandlerDefs.h>
ThermalController::ThermalController(object_id_t objectId, object_id_t parentId)
: ExtendedControllerBase(objectId, parentId),
sensorTemperatures(this),
componentTemperatures(this) {}
susTemperatures(this),
deviceTemperatures(this),
componentTemperatures(this),
max31865Set0(objects::RTD_0_IC3_PLOC_HEATSPREADER, EiveMax31855::RtdCommands::EXCHANGE_SET_ID),
max31865Set1(objects::RTD_1_IC4_PLOC_MISSIONBOARD, EiveMax31855::RtdCommands::EXCHANGE_SET_ID),
max31865Set2(objects::RTD_2_IC5_4K_CAMERA, EiveMax31855::RtdCommands::EXCHANGE_SET_ID),
max31865Set3(objects::RTD_3_IC6_DAC_HEATSPREADER, EiveMax31855::RtdCommands::EXCHANGE_SET_ID),
max31865Set4(objects::RTD_4_IC7_STARTRACKER, EiveMax31855::RtdCommands::EXCHANGE_SET_ID),
max31865Set5(objects::RTD_5_IC8_RW1_MX_MY, EiveMax31855::RtdCommands::EXCHANGE_SET_ID),
max31865Set6(objects::RTD_6_IC9_DRO, EiveMax31855::RtdCommands::EXCHANGE_SET_ID),
max31865Set7(objects::RTD_7_IC10_SCEX, EiveMax31855::RtdCommands::EXCHANGE_SET_ID),
max31865Set8(objects::RTD_8_IC11_X8, EiveMax31855::RtdCommands::EXCHANGE_SET_ID),
max31865Set9(objects::RTD_9_IC12_HPA, EiveMax31855::RtdCommands::EXCHANGE_SET_ID),
max31865Set10(objects::RTD_10_IC13_PL_TX, EiveMax31855::RtdCommands::EXCHANGE_SET_ID),
max31865Set11(objects::RTD_11_IC14_MPA, EiveMax31855::RtdCommands::EXCHANGE_SET_ID),
max31865Set12(objects::RTD_12_IC15_ACU, EiveMax31855::RtdCommands::EXCHANGE_SET_ID),
max31865Set13(objects::RTD_13_IC16_PLPCDU_HEATSPREADER, EiveMax31855::RtdCommands::EXCHANGE_SET_ID),
max31865Set14(objects::RTD_14_IC17_TCS_BOARD, EiveMax31855::RtdCommands::EXCHANGE_SET_ID),
max31865Set15(objects::RTD_15_IC18_IMTQ, EiveMax31855::RtdCommands::EXCHANGE_SET_ID),
tmp1075Set1(objects::TMP1075_HANDLER_1),
tmp1075Set2(objects::TMP1075_HANDLER_2),
susSet0(objects::SUS_0_N_LOC_XFYFZM_PT_XF),
susSet1(objects::SUS_1_N_LOC_XBYFZM_PT_XB),
susSet2(objects::SUS_2_N_LOC_XFYBZB_PT_YB),
susSet3(objects::SUS_3_N_LOC_XFYBZF_PT_YF),
susSet4(objects::SUS_4_N_LOC_XMYFZF_PT_ZF),
susSet5(objects::SUS_5_N_LOC_XFYMZB_PT_ZB),
susSet6(objects::SUS_6_R_LOC_XFYBZM_PT_XF),
susSet7(objects::SUS_7_R_LOC_XBYBZM_PT_XB),
susSet8(objects::SUS_8_R_LOC_XBYBZB_PT_YB),
susSet9(objects::SUS_9_R_LOC_XBYBZB_PT_YF),
susSet10(objects::SUS_10_N_LOC_XMYBZF_PT_ZF),
susSet11(objects::SUS_11_R_LOC_XBYMZB_PT_ZB) {}
ReturnValue_t ThermalController::initialize() { return ControllerBase::initialize(); }
ReturnValue_t ThermalController::initialize() {
auto result = ExtendedControllerBase::initialize();
return result;
}
ReturnValue_t ThermalController::handleCommandMessage(CommandMessage* message) {
return RETURN_FAILED;
}
void ThermalController::performControlOperation() {
ReturnValue_t result = sensorTemperatures.read();
if (result != RETURN_OK) {
return;
if (result == RETURN_OK) {
copySensors();
sensorTemperatures.commit();
}
result = susTemperatures.read();
if (result == RETURN_OK) {
copySus();
susTemperatures.commit();
}
result = deviceTemperatures.read();
if (result == RETURN_OK) {
copyDevices();
deviceTemperatures.commit();
}
result = componentTemperatures.read();
if (result != RETURN_OK) {
return;
}
componentTemperatures.rw = (sensorTemperatures.rw.value + sensorTemperatures.gps.value) / 2;
sensorTemperatures.commit();
componentTemperatures.commit();
}
ReturnValue_t ThermalController::initializeLocalDataPool(localpool::DataPool& localDataPoolMap,
LocalDataPoolManager& poolManager) {
localDataPoolMap.emplace(thermalControllerDefinitions::SENSOR_RW, new PoolEntry<float>({0.0}));
localDataPoolMap.emplace(thermalControllerDefinitions::SENSOR_GPS, new PoolEntry<float>({0.0}));
localDataPoolMap.emplace(thermalControllerDefinitions::SENSOR_PLOC_HEATSPREADER,
new PoolEntry<float>({0.0}));
localDataPoolMap.emplace(thermalControllerDefinitions::SENSOR_PLOC_MISSIONBOARD,
new PoolEntry<float>({1.0}));
localDataPoolMap.emplace(thermalControllerDefinitions::SENSOR_4K_CAMERA,
new PoolEntry<float>({2.0}));
localDataPoolMap.emplace(thermalControllerDefinitions::SENSOR_DAC_HEATSPREADER,
new PoolEntry<float>({3.0}));
localDataPoolMap.emplace(thermalControllerDefinitions::SENSOR_STARTRACKER,
new PoolEntry<float>({4.0}));
localDataPoolMap.emplace(thermalControllerDefinitions::SENSOR_RW1, new PoolEntry<float>({5.0}));
localDataPoolMap.emplace(thermalControllerDefinitions::SENSOR_DRO, new PoolEntry<float>({6.0}));
localDataPoolMap.emplace(thermalControllerDefinitions::SENSOR_SCEX, new PoolEntry<float>({7.0}));
localDataPoolMap.emplace(thermalControllerDefinitions::SENSOR_X8, new PoolEntry<float>({8.0}));
localDataPoolMap.emplace(thermalControllerDefinitions::SENSOR_HPA, new PoolEntry<float>({9.0}));
localDataPoolMap.emplace(thermalControllerDefinitions::SENSOR_TX_MODUL,
new PoolEntry<float>({10.0}));
localDataPoolMap.emplace(thermalControllerDefinitions::SENSOR_MPA, new PoolEntry<float>({11.0}));
localDataPoolMap.emplace(thermalControllerDefinitions::SENSOR_ACU, new PoolEntry<float>({12.0}));
localDataPoolMap.emplace(thermalControllerDefinitions::SENSOR_PLPCDU_HEATSPREADER,
new PoolEntry<float>({13.0}));
localDataPoolMap.emplace(thermalControllerDefinitions::SENSOR_TCS_BOARD,
new PoolEntry<float>({14.0}));
localDataPoolMap.emplace(thermalControllerDefinitions::SENSOR_MAGNETTORQUER,
new PoolEntry<float>({15.0}));
localDataPoolMap.emplace(thermalControllerDefinitions::SENSOR_TMP1075_1,
new PoolEntry<float>({15.0}));
localDataPoolMap.emplace(thermalControllerDefinitions::SENSOR_TMP1075_2,
new PoolEntry<float>({15.0}));
localDataPoolMap.emplace(thermalControllerDefinitions::SUS_0_N_LOC_XFYFZM_PT_XF,
new PoolEntry<float>({0.0}));
localDataPoolMap.emplace(thermalControllerDefinitions::SUS_6_R_LOC_XFYBZM_PT_XF,
new PoolEntry<float>({0.0}));
localDataPoolMap.emplace(thermalControllerDefinitions::SUS_1_N_LOC_XBYFZM_PT_XB,
new PoolEntry<float>({0.0}));
localDataPoolMap.emplace(thermalControllerDefinitions::SUS_7_R_LOC_XBYBZM_PT_XB,
new PoolEntry<float>({0.0}));
localDataPoolMap.emplace(thermalControllerDefinitions::SUS_2_N_LOC_XFYBZB_PT_YB,
new PoolEntry<float>({0.0}));
localDataPoolMap.emplace(thermalControllerDefinitions::SUS_8_R_LOC_XBYBZB_PT_YB,
new PoolEntry<float>({0.0}));
localDataPoolMap.emplace(thermalControllerDefinitions::SUS_3_N_LOC_XFYBZF_PT_YF,
new PoolEntry<float>({0.0}));
localDataPoolMap.emplace(thermalControllerDefinitions::SUS_9_R_LOC_XBYBZB_PT_YF,
new PoolEntry<float>({0.0}));
localDataPoolMap.emplace(thermalControllerDefinitions::SUS_4_N_LOC_XMYFZF_PT_ZF,
new PoolEntry<float>({0.0}));
localDataPoolMap.emplace(thermalControllerDefinitions::SUS_10_N_LOC_XMYBZF_PT_ZF,
new PoolEntry<float>({0.0}));
localDataPoolMap.emplace(thermalControllerDefinitions::SUS_5_N_LOC_XFYMZB_PT_ZB,
new PoolEntry<float>({0.0}));
localDataPoolMap.emplace(thermalControllerDefinitions::SUS_11_R_LOC_XBYMZB_PT_ZB,
new PoolEntry<float>({0.0}));
localDataPoolMap.emplace(thermalControllerDefinitions::COMPONENT_RW, new PoolEntry<float>({0.0}));
localDataPoolMap.emplace(thermalControllerDefinitions::TEMP_Q7S, new PoolEntry<float>({0.0}));
localDataPoolMap.emplace(thermalControllerDefinitions::BATTERY_TEMP_1,
new PoolEntry<int16_t>({0}));
localDataPoolMap.emplace(thermalControllerDefinitions::BATTERY_TEMP_2,
new PoolEntry<int16_t>({0}));
localDataPoolMap.emplace(thermalControllerDefinitions::BATTERY_TEMP_3,
new PoolEntry<int16_t>({0}));
localDataPoolMap.emplace(thermalControllerDefinitions::BATTERY_TEMP_4,
new PoolEntry<int16_t>({0}));
localDataPoolMap.emplace(thermalControllerDefinitions::TEMP_RW1, new PoolEntry<int32_t>({0}));
localDataPoolMap.emplace(thermalControllerDefinitions::TEMP_RW2, new PoolEntry<int32_t>({0}));
localDataPoolMap.emplace(thermalControllerDefinitions::TEMP_RW3, new PoolEntry<int32_t>({0}));
localDataPoolMap.emplace(thermalControllerDefinitions::TEMP_RW4, new PoolEntry<int32_t>({0}));
localDataPoolMap.emplace(thermalControllerDefinitions::TEMP_STAR_TRACKER,
new PoolEntry<float>({0.0}));
localDataPoolMap.emplace(thermalControllerDefinitions::TEMP_SYRLINKS_POWER_AMPLIFIER,
new PoolEntry<uint16_t>({0}));
localDataPoolMap.emplace(thermalControllerDefinitions::TEMP_SYRLINKS_BASEBAND_BOARD,
new PoolEntry<uint16_t>({0}));
localDataPoolMap.emplace(thermalControllerDefinitions::TEMP_MGT, new PoolEntry<uint16_t>({0}));
localDataPoolMap.emplace(thermalControllerDefinitions::TEMP_ACU, new PoolEntry<float>({0}));
localDataPoolMap.emplace(thermalControllerDefinitions::TEMP_PDU1, new PoolEntry<float>({0}));
localDataPoolMap.emplace(thermalControllerDefinitions::TEMP_PDU2, new PoolEntry<float>({0}));
localDataPoolMap.emplace(thermalControllerDefinitions::TEMP_1_P60DOCK,
new PoolEntry<float>({0}));
localDataPoolMap.emplace(thermalControllerDefinitions::TEMP_2_P60DOCK,
new PoolEntry<float>({0}));
localDataPoolMap.emplace(thermalControllerDefinitions::TEMP_GYRO_0_SIDE_A,
new PoolEntry<float>({0.0}));
localDataPoolMap.emplace(thermalControllerDefinitions::TEMP_GYRO_1_SIDE_A,
new PoolEntry<float>({0.0}));
localDataPoolMap.emplace(thermalControllerDefinitions::TEMP_GYRO_2_SIDE_B,
new PoolEntry<float>({0.0}));
localDataPoolMap.emplace(thermalControllerDefinitions::TEMP_GYRO_3_SIDE_B,
new PoolEntry<float>({0.0}));
localDataPoolMap.emplace(thermalControllerDefinitions::TEMP_MGM_0_SIDE_A,
new PoolEntry<float>({0.0}));
localDataPoolMap.emplace(thermalControllerDefinitions::TEMP_MGM_2_SIDE_B,
new PoolEntry<float>({0.0}));
localDataPoolMap.emplace(thermalControllerDefinitions::TEMP_ADC_PAYLOAD_PCDU,
new PoolEntry<float>({0.0}));
poolManager.subscribeForPeriodicPacket(sensorTemperatures.getSid(), true, 1.0, false);
poolManager.subscribeForPeriodicPacket(susTemperatures.getSid(), true, 1.0, false);
poolManager.subscribeForPeriodicPacket(deviceTemperatures.getSid(), true, 1.0, false);
return RETURN_OK;
}
LocalPoolDataSetBase* ThermalController::getDataSetHandle(sid_t sid) { return nullptr; }
LocalPoolDataSetBase* ThermalController::getDataSetHandle(sid_t sid) {
switch (sid.ownerSetId) {
case thermalControllerDefinitions::SENSOR_TEMPERATURES:
return &sensorTemperatures;
case thermalControllerDefinitions::SUS_TEMPERATURES:
return &susTemperatures;
case thermalControllerDefinitions::DEVICE_TEMPERATURES:
return &deviceTemperatures;
default:
return nullptr;
}
}
ReturnValue_t ThermalController::checkModeCommand(Mode_t mode, Submode_t submode,
uint32_t* msToReachTheMode) {
@ -46,3 +218,671 @@ ReturnValue_t ThermalController::checkModeCommand(Mode_t mode, Submode_t submode
}
return RETURN_OK;
}
void ThermalController::copySensors() {
PoolReadGuard pg0(&max31865Set0);
if (pg0.getReadResult() == HasReturnvaluesIF::RETURN_OK) {
sensorTemperatures.sensor_ploc_heatspreader.value = max31865Set0.temperatureCelcius.value;
sensorTemperatures.sensor_ploc_heatspreader.setValid(max31865Set0.temperatureCelcius.isValid());
if (not sensorTemperatures.sensor_ploc_heatspreader.isValid()) {
sensorTemperatures.sensor_ploc_heatspreader.value = INVALID_TEMPERATURE;
}
}
PoolReadGuard pg1(&max31865Set1);
if (pg1.getReadResult() == HasReturnvaluesIF::RETURN_OK) {
sensorTemperatures.sensor_ploc_missionboard.value = max31865Set1.temperatureCelcius.value;
sensorTemperatures.sensor_ploc_missionboard.setValid(max31865Set1.temperatureCelcius.isValid());
if (not sensorTemperatures.sensor_ploc_missionboard.isValid()) {
sensorTemperatures.sensor_ploc_missionboard.value = INVALID_TEMPERATURE;
}
}
PoolReadGuard pg2(&max31865Set2);
if (pg2.getReadResult() == HasReturnvaluesIF::RETURN_OK) {
sensorTemperatures.sensor_4k_camera.value = max31865Set2.temperatureCelcius.value;
sensorTemperatures.sensor_4k_camera.setValid(max31865Set2.temperatureCelcius.isValid());
if (not sensorTemperatures.sensor_4k_camera.isValid()) {
sensorTemperatures.sensor_4k_camera.value = INVALID_TEMPERATURE;
}
}
PoolReadGuard pg3(&max31865Set3);
if (pg3.getReadResult() == HasReturnvaluesIF::RETURN_OK) {
sensorTemperatures.sensor_dac_heatspreader.value = max31865Set3.temperatureCelcius.value;
sensorTemperatures.sensor_dac_heatspreader.setValid(max31865Set3.temperatureCelcius.isValid());
if (not sensorTemperatures.sensor_dac_heatspreader.isValid()) {
sensorTemperatures.sensor_dac_heatspreader.value = INVALID_TEMPERATURE;
}
}
PoolReadGuard pg4(&max31865Set4);
if (pg4.getReadResult() == HasReturnvaluesIF::RETURN_OK) {
sensorTemperatures.sensor_startracker.value = max31865Set4.temperatureCelcius.value;
sensorTemperatures.sensor_startracker.setValid(max31865Set4.temperatureCelcius.isValid());
if (not sensorTemperatures.sensor_startracker.isValid()) {
sensorTemperatures.sensor_startracker.value = INVALID_TEMPERATURE;
}
}
PoolReadGuard pg5(&max31865Set5);
if (pg5.getReadResult() == HasReturnvaluesIF::RETURN_OK) {
sensorTemperatures.sensor_rw1.value = max31865Set5.temperatureCelcius.value;
sensorTemperatures.sensor_rw1.setValid(max31865Set5.temperatureCelcius.isValid());
if (not sensorTemperatures.sensor_rw1.isValid()) {
sensorTemperatures.sensor_rw1.value = INVALID_TEMPERATURE;
}
}
PoolReadGuard pg6(&max31865Set6);
if (pg6.getReadResult() == HasReturnvaluesIF::RETURN_OK) {
sensorTemperatures.sensor_dro.value = max31865Set6.temperatureCelcius.value;
sensorTemperatures.sensor_dro.setValid(max31865Set6.temperatureCelcius.isValid());
if (not sensorTemperatures.sensor_dro.isValid()) {
sensorTemperatures.sensor_dro.value = INVALID_TEMPERATURE;
}
}
PoolReadGuard pg7(&max31865Set7);
if (pg7.getReadResult() == HasReturnvaluesIF::RETURN_OK) {
sensorTemperatures.sensor_scex.value = max31865Set7.temperatureCelcius.value;
sensorTemperatures.sensor_scex.setValid(max31865Set7.temperatureCelcius.isValid());
if (not sensorTemperatures.sensor_scex.isValid()) {
sensorTemperatures.sensor_scex.value = INVALID_TEMPERATURE;
}
}
PoolReadGuard pg8(&max31865Set8);
if (pg8.getReadResult() == HasReturnvaluesIF::RETURN_OK) {
sensorTemperatures.sensor_x8.value = max31865Set8.temperatureCelcius.value;
sensorTemperatures.sensor_x8.setValid(max31865Set8.temperatureCelcius.isValid());
if (not sensorTemperatures.sensor_x8.isValid()) {
sensorTemperatures.sensor_x8.value = INVALID_TEMPERATURE;
}
}
PoolReadGuard pg9(&max31865Set9);
if (pg9.getReadResult() == HasReturnvaluesIF::RETURN_OK) {
sensorTemperatures.sensor_hpa.value = max31865Set9.temperatureCelcius.value;
sensorTemperatures.sensor_hpa.setValid(max31865Set9.temperatureCelcius.isValid());
if (not sensorTemperatures.sensor_hpa.isValid()) {
sensorTemperatures.sensor_hpa.value = INVALID_TEMPERATURE;
}
}
PoolReadGuard pg10(&max31865Set10);
if (pg10.getReadResult() == HasReturnvaluesIF::RETURN_OK) {
sensorTemperatures.sensor_tx_modul.value = max31865Set10.temperatureCelcius.value;
sensorTemperatures.sensor_tx_modul.setValid(max31865Set10.temperatureCelcius.isValid());
if (not sensorTemperatures.sensor_tx_modul.isValid()) {
sensorTemperatures.sensor_tx_modul.value = INVALID_TEMPERATURE;
}
}
PoolReadGuard pg11(&max31865Set11);
if (pg11.getReadResult() == HasReturnvaluesIF::RETURN_OK) {
sensorTemperatures.sensor_mpa.value = max31865Set11.temperatureCelcius.value;
sensorTemperatures.sensor_mpa.setValid(max31865Set11.temperatureCelcius.isValid());
if (not sensorTemperatures.sensor_mpa.isValid()) {
sensorTemperatures.sensor_mpa.value = INVALID_TEMPERATURE;
}
}
PoolReadGuard pg12(&max31865Set12);
if (pg12.getReadResult() == HasReturnvaluesIF::RETURN_OK) {
sensorTemperatures.sensor_acu.value = max31865Set12.temperatureCelcius.value;
sensorTemperatures.sensor_acu.setValid(max31865Set12.temperatureCelcius.isValid());
if (not sensorTemperatures.sensor_acu.isValid()) {
sensorTemperatures.sensor_acu.value = INVALID_TEMPERATURE;
}
}
PoolReadGuard pg13(&max31865Set13);
if (pg13.getReadResult() == HasReturnvaluesIF::RETURN_OK) {
sensorTemperatures.sensor_plpcdu_heatspreader.value = max31865Set13.temperatureCelcius.value;
sensorTemperatures.sensor_plpcdu_heatspreader.setValid(
max31865Set13.temperatureCelcius.isValid());
if (not sensorTemperatures.sensor_plpcdu_heatspreader.isValid()) {
sensorTemperatures.sensor_plpcdu_heatspreader.value = INVALID_TEMPERATURE;
}
}
PoolReadGuard pg14(&max31865Set14);
if (pg14.getReadResult() == HasReturnvaluesIF::RETURN_OK) {
sensorTemperatures.sensor_tcs_board.value = max31865Set14.temperatureCelcius.value;
sensorTemperatures.sensor_tcs_board.setValid(max31865Set14.temperatureCelcius.isValid());
if (not sensorTemperatures.sensor_tcs_board.isValid()) {
sensorTemperatures.sensor_tcs_board.value = INVALID_TEMPERATURE;
}
}
PoolReadGuard pg15(&max31865Set15);
if (pg15.getReadResult() == HasReturnvaluesIF::RETURN_OK) {
sensorTemperatures.sensor_magnettorquer.value = max31865Set15.temperatureCelcius.value;
sensorTemperatures.sensor_magnettorquer.setValid(max31865Set15.temperatureCelcius.isValid());
if (not sensorTemperatures.sensor_magnettorquer.isValid()) {
sensorTemperatures.sensor_magnettorquer.value = INVALID_TEMPERATURE;
}
}
PoolReadGuard pg111(&tmp1075Set1);
if (pg1.getReadResult() == HasReturnvaluesIF::RETURN_OK) {
sensorTemperatures.sensor_tmp1075_1.value = tmp1075Set1.temperatureCelcius.value;
sensorTemperatures.sensor_tmp1075_1.setValid(tmp1075Set1.temperatureCelcius.isValid());
if (not tmp1075Set1.temperatureCelcius.isValid()) {
sensorTemperatures.sensor_tmp1075_1.value = INVALID_TEMPERATURE;
}
}
PoolReadGuard pg112(&tmp1075Set2);
if (pg2.getReadResult() == HasReturnvaluesIF::RETURN_OK) {
sensorTemperatures.sensor_tmp1075_2.value = tmp1075Set2.temperatureCelcius.value;
sensorTemperatures.sensor_tmp1075_2.setValid(tmp1075Set2.temperatureCelcius.isValid());
if (not tmp1075Set2.temperatureCelcius.isValid()) {
sensorTemperatures.sensor_tmp1075_2.value = INVALID_TEMPERATURE;
}
}
}
void ThermalController::copySus() {
PoolReadGuard pg0(&susSet0);
if (pg0.getReadResult() == HasReturnvaluesIF::RETURN_OK) {
susTemperatures.sus_0_n_loc_xfyfzm_pt_xf.value = susSet0.temperatureCelcius.value;
susTemperatures.sus_0_n_loc_xfyfzm_pt_xf.setValid(susSet0.temperatureCelcius.isValid());
if (not susTemperatures.sus_0_n_loc_xfyfzm_pt_xf.isValid()) {
susTemperatures.sus_0_n_loc_xfyfzm_pt_xf.value = INVALID_TEMPERATURE;
}
}
PoolReadGuard pg1(&susSet1);
if (pg1.getReadResult() == HasReturnvaluesIF::RETURN_OK) {
susTemperatures.sus_6_r_loc_xfybzm_pt_xf.value = susSet1.temperatureCelcius.value;
susTemperatures.sus_6_r_loc_xfybzm_pt_xf.setValid(susSet1.temperatureCelcius.isValid());
if (not susTemperatures.sus_6_r_loc_xfybzm_pt_xf.isValid()) {
susTemperatures.sus_6_r_loc_xfybzm_pt_xf.value = INVALID_TEMPERATURE;
}
}
PoolReadGuard pg2(&susSet2);
if (pg2.getReadResult() == HasReturnvaluesIF::RETURN_OK) {
susTemperatures.sus_1_n_loc_xbyfzm_pt_xb.value = susSet2.temperatureCelcius.value;
susTemperatures.sus_1_n_loc_xbyfzm_pt_xb.setValid(susSet2.temperatureCelcius.isValid());
if (not susTemperatures.sus_1_n_loc_xbyfzm_pt_xb.isValid()) {
susTemperatures.sus_1_n_loc_xbyfzm_pt_xb.value = INVALID_TEMPERATURE;
}
}
PoolReadGuard pg3(&susSet3);
if (pg3.getReadResult() == HasReturnvaluesIF::RETURN_OK) {
susTemperatures.sus_7_r_loc_xbybzm_pt_xb.value = susSet3.temperatureCelcius.value;
susTemperatures.sus_7_r_loc_xbybzm_pt_xb.setValid(susSet3.temperatureCelcius.isValid());
if (not susTemperatures.sus_7_r_loc_xbybzm_pt_xb.isValid()) {
susTemperatures.sus_7_r_loc_xbybzm_pt_xb.value = INVALID_TEMPERATURE;
}
}
PoolReadGuard pg4(&susSet4);
if (pg4.getReadResult() == HasReturnvaluesIF::RETURN_OK) {
susTemperatures.sus_2_n_loc_xfybzb_pt_yb.value = susSet4.temperatureCelcius.value;
susTemperatures.sus_2_n_loc_xfybzb_pt_yb.setValid(susSet4.temperatureCelcius.isValid());
if (not susTemperatures.sus_2_n_loc_xfybzb_pt_yb.isValid()) {
susTemperatures.sus_2_n_loc_xfybzb_pt_yb.value = INVALID_TEMPERATURE;
}
}
PoolReadGuard pg5(&susSet5);
if (pg5.getReadResult() == HasReturnvaluesIF::RETURN_OK) {
susTemperatures.sus_8_r_loc_xbybzb_pt_yb.value = susSet5.temperatureCelcius.value;
susTemperatures.sus_8_r_loc_xbybzb_pt_yb.setValid(susSet5.temperatureCelcius.isValid());
if (not susTemperatures.sus_8_r_loc_xbybzb_pt_yb.isValid()) {
susTemperatures.sus_8_r_loc_xbybzb_pt_yb.value = INVALID_TEMPERATURE;
}
}
PoolReadGuard pg6(&susSet6);
if (pg6.getReadResult() == HasReturnvaluesIF::RETURN_OK) {
susTemperatures.sus_3_n_loc_xfybzf_pt_yf.value = susSet6.temperatureCelcius.value;
susTemperatures.sus_3_n_loc_xfybzf_pt_yf.setValid(susSet6.temperatureCelcius.isValid());
if (not susTemperatures.sus_3_n_loc_xfybzf_pt_yf.isValid()) {
susTemperatures.sus_3_n_loc_xfybzf_pt_yf.value = INVALID_TEMPERATURE;
}
}
PoolReadGuard pg7(&susSet7);
if (pg7.getReadResult() == HasReturnvaluesIF::RETURN_OK) {
susTemperatures.sus_9_r_loc_xbybzb_pt_yf.value = susSet7.temperatureCelcius.value;
susTemperatures.sus_9_r_loc_xbybzb_pt_yf.setValid(susSet7.temperatureCelcius.isValid());
if (not susTemperatures.sus_9_r_loc_xbybzb_pt_yf.isValid()) {
susTemperatures.sus_9_r_loc_xbybzb_pt_yf.value = INVALID_TEMPERATURE;
}
}
PoolReadGuard pg8(&susSet8);
if (pg8.getReadResult() == HasReturnvaluesIF::RETURN_OK) {
susTemperatures.sus_4_n_loc_xmyfzf_pt_zf.value = susSet8.temperatureCelcius.value;
susTemperatures.sus_4_n_loc_xmyfzf_pt_zf.setValid(susSet8.temperatureCelcius.isValid());
if (not susTemperatures.sus_4_n_loc_xmyfzf_pt_zf.isValid()) {
susTemperatures.sus_4_n_loc_xmyfzf_pt_zf.value = INVALID_TEMPERATURE;
}
}
PoolReadGuard pg9(&susSet9);
if (pg9.getReadResult() == HasReturnvaluesIF::RETURN_OK) {
susTemperatures.sus_10_n_loc_xmybzf_pt_zf.value = susSet9.temperatureCelcius.value;
susTemperatures.sus_10_n_loc_xmybzf_pt_zf.setValid(susSet9.temperatureCelcius.isValid());
if (not susTemperatures.sus_10_n_loc_xmybzf_pt_zf.isValid()) {
susTemperatures.sus_10_n_loc_xmybzf_pt_zf.value = INVALID_TEMPERATURE;
}
}
PoolReadGuard pg10(&susSet10);
if (pg10.getReadResult() == HasReturnvaluesIF::RETURN_OK) {
susTemperatures.sus_5_n_loc_xfymzb_pt_zb.value = susSet10.temperatureCelcius.value;
susTemperatures.sus_5_n_loc_xfymzb_pt_zb.setValid(susSet10.temperatureCelcius.isValid());
if (not susTemperatures.sus_5_n_loc_xfymzb_pt_zb.isValid()) {
susTemperatures.sus_5_n_loc_xfymzb_pt_zb.value = INVALID_TEMPERATURE;
}
}
PoolReadGuard pg11(&susSet11);
if (pg11.getReadResult() == HasReturnvaluesIF::RETURN_OK) {
susTemperatures.sus_11_r_loc_xbymzb_pt_zb.value = susSet11.temperatureCelcius.value;
susTemperatures.sus_11_r_loc_xbymzb_pt_zb.setValid(susSet11.temperatureCelcius.isValid());
if (not susTemperatures.sus_11_r_loc_xbymzb_pt_zb.isValid()) {
susTemperatures.sus_11_r_loc_xbymzb_pt_zb.value = INVALID_TEMPERATURE;
}
}
}
void ThermalController::copyDevices() {
lp_var_t<float> tempQ7s = lp_var_t<float>(objects::CORE_CONTROLLER, core::PoolIds::TEMPERATURE);
ReturnValue_t result = tempQ7s.read();
if (result != RETURN_OK) {
sif::warning << "ThermalController: Failed to read Q7S temperature" << std::endl;
deviceTemperatures.q7s.setValid(false);
deviceTemperatures.q7s = static_cast<float>(INVALID_TEMPERATURE);
}
else {
deviceTemperatures.q7s = tempQ7s;
deviceTemperatures.q7s.setValid(tempQ7s.isValid());
}
result = tempQ7s.commit();
if (result != RETURN_OK) {
sif::warning << "ThermalController: Failed to commit" << std::endl;
}
lp_var_t<int16_t> battTemp1 = lp_var_t<int16_t>(objects::BPX_BATT_HANDLER, BpxBattery::BATT_TEMP_1);
result = battTemp1.read();
if (result != RETURN_OK) {
sif::warning << "ThermalController: Failed to read battery temperature 1" << std::endl;
deviceTemperatures.batteryTemp1.setValid(false);
deviceTemperatures.batteryTemp1 = static_cast<float>(INVALID_TEMPERATURE);
}
else {
deviceTemperatures.batteryTemp1 = battTemp1;
deviceTemperatures.batteryTemp1.setValid(battTemp1.isValid());
}
result = battTemp1.commit();
if (result != RETURN_OK) {
sif::warning << "ThermalController: Failed to commit" << std::endl;
}
lp_var_t<int16_t> battTemp2 = lp_var_t<int16_t>(objects::BPX_BATT_HANDLER, BpxBattery::BATT_TEMP_2);
result = battTemp2.read();
if (result != RETURN_OK) {
sif::warning << "ThermalController: Failed to read battery temperature 2" << std::endl;
deviceTemperatures.batteryTemp2.setValid(false);
deviceTemperatures.batteryTemp2 = static_cast<float>(INVALID_TEMPERATURE);
}
else {
deviceTemperatures.batteryTemp2 = battTemp2;
deviceTemperatures.batteryTemp2.setValid(battTemp2.isValid());
}
result = battTemp2.commit();
if (result != RETURN_OK) {
sif::warning << "ThermalController: Failed to commit" << std::endl;
}
lp_var_t<int16_t> battTemp3 = lp_var_t<int16_t>(objects::BPX_BATT_HANDLER, BpxBattery::BATT_TEMP_3);
result = battTemp3.read();
if (result != RETURN_OK) {
sif::warning << "ThermalController: Failed to read battery temperature 3" << std::endl;
deviceTemperatures.batteryTemp3.setValid(false);
deviceTemperatures.batteryTemp3 = static_cast<float>(INVALID_TEMPERATURE);
}
else {
deviceTemperatures.batteryTemp3 = battTemp3;
deviceTemperatures.batteryTemp3.setValid(battTemp3.isValid());
}
result = battTemp3.commit();
if (result != RETURN_OK) {
sif::warning << "ThermalController: Failed to commit" << std::endl;
}
lp_var_t<int16_t> battTemp4 = lp_var_t<int16_t>(objects::BPX_BATT_HANDLER, BpxBattery::BATT_TEMP_4);
result = battTemp4.read();
if (result != RETURN_OK) {
sif::warning << "ThermalController: Failed to read battery temperature 4" << std::endl;
deviceTemperatures.batteryTemp4.setValid(false);
deviceTemperatures.batteryTemp4 = static_cast<float>(INVALID_TEMPERATURE);
}
else {
deviceTemperatures.batteryTemp4 = battTemp4;
deviceTemperatures.batteryTemp4.setValid(battTemp4.isValid());
}
result = battTemp4.commit();
if (result != RETURN_OK) {
sif::warning << "ThermalController: Failed to commit" << std::endl;
}
lp_var_t<int32_t> tempRw1 = lp_var_t<int32_t>(objects::RW1, RwDefinitions::TEMPERATURE_C);
result = tempRw1.read();
if (result != RETURN_OK) {
sif::warning << "ThermalController: Failed to read reaction wheel 1 temperature" << std::endl;
deviceTemperatures.rw1.setValid(false);
deviceTemperatures.rw1 = static_cast<int32_t>(INVALID_TEMPERATURE);
}
else {
deviceTemperatures.rw1.setValid(tempRw1.isValid());
deviceTemperatures.rw1 = tempRw1;
}
result = tempRw1.commit();
if (result != RETURN_OK) {
sif::warning << "ThermalController: Failed to commit" << std::endl;
}
lp_var_t<int32_t> tempRw2 = lp_var_t<int32_t>(objects::RW2, RwDefinitions::TEMPERATURE_C);
result = tempRw2.read();
if (result != RETURN_OK) {
sif::warning << "ThermalController: Failed to read reaction wheel 2 temperature" << std::endl;
deviceTemperatures.rw2.setValid(false);
deviceTemperatures.rw2 = static_cast<int32_t>(INVALID_TEMPERATURE);
}
else {
deviceTemperatures.rw2.setValid(tempRw2.isValid());
deviceTemperatures.rw2 = tempRw2;
}
result = tempRw2.commit();
if (result != RETURN_OK) {
sif::warning << "ThermalController: Failed to commit" << std::endl;
}
lp_var_t<int32_t> tempRw3 = lp_var_t<int32_t>(objects::RW3, RwDefinitions::TEMPERATURE_C);
result = tempRw3.read();
if (result != RETURN_OK) {
sif::warning << "ThermalController: Failed to read reaction wheel 3 temperature" << std::endl;
deviceTemperatures.rw3.setValid(false);
deviceTemperatures.rw3 = static_cast<int32_t>(INVALID_TEMPERATURE);
}
else {
deviceTemperatures.rw3.setValid(tempRw3.isValid());
deviceTemperatures.rw3 = tempRw3;
}
result = tempRw3.commit();
if (result != RETURN_OK) {
sif::warning << "ThermalController: Failed to commit" << std::endl;
}
lp_var_t<int32_t> tempRw4 = lp_var_t<int32_t>(objects::RW4, RwDefinitions::TEMPERATURE_C);
result = tempRw4.read();
if (result != RETURN_OK) {
sif::warning << "ThermalController: Failed to read reaction wheel 4 temperature" << std::endl;
deviceTemperatures.rw4.setValid(false);
deviceTemperatures.rw4 = static_cast<int32_t>(INVALID_TEMPERATURE);
}
else {
deviceTemperatures.rw4.setValid(tempRw4.isValid());
deviceTemperatures.rw4 = tempRw4;
}
result = tempRw4.commit();
if (result != RETURN_OK) {
sif::warning << "ThermalController: Failed to commit" << std::endl;
}
lp_var_t<float> tempStartracker =
lp_var_t<float>(objects::STAR_TRACKER, startracker::MCU_TEMPERATURE);
result = tempStartracker.read();
if (result != RETURN_OK) {
sif::warning << "ThermalController: Failed to read startracker temperature" << std::endl;
deviceTemperatures.startracker.setValid(false);
deviceTemperatures.startracker = static_cast<float>(INVALID_TEMPERATURE);
}
else {
deviceTemperatures.startracker.setValid(tempStartracker.isValid());
deviceTemperatures.startracker = tempStartracker;
}
result = tempStartracker.commit();
if (result != RETURN_OK) {
sif::warning << "ThermalController: Failed to commit" << std::endl;
}
lp_var_t<uint16_t> tempSyrlinksPowerAmplifier =
lp_var_t<uint16_t>(objects::SYRLINKS_HK_HANDLER, syrlinks::TEMP_POWER_AMPLIFIER);
result = tempSyrlinksPowerAmplifier.read();
if (result != RETURN_OK) {
sif::warning << "ThermalController: Failed to read syrlinks power amplifier temperature" << std::endl;
deviceTemperatures.syrlinksPowerAmplifier.setValid(false);
deviceTemperatures.syrlinksPowerAmplifier = static_cast<float>(INVALID_TEMPERATURE);
}
else {
deviceTemperatures.syrlinksPowerAmplifier.setValid(tempSyrlinksPowerAmplifier.isValid());
deviceTemperatures.syrlinksPowerAmplifier = tempSyrlinksPowerAmplifier;
}
result = tempSyrlinksPowerAmplifier.commit();
if (result != RETURN_OK) {
sif::warning << "ThermalController: Failed to commit" << std::endl;
}
lp_var_t<uint16_t> tempSyrlinksBasebandBoard =
lp_var_t<uint16_t>(objects::SYRLINKS_HK_HANDLER, syrlinks::TEMP_BASEBAND_BOARD);
result = tempSyrlinksBasebandBoard.read();
if (result != RETURN_OK) {
sif::warning << "ThermalController: Failed to read syrlinks baseband board temperature" << std::endl;
deviceTemperatures.syrlinksBasebandBoard.setValid(false);
deviceTemperatures.syrlinksBasebandBoard = static_cast<float>(INVALID_TEMPERATURE);
}
else {
deviceTemperatures.syrlinksBasebandBoard.setValid(tempSyrlinksBasebandBoard.isValid());
deviceTemperatures.syrlinksBasebandBoard = tempSyrlinksBasebandBoard;
}
result = tempSyrlinksBasebandBoard.commit();
if (result != RETURN_OK) {
sif::warning << "ThermalController: Failed to commit" << std::endl;
}
lp_var_t<uint16_t> tempMgt =
lp_var_t<uint16_t>(objects::IMTQ_HANDLER, IMTQ::MCU_TEMPERATURE);
result = tempMgt.read();
if (result != RETURN_OK) {
sif::warning << "ThermalController: Failed to read MGT temperature" << std::endl;
deviceTemperatures.mgt.setValid(false);
deviceTemperatures.mgt = static_cast<float>(INVALID_TEMPERATURE);
}
else {
deviceTemperatures.mgt.setValid(tempMgt.isValid());
deviceTemperatures.mgt = tempMgt;
}
result = tempMgt.commit();
if (result != RETURN_OK) {
sif::warning << "ThermalController: Failed to commit" << std::endl;
}
lp_vec_t<float, 3> tempAcu =
lp_vec_t<float, 3>(objects::ACU_HANDLER, P60System::pool::ACU_TEMPERATURES);
result = tempAcu.read();
if (result != RETURN_OK) {
sif::warning << "ThermalController: Failed to read ACU temperatures" << std::endl;
deviceTemperatures.acu.setValid(false);
std::memset(deviceTemperatures.acu.value, INVALID_TEMPERATURE,
deviceTemperatures.acu.getSize());
}
else {
deviceTemperatures.acu.setValid(tempAcu.isValid());
deviceTemperatures.acu = tempAcu;
}
result = tempAcu.commit();
if (result != RETURN_OK) {
sif::warning << "ThermalController: Failed to commit" << std::endl;
}
lp_var_t<float> tempPdu1 =
lp_var_t<float>(objects::PDU1_HANDLER, P60System::pool::PDU_TEMPERATURE);
result = tempPdu1.read();
if (result != RETURN_OK) {
sif::warning << "ThermalController: Failed to read PDU1 temperature" << std::endl;
deviceTemperatures.pdu1.setValid(false);
deviceTemperatures.pdu1 = static_cast<float>(INVALID_TEMPERATURE);
}
else {
deviceTemperatures.pdu1.setValid(tempPdu1.isValid());
deviceTemperatures.pdu1 = tempPdu1;
}
result = tempPdu1.commit();
if (result != RETURN_OK) {
sif::warning << "ThermalController: Failed to commit" << std::endl;
}
lp_var_t<float> tempPdu2 =
lp_var_t<float>(objects::PDU2_HANDLER, P60System::pool::PDU_TEMPERATURE);
result = tempPdu2.read();
if (result != RETURN_OK) {
sif::warning << "ThermalController: Failed to read PDU2 temperature" << std::endl;
deviceTemperatures.pdu2.setValid(false);
deviceTemperatures.pdu2 = static_cast<float>(INVALID_TEMPERATURE);
}
else {
deviceTemperatures.pdu2.setValid(tempPdu1.isValid());
deviceTemperatures.pdu2 = tempPdu1;
}
result = tempPdu2.commit();
if (result != RETURN_OK) {
sif::warning << "ThermalController: Failed to commit" << std::endl;
}
lp_var_t<float> temp1P60dock =
lp_var_t<float>(objects::P60DOCK_HANDLER, P60System::pool::P60DOCK_TEMPERATURE_1);
result = temp1P60dock.read();
if (result != RETURN_OK) {
sif::warning << "ThermalController: Failed to read P60 dock temperature 1" << std::endl;
deviceTemperatures.temp1P60dock.setValid(false);
deviceTemperatures.temp1P60dock = static_cast<float>(INVALID_TEMPERATURE);
}
else {
deviceTemperatures.temp1P60dock.setValid(temp1P60dock.isValid());
deviceTemperatures.temp1P60dock = temp1P60dock;
}
result = temp1P60dock.commit();
if (result != RETURN_OK) {
sif::warning << "ThermalController: Failed to commit" << std::endl;
}
lp_var_t<float> temp2P60dock =
lp_var_t<float>(objects::P60DOCK_HANDLER, P60System::pool::P60DOCK_TEMPERATURE_2);
result = temp2P60dock.read();
if (result != RETURN_OK) {
sif::warning << "ThermalController: Failed to read P60 dock temperature 2" << std::endl;
deviceTemperatures.temp2P60dock.setValid(false);
deviceTemperatures.temp2P60dock = static_cast<float>(INVALID_TEMPERATURE);
}
else {
deviceTemperatures.temp2P60dock.setValid(temp2P60dock.isValid());
deviceTemperatures.temp2P60dock = temp2P60dock;
}
result = temp2P60dock.commit();
if (result != RETURN_OK) {
sif::warning << "ThermalController: Failed to commit" << std::endl;
}
lp_var_t<float> tempGyro0 =
lp_var_t<float>(objects::GYRO_0_ADIS_HANDLER, ADIS1650X::TEMPERATURE);
result = tempGyro0.read();
if (result != RETURN_OK) {
sif::warning << "ThermalController: Failed to read gyro 0 temperature" << std::endl;
deviceTemperatures.gyro0SideA.setValid(false);
deviceTemperatures.gyro0SideA = static_cast<float>(INVALID_TEMPERATURE);
}
else {
deviceTemperatures.gyro0SideA.setValid(tempGyro0.isValid());
deviceTemperatures.gyro0SideA = tempGyro0;
}
result = tempGyro0.commit();
if (result != RETURN_OK) {
sif::warning << "ThermalController: Failed to commit" << std::endl;
}
lp_var_t<float> tempGyro1 =
lp_var_t<float>(objects::GYRO_1_L3G_HANDLER, L3GD20H::TEMPERATURE);
result = tempGyro1.read();
if (result != RETURN_OK) {
sif::warning << "ThermalController: Failed to read gyro 1 temperature" << std::endl;
deviceTemperatures.gyro1SideA.setValid(false);
deviceTemperatures.gyro1SideA = static_cast<float>(INVALID_TEMPERATURE);
}
else {
deviceTemperatures.gyro1SideA.setValid(tempGyro1.isValid());
deviceTemperatures.gyro1SideA = tempGyro1;
}
result = tempGyro1.commit();
if (result != RETURN_OK) {
sif::warning << "ThermalController: Failed to commit" << std::endl;
}
lp_var_t<float> tempGyro2 =
lp_var_t<float>(objects::GYRO_2_ADIS_HANDLER, ADIS1650X::TEMPERATURE);
result = tempGyro2.read();
if (result != RETURN_OK) {
sif::warning << "ThermalController: Failed to read gyro 2 temperature" << std::endl;
deviceTemperatures.gyro2SideB.setValid(false);
deviceTemperatures.gyro2SideB = static_cast<float>(INVALID_TEMPERATURE);
}
else {
deviceTemperatures.gyro2SideB.setValid(tempGyro2.isValid());
deviceTemperatures.gyro2SideB = tempGyro2;
}
result = tempGyro2.commit();
if (result != RETURN_OK) {
sif::warning << "ThermalController: Failed to commit" << std::endl;
}
lp_var_t<float> tempGyro3 =
lp_var_t<float>(objects::GYRO_3_L3G_HANDLER, L3GD20H::TEMPERATURE);
result = tempGyro3.read();
if (result != RETURN_OK) {
sif::warning << "ThermalController: Failed to read gyro 3 temperature" << std::endl;
deviceTemperatures.gyro3SideB.setValid(false);
deviceTemperatures.gyro3SideB = static_cast<float>(INVALID_TEMPERATURE);
}
else {
deviceTemperatures.gyro3SideB.setValid(tempGyro3.isValid());
deviceTemperatures.gyro3SideB = tempGyro3;
}
result = tempGyro3.commit();
if (result != RETURN_OK) {
sif::warning << "ThermalController: Failed to commit" << std::endl;
}
lp_var_t<float> tempMgm0 =
lp_var_t<float>(objects::MGM_0_LIS3_HANDLER, MGMLIS3MDL::TEMPERATURE_CELCIUS);
result = tempMgm0.read();
if (result != RETURN_OK) {
sif::warning << "ThermalController: Failed to read MGM 0 temperature" << std::endl;
deviceTemperatures.mgm0SideA.setValid(false);
deviceTemperatures.mgm0SideA = static_cast<float>(INVALID_TEMPERATURE);
}
else {
deviceTemperatures.mgm0SideA.setValid(tempMgm0.isValid());
deviceTemperatures.mgm0SideA = tempMgm0;
}
result = tempMgm0.commit();
if (result != RETURN_OK) {
sif::warning << "ThermalController: Failed to commit" << std::endl;
}
lp_var_t<float> tempMgm2 =
lp_var_t<float>(objects::MGM_2_LIS3_HANDLER, MGMLIS3MDL::TEMPERATURE_CELCIUS);
result = tempMgm2.read();
if (result != RETURN_OK) {
sif::warning << "ThermalController: Failed to read MGM 2 temperature" << std::endl;
deviceTemperatures.mgm2SideB.setValid(false);
deviceTemperatures.mgm2SideB = static_cast<float>(INVALID_TEMPERATURE);
}
else {
deviceTemperatures.mgm2SideB.setValid(tempMgm2.isValid());
deviceTemperatures.mgm2SideB = tempMgm2;
}
result = tempMgm2.commit();
if (result != RETURN_OK) {
sif::warning << "ThermalController: Failed to commit" << std::endl;
}
lp_var_t<float> tempAdcPayloadPcdu =
lp_var_t<float>(objects::PLPCDU_HANDLER, plpcdu::TEMP);
result = tempAdcPayloadPcdu.read();
if (result != RETURN_OK) {
sif::warning << "ThermalController: Failed to read payload PCDU ADC temperature" << std::endl;
deviceTemperatures.adcPayloadPcdu.setValid(false);
deviceTemperatures.adcPayloadPcdu = static_cast<float>(INVALID_TEMPERATURE);
}
else {
deviceTemperatures.adcPayloadPcdu.setValid(tempAdcPayloadPcdu.isValid());
deviceTemperatures.adcPayloadPcdu = tempAdcPayloadPcdu;
}
result = tempAdcPayloadPcdu.commit();
if (result != RETURN_OK) {
sif::warning << "ThermalController: Failed to commit" << std::endl;
}
}

View File

@ -3,9 +3,14 @@
#include <fsfw/controller/ExtendedControllerBase.h>
#include <mission/controller/controllerdefinitions/ThermalControllerDefinitions.h>
#include <mission/devices/devicedefinitions/Max31865Definitions.h>
#include <mission/devices/devicedefinitions/SusDefinitions.h>
#include <mission/devices/devicedefinitions/Tmp1075Definitions.h>
class ThermalController : public ExtendedControllerBase {
public:
static const uint16_t INVALID_TEMPERATURE = 999;
ThermalController(object_id_t objectId, object_id_t parentId);
ReturnValue_t initialize() override;
@ -23,7 +28,47 @@ class ThermalController : public ExtendedControllerBase {
private:
thermalControllerDefinitions::SensorTemperatures sensorTemperatures;
thermalControllerDefinitions::SusTemperatures susTemperatures;
thermalControllerDefinitions::DeviceTemperatures deviceTemperatures;
thermalControllerDefinitions::ComponentTemperatures componentTemperatures;
// Temperature Sensors
MAX31865::Max31865Set max31865Set0;
MAX31865::Max31865Set max31865Set1;
MAX31865::Max31865Set max31865Set2;
MAX31865::Max31865Set max31865Set3;
MAX31865::Max31865Set max31865Set4;
MAX31865::Max31865Set max31865Set5;
MAX31865::Max31865Set max31865Set6;
MAX31865::Max31865Set max31865Set7;
MAX31865::Max31865Set max31865Set8;
MAX31865::Max31865Set max31865Set9;
MAX31865::Max31865Set max31865Set10;
MAX31865::Max31865Set max31865Set11;
MAX31865::Max31865Set max31865Set12;
MAX31865::Max31865Set max31865Set13;
MAX31865::Max31865Set max31865Set14;
MAX31865::Max31865Set max31865Set15;
TMP1075::Tmp1075Dataset tmp1075Set1;
TMP1075::Tmp1075Dataset tmp1075Set2;
// SUS
SUS::SusDataset susSet0;
SUS::SusDataset susSet1;
SUS::SusDataset susSet2;
SUS::SusDataset susSet3;
SUS::SusDataset susSet4;
SUS::SusDataset susSet5;
SUS::SusDataset susSet6;
SUS::SusDataset susSet7;
SUS::SusDataset susSet8;
SUS::SusDataset susSet9;
SUS::SusDataset susSet10;
SUS::SusDataset susSet11;
void copySensors();
void copySus();
void copyDevices();
};
#endif /* MISSION_CONTROLLER_THERMALCONTROLLER_H_ */

View File

@ -6,22 +6,191 @@
namespace thermalControllerDefinitions {
enum SetIds : uint32_t { SENSOR_TEMPERATURES, COMPONENT_TEMPERATURES };
enum SetIds : uint32_t {
SENSOR_TEMPERATURES,
DEVICE_TEMPERATURES,
SUS_TEMPERATURES,
COMPONENT_TEMPERATURES
};
enum PoolIds : lp_id_t { SENSOR_RW, SENSOR_GPS, COMPONENT_RW };
enum PoolIds : lp_id_t {
SENSOR_PLOC_HEATSPREADER,
SENSOR_PLOC_MISSIONBOARD,
SENSOR_4K_CAMERA,
SENSOR_DAC_HEATSPREADER,
SENSOR_STARTRACKER,
SENSOR_RW1,
SENSOR_DRO,
SENSOR_SCEX,
SENSOR_X8,
SENSOR_HPA,
SENSOR_TX_MODUL,
SENSOR_MPA,
SENSOR_ACU,
SENSOR_PLPCDU_HEATSPREADER,
SENSOR_TCS_BOARD,
SENSOR_MAGNETTORQUER,
SENSOR_TMP1075_1,
SENSOR_TMP1075_2,
SUS_0_N_LOC_XFYFZM_PT_XF,
SUS_6_R_LOC_XFYBZM_PT_XF,
SUS_1_N_LOC_XBYFZM_PT_XB,
SUS_7_R_LOC_XBYBZM_PT_XB,
SUS_2_N_LOC_XFYBZB_PT_YB,
SUS_8_R_LOC_XBYBZB_PT_YB,
SUS_3_N_LOC_XFYBZF_PT_YF,
SUS_9_R_LOC_XBYBZB_PT_YF,
SUS_4_N_LOC_XMYFZF_PT_ZF,
SUS_10_N_LOC_XMYBZF_PT_ZF,
SUS_5_N_LOC_XFYMZB_PT_ZB,
SUS_11_R_LOC_XBYMZB_PT_ZB,
COMPONENT_RW,
TEMP_Q7S,
BATTERY_TEMP_1,
BATTERY_TEMP_2,
BATTERY_TEMP_3,
BATTERY_TEMP_4,
TEMP_RW1,
TEMP_RW2,
TEMP_RW3,
TEMP_RW4,
TEMP_STAR_TRACKER,
TEMP_SYRLINKS_POWER_AMPLIFIER,
TEMP_SYRLINKS_BASEBAND_BOARD,
TEMP_MGT,
TEMP_ACU,
TEMP_PDU1,
TEMP_PDU2,
TEMP_1_P60DOCK,
TEMP_2_P60DOCK,
TEMP_GYRO_0_SIDE_A,
TEMP_GYRO_1_SIDE_A,
TEMP_GYRO_2_SIDE_B,
TEMP_GYRO_3_SIDE_B,
TEMP_MGM_0_SIDE_A,
TEMP_MGM_2_SIDE_B,
TEMP_ADC_PAYLOAD_PCDU
};
static const uint8_t ENTRIES_SENSOR_TEMPERATURE_SET = 18;
static const uint8_t ENTRIES_DEVICE_TEMPERATURE_SET = 25;
static const uint8_t ENTRIES_SUS_TEMPERATURE_SET = 12;
/**
* @brief This dataset can be used to store the collected temperatures of all temperature sensors
*/
class SensorTemperatures : public StaticLocalDataSet<2> {
class SensorTemperatures : public StaticLocalDataSet<ENTRIES_SENSOR_TEMPERATURE_SET> {
public:
SensorTemperatures(HasLocalDataPoolIF* owner) : StaticLocalDataSet(owner, SENSOR_TEMPERATURES) {}
SensorTemperatures(object_id_t objectId)
: StaticLocalDataSet(sid_t(objectId, SENSOR_TEMPERATURES)) {}
lp_var_t<float> rw = lp_var_t<float>(sid.objectId, PoolIds::SENSOR_RW, this);
lp_var_t<float> gps = lp_var_t<float>(sid.objectId, PoolIds::SENSOR_GPS, this);
lp_var_t<float> sensor_ploc_heatspreader =
lp_var_t<float>(sid.objectId, PoolIds::SENSOR_PLOC_HEATSPREADER, this);
lp_var_t<float> sensor_ploc_missionboard =
lp_var_t<float>(sid.objectId, PoolIds::SENSOR_PLOC_MISSIONBOARD, this);
lp_var_t<float> sensor_4k_camera = lp_var_t<float>(sid.objectId, PoolIds::SENSOR_4K_CAMERA, this);
lp_var_t<float> sensor_dac_heatspreader =
lp_var_t<float>(sid.objectId, PoolIds::SENSOR_DAC_HEATSPREADER, this);
lp_var_t<float> sensor_startracker =
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_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_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_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_plpcdu_heatspreader =
lp_var_t<float>(sid.objectId, PoolIds::SENSOR_PLPCDU_HEATSPREADER, this);
lp_var_t<float> sensor_tcs_board = lp_var_t<float>(sid.objectId, PoolIds::SENSOR_TCS_BOARD, this);
lp_var_t<float> sensor_magnettorquer =
lp_var_t<float>(sid.objectId, PoolIds::SENSOR_MAGNETTORQUER, this);
lp_var_t<float> sensor_tmp1075_1 = lp_var_t<float>(sid.objectId, PoolIds::SENSOR_TMP1075_1, this);
lp_var_t<float> sensor_tmp1075_2 = lp_var_t<float>(sid.objectId, PoolIds::SENSOR_TMP1075_2, this);
};
/**
* @brief This dataset can be used to store the collected temperatures of all device temperature
* sensors
*/
class DeviceTemperatures : public StaticLocalDataSet<ENTRIES_DEVICE_TEMPERATURE_SET> {
public:
DeviceTemperatures(HasLocalDataPoolIF* owner) : StaticLocalDataSet(owner, DEVICE_TEMPERATURES) {}
DeviceTemperatures(object_id_t objectId)
: StaticLocalDataSet(sid_t(objectId, DEVICE_TEMPERATURES)) {}
lp_var_t<float> q7s = lp_var_t<float>(sid.objectId, PoolIds::TEMP_Q7S, this);
lp_var_t<int16_t> batteryTemp1 = lp_var_t<int16_t>(sid.objectId, PoolIds::BATTERY_TEMP_1, this);
lp_var_t<int16_t> batteryTemp2 = lp_var_t<int16_t>(sid.objectId, PoolIds::BATTERY_TEMP_2, this);
lp_var_t<int16_t> batteryTemp3 = lp_var_t<int16_t>(sid.objectId, PoolIds::BATTERY_TEMP_3, this);
lp_var_t<int16_t> batteryTemp4 = lp_var_t<int16_t>(sid.objectId, PoolIds::BATTERY_TEMP_4, this);
lp_var_t<int32_t> rw1 = lp_var_t<int32_t>(sid.objectId, PoolIds::TEMP_RW1, this);
lp_var_t<int32_t> rw2 = lp_var_t<int32_t>(sid.objectId, PoolIds::TEMP_RW2, this);
lp_var_t<int32_t> rw3 = lp_var_t<int32_t>(sid.objectId, PoolIds::TEMP_RW3, this);
lp_var_t<int32_t> rw4 = lp_var_t<int32_t>(sid.objectId, PoolIds::TEMP_RW4, this);
lp_var_t<float> startracker = lp_var_t<float>(sid.objectId, PoolIds::TEMP_STAR_TRACKER, this);
lp_var_t<uint16_t> syrlinksPowerAmplifier =
lp_var_t<uint16_t>(sid.objectId, PoolIds::TEMP_SYRLINKS_POWER_AMPLIFIER, this);
lp_var_t<uint16_t> syrlinksBasebandBoard =
lp_var_t<uint16_t>(sid.objectId, PoolIds::TEMP_SYRLINKS_BASEBAND_BOARD, this);
lp_var_t<uint16_t> mgt = lp_var_t<uint16_t>(sid.objectId, PoolIds::TEMP_MGT, this);
lp_vec_t<float, 3> acu = lp_vec_t<float, 3>(sid.objectId, PoolIds::TEMP_ACU, this);
lp_var_t<float> pdu1 = lp_var_t<float>(sid.objectId, PoolIds::TEMP_PDU1, this);
lp_var_t<float> pdu2 = lp_var_t<float>(sid.objectId, PoolIds::TEMP_PDU2, this);
lp_var_t<float> temp1P60dock = lp_var_t<float>(sid.objectId, PoolIds::TEMP_1_P60DOCK, this);
lp_var_t<float> temp2P60dock = lp_var_t<float>(sid.objectId, PoolIds::TEMP_2_P60DOCK, this);
lp_var_t<float> gyro0SideA = lp_var_t<float>(sid.objectId, PoolIds::TEMP_GYRO_0_SIDE_A, this);
lp_var_t<float> gyro1SideA = lp_var_t<float>(sid.objectId, PoolIds::TEMP_GYRO_1_SIDE_A, this);
lp_var_t<float> gyro2SideB = lp_var_t<float>(sid.objectId, PoolIds::TEMP_GYRO_2_SIDE_B, this);
lp_var_t<float> gyro3SideB = lp_var_t<float>(sid.objectId, PoolIds::TEMP_GYRO_3_SIDE_B, this);
lp_var_t<float> mgm0SideA = lp_var_t<float>(sid.objectId, PoolIds::TEMP_MGM_0_SIDE_A, this);
lp_var_t<float> mgm2SideB = lp_var_t<float>(sid.objectId, PoolIds::TEMP_MGM_2_SIDE_B, this);
lp_var_t<float> adcPayloadPcdu =
lp_var_t<float>(sid.objectId, PoolIds::TEMP_ADC_PAYLOAD_PCDU, this);
};
/**
* @brief This dataset can be used to store the collected temperatures of all SUS temperature
* sensors
*/
class SusTemperatures : public StaticLocalDataSet<ENTRIES_SUS_TEMPERATURE_SET> {
public:
SusTemperatures(HasLocalDataPoolIF* owner) : StaticLocalDataSet(owner, SUS_TEMPERATURES) {}
SusTemperatures(object_id_t objectId)
: StaticLocalDataSet(sid_t(objectId, SUS_TEMPERATURES)) {}
lp_var_t<float> sus_0_n_loc_xfyfzm_pt_xf =
lp_var_t<float>(sid.objectId, PoolIds::SUS_0_N_LOC_XFYFZM_PT_XF, this);
lp_var_t<float> sus_6_r_loc_xfybzm_pt_xf =
lp_var_t<float>(sid.objectId, PoolIds::SUS_6_R_LOC_XFYBZM_PT_XF, this);
lp_var_t<float> sus_1_n_loc_xbyfzm_pt_xb =
lp_var_t<float>(sid.objectId, PoolIds::SUS_1_N_LOC_XBYFZM_PT_XB, this);
lp_var_t<float> sus_7_r_loc_xbybzm_pt_xb =
lp_var_t<float>(sid.objectId, PoolIds::SUS_7_R_LOC_XBYBZM_PT_XB, this);
lp_var_t<float> sus_2_n_loc_xfybzb_pt_yb =
lp_var_t<float>(sid.objectId, PoolIds::SUS_2_N_LOC_XFYBZB_PT_YB, this);
lp_var_t<float> sus_8_r_loc_xbybzb_pt_yb =
lp_var_t<float>(sid.objectId, PoolIds::SUS_8_R_LOC_XBYBZB_PT_YB, this);
lp_var_t<float> sus_3_n_loc_xfybzf_pt_yf =
lp_var_t<float>(sid.objectId, PoolIds::SUS_3_N_LOC_XFYBZF_PT_YF, this);
lp_var_t<float> sus_9_r_loc_xbybzb_pt_yf =
lp_var_t<float>(sid.objectId, PoolIds::SUS_9_R_LOC_XBYBZB_PT_YF, this);
lp_var_t<float> sus_4_n_loc_xmyfzf_pt_zf =
lp_var_t<float>(sid.objectId, PoolIds::SUS_4_N_LOC_XMYFZF_PT_ZF, this);
lp_var_t<float> sus_10_n_loc_xmybzf_pt_zf =
lp_var_t<float>(sid.objectId, PoolIds::SUS_10_N_LOC_XMYBZF_PT_ZF, this);
lp_var_t<float> sus_5_n_loc_xfymzb_pt_zb =
lp_var_t<float>(sid.objectId, PoolIds::SUS_5_N_LOC_XFYMZB_PT_ZB, this);
lp_var_t<float> sus_11_r_loc_xbymzb_pt_zb =
lp_var_t<float>(sid.objectId, PoolIds::SUS_11_R_LOC_XBYMZB_PT_ZB, this);
};
/**
@ -30,14 +199,14 @@ class SensorTemperatures : public StaticLocalDataSet<2> {
class ComponentTemperatures : public StaticLocalDataSet<2> {
public:
ComponentTemperatures(HasLocalDataPoolIF* owner)
: StaticLocalDataSet(owner, SENSOR_TEMPERATURES) {}
: StaticLocalDataSet(owner, COMPONENT_TEMPERATURES) {}
ComponentTemperatures(object_id_t objectId)
: StaticLocalDataSet(sid_t(objectId, SENSOR_TEMPERATURES)) {}
: StaticLocalDataSet(sid_t(objectId, COMPONENT_TEMPERATURES)) {}
lp_var_t<float> rw = lp_var_t<float>(sid.objectId, PoolIds::COMPONENT_RW, this);
};
} // namespace thermalControllerDefinitions
#endif /* MISSION_CONTROLLER_CONTROLLERDEFINITIONS_THERMALCONTROLLERDEFINITIONS_H_ */
#endif /* MISSION_CONTROLLER_CONTROLLERDEFINITIONS_THERMALCONTROLLERDEFINITIONS_H_ */

View File

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

View File

@ -4,6 +4,7 @@
#include <fsfw/health/HealthTable.h>
#include <fsfw/internalerror/InternalErrorReporter.h>
#include <fsfw/pus/CService200ModeCommanding.h>
#include <fsfw/pus/CService201HealthCommanding.h>
#include <fsfw/pus/Service17Test.h>
#include <fsfw/pus/Service1TelecommandVerification.h>
#include <fsfw/pus/Service20ParameterManagement.h>
@ -20,6 +21,7 @@
#include "OBSWConfig.h"
#include "eive/definitions.h"
#include "fsfw/pus/Service11TelecommandScheduling.h"
#include "objects/systemObjectList.h"
#include "tmtc/apid.h"
#include "tmtc/pusIds.h"
@ -44,10 +46,13 @@
#define OBSW_TM_TO_PTME 0
#endif
void ObjectFactory::produceGenericObjects() {
void ObjectFactory::produceGenericObjects(HealthTableIF** healthTable_) {
// Framework objects
new EventManager(objects::EVENT_MANAGER);
new HealthTable(objects::HEALTH_TABLE);
auto healthTable = new HealthTable(objects::HEALTH_TABLE);
if (healthTable_ != nullptr) {
*healthTable_ = healthTable;
}
new InternalErrorReporter(objects::INTERNAL_ERROR_REPORTER);
new TimeStamper(objects::TIME_STAMPER);
@ -69,7 +74,7 @@ void ObjectFactory::produceGenericObjects() {
new PoolManager(objects::IPC_STORE, poolCfg);
}
new CCSDSDistributor(apid::EIVE_OBSW, objects::CCSDS_PACKET_DISTRIBUTOR);
auto* ccsdsDistrib = new CCSDSDistributor(apid::EIVE_OBSW, objects::CCSDS_PACKET_DISTRIBUTOR);
new PUSDistributor(apid::EIVE_OBSW, objects::PUS_PACKET_DISTRIBUTOR,
objects::CCSDS_PACKET_DISTRIBUTOR);
@ -92,12 +97,16 @@ void ObjectFactory::produceGenericObjects() {
new Service8FunctionManagement(objects::PUS_SERVICE_8_FUNCTION_MGMT, apid::EIVE_OBSW,
pus::PUS_SERVICE_8, 3, 60);
new Service9TimeManagement(objects::PUS_SERVICE_9_TIME_MGMT, apid::EIVE_OBSW, pus::PUS_SERVICE_9);
new Service11TelecommandScheduling<common::OBSW_MAX_SCHEDULED_TCS>(
objects::PUS_SERVICE_11_TC_SCHEDULER, apid::EIVE_OBSW, pus::PUS_SERVICE_11, ccsdsDistrib);
new Service17Test(objects::PUS_SERVICE_17_TEST, apid::EIVE_OBSW, pus::PUS_SERVICE_17);
new Service20ParameterManagement(objects::PUS_SERVICE_20_PARAMETERS, apid::EIVE_OBSW,
pus::PUS_SERVICE_20);
new CService200ModeCommanding(objects::PUS_SERVICE_200_MODE_MGMT, apid::EIVE_OBSW,
pus::PUS_SERVICE_200, 8, config::LONGEST_MODE_TIMEOUT_SECONDS);
pus::PUS_SERVICE_200, 8);
new CService201HealthCommanding(objects::PUS_SERVICE_201_HEALTH, apid::EIVE_OBSW,
pus::PUS_SERVICE_201);
#if OBSW_ADD_TCPIP_BRIDGE == 1
#if OBSW_USE_TMTC_TCP_BRIDGE == 0
auto tmtcBridge = new UdpTmTcBridge(objects::TMTC_BRIDGE, objects::CCSDS_PACKET_DISTRIBUTOR);
@ -115,6 +124,6 @@ void ObjectFactory::produceGenericObjects() {
tcpServer->enableWiretapping(true);
#endif /* OBSW_TCP_SERVER_WIRETAPPING == 1 */
#endif /* OBSW_USE_TMTC_TCP_BRIDGE == 0 */
tmtcBridge->setMaxNumberOfPacketsStored(70);
tmtcBridge->setMaxNumberOfPacketsStored(300);
#endif /* OBSW_ADD_TCPIP_BRIDGE == 1 */
}

View File

@ -1,9 +1,11 @@
#ifndef MISSION_CORE_GENERICFACTORY_H_
#define MISSION_CORE_GENERICFACTORY_H_
class HealthTableIF;
namespace ObjectFactory {
void produceGenericObjects();
void produceGenericObjects(HealthTableIF** healthTable = nullptr);
}

View File

@ -6,7 +6,8 @@ ACUHandler::ACUHandler(object_id_t objectId, object_id_t comIF, CookieIF *comCoo
FailureIsolationBase *customFdir)
: GomspaceDeviceHandler(objectId, comIF, comCookie, customFdir, ACU::MAX_CONFIGTABLE_ADDRESS,
ACU::MAX_HKTABLE_ADDRESS, ACU::HK_TABLE_REPLY_SIZE),
acuHkTableDataset(this) {}
coreHk(this),
auxHk(this) {}
ACUHandler::~ACUHandler() {}
@ -15,243 +16,145 @@ ReturnValue_t ACUHandler::buildNormalDeviceCommand(DeviceCommandId_t *id) {
return buildCommandFromCommand(*id, NULL, 0);
}
void ACUHandler::fillCommandAndReplyMap() {
GomspaceDeviceHandler::fillCommandAndReplyMap();
this->insertInCommandMap(PRINT_CHANNEL_STATS);
}
void ACUHandler::fillCommandAndReplyMap() { GomspaceDeviceHandler::fillCommandAndReplyMap(); }
void ACUHandler::letChildHandleHkReply(DeviceCommandId_t id, const uint8_t *packet) {
parseHkTableReply(packet);
handleDeviceTM(&acuHkTableDataset, id, true);
if (debugMode) {
#if OBSW_VERBOSE_LEVEL >= 1
acuHkTableDataset.read();
float temperatureC_1 = acuHkTableDataset.temperature1.value * 0.1;
float temperatureC_2 = acuHkTableDataset.temperature2.value * 0.1;
float temperatureC_3 = acuHkTableDataset.temperature3.value * 0.1;
sif::info << "ACU: Temperature 1: " << temperatureC_1 << " °C" << std::endl;
sif::info << "ACU: Temperature 2: " << temperatureC_2 << " °C" << std::endl;
sif::info << "ACU: Temperature 3: " << temperatureC_3 << " °C" << std::endl;
sif::info << "ACU: Ground Watchdog Timer Count: " << acuHkTableDataset.wdtCntGnd.value
<< std::endl;
PoolReadGuard pg0(&auxHk);
PoolReadGuard pg1(&coreHk);
if (pg0.getReadResult() != RETURN_OK or pg1.getReadResult() != RETURN_OK) {
return;
}
for (size_t idx = 0; idx < 3; idx++) {
float tempC = coreHk.temperatures[idx] * 0.1;
sif::info << "ACU: Temperature " << idx << ": " << tempC << " °C" << std::endl;
}
sif::info << "ACU: Ground Watchdog Timer Count: " << auxHk.wdtCntGnd.value << std::endl;
sif::info << "ACU: Ground watchdog timer, seconds left before reboot: "
<< acuHkTableDataset.wdtGndLeft.value << std::endl;
acuHkTableDataset.commit();
<< auxHk.wdtGndLeft.value << std::endl;
#endif
}
}
LocalPoolDataSetBase *ACUHandler::getDataSetHandle(sid_t sid) {
if (sid == acuHkTableDataset.getSid()) {
return &acuHkTableDataset;
if (sid == coreHk.getSid()) {
return &coreHk;
} else if (sid == auxHk.getSid()) {
return &auxHk;
}
return nullptr;
}
void ACUHandler::parseHkTableReply(const uint8_t *packet) {
ReturnValue_t ACUHandler::parseHkTableReply(const uint8_t *packet) {
uint16_t dataOffset = 0;
acuHkTableDataset.read();
PoolReadGuard pg0(&coreHk);
PoolReadGuard pg1(&auxHk);
auto res0 = pg0.getReadResult();
auto res1 = pg1.getReadResult();
if (res0 != RETURN_OK) {
return res0;
}
if (res1 != RETURN_OK) {
return res1;
}
dataOffset += 12;
acuHkTableDataset.currentInChannel0 = *(packet + dataOffset) << 8 | *(packet + dataOffset + 1);
for (size_t idx = 0; idx < 6; idx++) {
coreHk.currentInChannels[idx] = (packet[dataOffset] << 8) | packet[dataOffset + 1];
dataOffset += 4;
}
for (size_t idx = 0; idx < 6; idx++) {
coreHk.voltageInChannels[idx] = (packet[dataOffset] << 8) | packet[dataOffset + 1];
dataOffset += 4;
}
coreHk.vcc = *(packet + dataOffset) << 8 | *(packet + dataOffset + 1);
dataOffset += 4;
acuHkTableDataset.currentInChannel1 = *(packet + dataOffset) << 8 | *(packet + dataOffset + 1);
dataOffset += 4;
acuHkTableDataset.currentInChannel2 = *(packet + dataOffset) << 8 | *(packet + dataOffset + 1);
dataOffset += 4;
acuHkTableDataset.currentInChannel3 = *(packet + dataOffset) << 8 | *(packet + dataOffset + 1);
dataOffset += 4;
acuHkTableDataset.currentInChannel4 = *(packet + dataOffset) << 8 | *(packet + dataOffset + 1);
dataOffset += 4;
acuHkTableDataset.currentInChannel5 = *(packet + dataOffset) << 8 | *(packet + dataOffset + 1);
coreHk.vbat = *(packet + dataOffset) << 8 | *(packet + dataOffset + 1);
dataOffset += 4;
acuHkTableDataset.voltageInChannel0 = *(packet + dataOffset) << 8 | *(packet + dataOffset + 1);
dataOffset += 4;
acuHkTableDataset.voltageInChannel1 = *(packet + dataOffset) << 8 | *(packet + dataOffset + 1);
dataOffset += 4;
acuHkTableDataset.voltageInChannel2 = *(packet + dataOffset) << 8 | *(packet + dataOffset + 1);
dataOffset += 4;
acuHkTableDataset.voltageInChannel3 = *(packet + dataOffset) << 8 | *(packet + dataOffset + 1);
dataOffset += 4;
acuHkTableDataset.voltageInChannel4 = *(packet + dataOffset) << 8 | *(packet + dataOffset + 1);
dataOffset += 4;
acuHkTableDataset.voltageInChannel5 = *(packet + dataOffset) << 8 | *(packet + dataOffset + 1);
dataOffset += 4;
for (size_t idx = 0; idx < 3; idx++) {
coreHk.temperatures[idx] = ((packet[dataOffset] << 8) | packet[dataOffset + 1]) * 0.1;
dataOffset += 4;
}
acuHkTableDataset.vcc = *(packet + dataOffset) << 8 | *(packet + dataOffset + 1);
dataOffset += 4;
acuHkTableDataset.vbat = *(packet + dataOffset) << 8 | *(packet + dataOffset + 1);
dataOffset += 4;
acuHkTableDataset.temperature1 = *(packet + dataOffset) << 8 | *(packet + dataOffset + 1);
dataOffset += 4;
acuHkTableDataset.temperature2 = *(packet + dataOffset) << 8 | *(packet + dataOffset + 1);
dataOffset += 4;
acuHkTableDataset.temperature3 = *(packet + dataOffset) << 8 | *(packet + dataOffset + 1);
dataOffset += 4;
acuHkTableDataset.mpptMode = *(packet + dataOffset);
coreHk.mpptMode = packet[dataOffset];
dataOffset += 3;
acuHkTableDataset.vboostInChannel0 = *(packet + dataOffset) << 8 | *(packet + dataOffset + 1);
dataOffset += 4;
acuHkTableDataset.vboostInChannel1 = *(packet + dataOffset) << 8 | *(packet + dataOffset + 1);
dataOffset += 4;
acuHkTableDataset.vboostInChannel2 = *(packet + dataOffset) << 8 | *(packet + dataOffset + 1);
dataOffset += 4;
acuHkTableDataset.vboostInChannel3 = *(packet + dataOffset) << 8 | *(packet + dataOffset + 1);
dataOffset += 4;
acuHkTableDataset.vboostInChannel4 = *(packet + dataOffset) << 8 | *(packet + dataOffset + 1);
dataOffset += 4;
acuHkTableDataset.vboostInChannel5 = *(packet + dataOffset) << 8 | *(packet + dataOffset + 1);
dataOffset += 4;
for (size_t idx = 0; idx < 6; idx++) {
coreHk.vboostInChannels[idx] = (packet[dataOffset] << 8) | packet[dataOffset + 1];
dataOffset += 4;
}
for (size_t idx = 0; idx < 6; idx++) {
coreHk.powerInChannels[idx] = (packet[dataOffset] << 8) | packet[dataOffset + 1];
dataOffset += 4;
}
for (size_t idx = 0; idx < 3; idx++) {
auxHk.dacEnables[idx] = packet[dataOffset];
dataOffset += 3;
}
for (size_t idx = 0; idx < 6; idx++) {
auxHk.dacRawChannelVals[idx] = (packet[dataOffset] << 8) | packet[dataOffset + 1];
dataOffset += 4;
}
acuHkTableDataset.powerInChannel0 = *(packet + dataOffset) << 8 | *(packet + dataOffset + 1);
dataOffset += 4;
acuHkTableDataset.powerInChannel1 = *(packet + dataOffset) << 8 | *(packet + dataOffset + 1);
dataOffset += 4;
acuHkTableDataset.powerInChannel2 = *(packet + dataOffset) << 8 | *(packet + dataOffset + 1);
dataOffset += 4;
acuHkTableDataset.powerInChannel3 = *(packet + dataOffset) << 8 | *(packet + dataOffset + 1);
dataOffset += 4;
acuHkTableDataset.powerInChannel4 = *(packet + dataOffset) << 8 | *(packet + dataOffset + 1);
dataOffset += 4;
acuHkTableDataset.powerInChannel5 = *(packet + dataOffset) << 8 | *(packet + dataOffset + 1);
dataOffset += 4;
acuHkTableDataset.dac0Enable = *(packet + dataOffset);
dataOffset += 3;
acuHkTableDataset.dac1Enable = *(packet + dataOffset);
dataOffset += 3;
acuHkTableDataset.dac2Enable = *(packet + dataOffset);
dataOffset += 3;
acuHkTableDataset.dacRawChannelVal0 = *(packet + dataOffset) << 8 | *(packet + dataOffset + 1);
dataOffset += 4;
acuHkTableDataset.dacRawChannelVal1 = *(packet + dataOffset) << 8 | *(packet + dataOffset + 1);
dataOffset += 4;
acuHkTableDataset.dacRawChannelVal2 = *(packet + dataOffset) << 8 | *(packet + dataOffset + 1);
dataOffset += 4;
acuHkTableDataset.dacRawChannelVal3 = *(packet + dataOffset) << 8 | *(packet + dataOffset + 1);
dataOffset += 4;
acuHkTableDataset.dacRawChannelVal4 = *(packet + dataOffset) << 8 | *(packet + dataOffset + 1);
dataOffset += 4;
acuHkTableDataset.dacRawChannelVal5 = *(packet + dataOffset) << 8 | *(packet + dataOffset + 1);
dataOffset += 4;
acuHkTableDataset.bootCause = *(packet + dataOffset) << 24 | *(packet + dataOffset + 1) << 16 |
*(packet + dataOffset + 2) << 8 | *(packet + dataOffset + 3);
auxHk.bootCause = *(packet + dataOffset) << 24 | *(packet + dataOffset + 1) << 16 |
*(packet + dataOffset + 2) << 8 | *(packet + dataOffset + 3);
dataOffset += 6;
acuHkTableDataset.bootcnt = *(packet + dataOffset) << 24 | *(packet + dataOffset + 1) << 16 |
*(packet + dataOffset + 2) << 8 | *(packet + dataOffset + 3);
coreHk.bootcnt = *(packet + dataOffset) << 24 | *(packet + dataOffset + 1) << 16 |
*(packet + dataOffset + 2) << 8 | *(packet + dataOffset + 3);
dataOffset += 6;
acuHkTableDataset.uptime = *(packet + dataOffset) << 24 | *(packet + dataOffset + 1) << 16 |
*(packet + dataOffset + 2) << 8 | *(packet + dataOffset + 3);
coreHk.uptime = *(packet + dataOffset) << 24 | *(packet + dataOffset + 1) << 16 |
*(packet + dataOffset + 2) << 8 | *(packet + dataOffset + 3);
dataOffset += 6;
acuHkTableDataset.resetCause = *(packet + dataOffset) << 8 | *(packet + dataOffset + 1);
auxHk.resetCause = *(packet + dataOffset) << 8 | *(packet + dataOffset + 1);
dataOffset += 4;
acuHkTableDataset.mpptTime = *(packet + dataOffset) << 8 | *(packet + dataOffset + 1);
coreHk.mpptTime = *(packet + dataOffset) << 8 | *(packet + dataOffset + 1);
/* +12 because here starts the second csp packet */
dataOffset += 2 + 12;
acuHkTableDataset.mpptPeriod = *(packet + dataOffset) << 8 | *(packet + dataOffset + 1);
coreHk.mpptPeriod = *(packet + dataOffset) << 8 | *(packet + dataOffset + 1);
dataOffset += 4;
acuHkTableDataset.device0 = *(packet + dataOffset);
dataOffset += 3;
acuHkTableDataset.device1 = *(packet + dataOffset);
dataOffset += 3;
acuHkTableDataset.device2 = *(packet + dataOffset);
dataOffset += 3;
acuHkTableDataset.device3 = *(packet + dataOffset);
dataOffset += 3;
acuHkTableDataset.device4 = *(packet + dataOffset);
dataOffset += 3;
acuHkTableDataset.device5 = *(packet + dataOffset);
dataOffset += 3;
acuHkTableDataset.device6 = *(packet + dataOffset);
dataOffset += 3;
acuHkTableDataset.device7 = *(packet + dataOffset);
dataOffset += 3;
for (size_t idx = 0; idx < 8; idx++) {
auxHk.deviceTypes[idx] = packet[dataOffset];
dataOffset += 3;
}
for (size_t idx = 0; idx < 8; idx++) {
auxHk.devicesStatus[idx] = packet[dataOffset];
dataOffset += 3;
}
acuHkTableDataset.device0Status = *(packet + dataOffset);
dataOffset += 3;
acuHkTableDataset.device1Status = *(packet + dataOffset);
dataOffset += 3;
acuHkTableDataset.device2Status = *(packet + dataOffset);
dataOffset += 3;
acuHkTableDataset.device3Status = *(packet + dataOffset);
dataOffset += 3;
acuHkTableDataset.device4Status = *(packet + dataOffset);
dataOffset += 3;
acuHkTableDataset.device5Status = *(packet + dataOffset);
dataOffset += 3;
acuHkTableDataset.device6Status = *(packet + dataOffset);
dataOffset += 3;
acuHkTableDataset.device7Status = *(packet + dataOffset);
dataOffset += 3;
acuHkTableDataset.wdtCntGnd = *(packet + dataOffset) << 24 | *(packet + dataOffset + 1) << 16 |
*(packet + dataOffset + 2) << 8 | *(packet + dataOffset + 3);
auxHk.wdtCntGnd = *(packet + dataOffset) << 24 | *(packet + dataOffset + 1) << 16 |
*(packet + dataOffset + 2) << 8 | *(packet + dataOffset + 3);
dataOffset += 6;
acuHkTableDataset.wdtGndLeft = *(packet + dataOffset) << 24 | *(packet + dataOffset + 1) << 16 |
*(packet + dataOffset + 2) << 8 | *(packet + dataOffset + 3);
auxHk.wdtGndLeft = *(packet + dataOffset) << 24 | *(packet + dataOffset + 1) << 16 |
*(packet + dataOffset + 2) << 8 | *(packet + dataOffset + 3);
dataOffset += 6;
acuHkTableDataset.commit();
coreHk.setValidity(true, true);
auxHk.setValidity(true, true);
return RETURN_OK;
}
ReturnValue_t ACUHandler::initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
LocalDataPoolManager &poolManager) {
using namespace P60System;
localDataPoolMap.emplace(pool::ACU_CURRENT_IN_CHANNEL0, new PoolEntry<int16_t>({0}));
localDataPoolMap.emplace(pool::ACU_CURRENT_IN_CHANNEL1, new PoolEntry<int16_t>({0}));
localDataPoolMap.emplace(pool::ACU_CURRENT_IN_CHANNEL2, new PoolEntry<int16_t>({0}));
localDataPoolMap.emplace(pool::ACU_CURRENT_IN_CHANNEL3, new PoolEntry<int16_t>({0}));
localDataPoolMap.emplace(pool::ACU_CURRENT_IN_CHANNEL4, new PoolEntry<int16_t>({0}));
localDataPoolMap.emplace(pool::ACU_CURRENT_IN_CHANNEL5, new PoolEntry<int16_t>({0}));
localDataPoolMap.emplace(pool::ACU_VOLTAGE_IN_CHANNEL0, new PoolEntry<uint16_t>({0}));
localDataPoolMap.emplace(pool::ACU_VOLTAGE_IN_CHANNEL1, new PoolEntry<uint16_t>({0}));
localDataPoolMap.emplace(pool::ACU_VOLTAGE_IN_CHANNEL2, new PoolEntry<uint16_t>({0}));
localDataPoolMap.emplace(pool::ACU_VOLTAGE_IN_CHANNEL3, new PoolEntry<uint16_t>({0}));
localDataPoolMap.emplace(pool::ACU_VOLTAGE_IN_CHANNEL4, new PoolEntry<uint16_t>({0}));
localDataPoolMap.emplace(pool::ACU_VOLTAGE_IN_CHANNEL5, new PoolEntry<uint16_t>({0}));
localDataPoolMap.emplace(pool::ACU_CURRENT_IN_CHANNELS, new PoolEntry<int16_t>(6));
localDataPoolMap.emplace(pool::ACU_VOLTAGE_IN_CHANNELS, new PoolEntry<uint16_t>(6));
localDataPoolMap.emplace(pool::ACU_VCC, new PoolEntry<uint16_t>({0}));
localDataPoolMap.emplace(pool::ACU_VBAT, new PoolEntry<uint16_t>({0}));
localDataPoolMap.emplace(pool::ACU_TEMPERATURE_1, new PoolEntry<int16_t>({0}));
localDataPoolMap.emplace(pool::ACU_TEMPERATURE_2, new PoolEntry<int16_t>({0}));
localDataPoolMap.emplace(pool::ACU_TEMPERATURE_3, new PoolEntry<int16_t>({0}));
localDataPoolMap.emplace(pool::ACU_TEMPERATURES, new PoolEntry<float>(3));
localDataPoolMap.emplace(pool::ACU_MPPT_MODE, new PoolEntry<uint8_t>({0}));
localDataPoolMap.emplace(pool::ACU_VBOOST_CHANNEL0, new PoolEntry<uint16_t>({0}));
localDataPoolMap.emplace(pool::ACU_VBOOST_CHANNEL1, new PoolEntry<uint16_t>({0}));
localDataPoolMap.emplace(pool::ACU_VBOOST_CHANNEL2, new PoolEntry<uint16_t>({0}));
localDataPoolMap.emplace(pool::ACU_VBOOST_CHANNEL3, new PoolEntry<uint16_t>({0}));
localDataPoolMap.emplace(pool::ACU_VBOOST_CHANNEL4, new PoolEntry<uint16_t>({0}));
localDataPoolMap.emplace(pool::ACU_VBOOST_CHANNEL5, new PoolEntry<uint16_t>({0}));
localDataPoolMap.emplace(pool::ACU_VBOOST_IN_CHANNELS, new PoolEntry<uint16_t>(6));
localDataPoolMap.emplace(pool::ACU_POWER_IN_CHANNELS, new PoolEntry<uint16_t>(6));
localDataPoolMap.emplace(pool::ACU_POWER_CHANNEL0, new PoolEntry<uint16_t>({0}));
localDataPoolMap.emplace(pool::ACU_POWER_CHANNEL1, new PoolEntry<uint16_t>({0}));
localDataPoolMap.emplace(pool::ACU_POWER_CHANNEL2, new PoolEntry<uint16_t>({0}));
localDataPoolMap.emplace(pool::ACU_POWER_CHANNEL3, new PoolEntry<uint16_t>({0}));
localDataPoolMap.emplace(pool::ACU_POWER_CHANNEL4, new PoolEntry<uint16_t>({0}));
localDataPoolMap.emplace(pool::ACU_POWER_CHANNEL5, new PoolEntry<uint16_t>({0}));
localDataPoolMap.emplace(pool::ACU_DAC_EN_0, new PoolEntry<uint8_t>({0}));
localDataPoolMap.emplace(pool::ACU_DAC_EN_1, new PoolEntry<uint8_t>({0}));
localDataPoolMap.emplace(pool::ACU_DAC_EN_2, new PoolEntry<uint8_t>({0}));
localDataPoolMap.emplace(pool::ACU_DAC_RAW_0, new PoolEntry<uint16_t>({0}));
localDataPoolMap.emplace(pool::ACU_DAC_RAW_1, new PoolEntry<uint16_t>({0}));
localDataPoolMap.emplace(pool::ACU_DAC_RAW_2, new PoolEntry<uint16_t>({0}));
localDataPoolMap.emplace(pool::ACU_DAC_RAW_3, new PoolEntry<uint16_t>({0}));
localDataPoolMap.emplace(pool::ACU_DAC_RAW_4, new PoolEntry<uint16_t>({0}));
localDataPoolMap.emplace(pool::ACU_DAC_RAW_5, new PoolEntry<uint16_t>({0}));
localDataPoolMap.emplace(pool::ACU_DAC_ENABLES, new PoolEntry<uint8_t>(3));
localDataPoolMap.emplace(pool::ACU_DAC_RAW_CHANNELS, new PoolEntry<uint16_t>(6));
localDataPoolMap.emplace(pool::ACU_BOOTCAUSE, new PoolEntry<uint32_t>({0}));
localDataPoolMap.emplace(pool::ACU_BOOTCNT, new PoolEntry<uint32_t>({0}));
@ -260,65 +163,47 @@ ReturnValue_t ACUHandler::initializeLocalDataPool(localpool::DataPool &localData
localDataPoolMap.emplace(pool::ACU_MPPT_TIME, new PoolEntry<uint16_t>({0}));
localDataPoolMap.emplace(pool::ACU_MPPT_PERIOD, new PoolEntry<uint16_t>({0}));
localDataPoolMap.emplace(pool::ACU_DEVICE_0, new PoolEntry<uint8_t>({0}));
localDataPoolMap.emplace(pool::ACU_DEVICE_1, new PoolEntry<uint8_t>({0}));
localDataPoolMap.emplace(pool::ACU_DEVICE_2, new PoolEntry<uint8_t>({0}));
localDataPoolMap.emplace(pool::ACU_DEVICE_3, new PoolEntry<uint8_t>({0}));
localDataPoolMap.emplace(pool::ACU_DEVICE_4, new PoolEntry<uint8_t>({0}));
localDataPoolMap.emplace(pool::ACU_DEVICE_5, new PoolEntry<uint8_t>({0}));
localDataPoolMap.emplace(pool::ACU_DEVICE_6, new PoolEntry<uint8_t>({0}));
localDataPoolMap.emplace(pool::ACU_DEVICE_7, new PoolEntry<uint8_t>({0}));
localDataPoolMap.emplace(pool::ACU_DEVICE_0_STATUS, new PoolEntry<uint8_t>({0}));
localDataPoolMap.emplace(pool::ACU_DEVICE_1_STATUS, new PoolEntry<uint8_t>({0}));
localDataPoolMap.emplace(pool::ACU_DEVICE_2_STATUS, new PoolEntry<uint8_t>({0}));
localDataPoolMap.emplace(pool::ACU_DEVICE_3_STATUS, new PoolEntry<uint8_t>({0}));
localDataPoolMap.emplace(pool::ACU_DEVICE_4_STATUS, new PoolEntry<uint8_t>({0}));
localDataPoolMap.emplace(pool::ACU_DEVICE_5_STATUS, new PoolEntry<uint8_t>({0}));
localDataPoolMap.emplace(pool::ACU_DEVICE_6_STATUS, new PoolEntry<uint8_t>({0}));
localDataPoolMap.emplace(pool::ACU_DEVICE_7_STATUS, new PoolEntry<uint8_t>({0}));
localDataPoolMap.emplace(pool::ACU_DEVICES, new PoolEntry<uint8_t>(8));
localDataPoolMap.emplace(pool::ACU_DEVICES_STATUS, new PoolEntry<uint8_t>(8));
localDataPoolMap.emplace(pool::ACU_WDT_CNT_GND, new PoolEntry<uint32_t>({0}));
localDataPoolMap.emplace(pool::ACU_WDT_GND_LEFT, new PoolEntry<uint32_t>({0}));
poolManager.subscribeForPeriodicPacket(acuHkTableDataset.getSid(), false, 30.0, false);
poolManager.subscribeForPeriodicPacket(coreHk.getSid(), false, 10.0, true);
poolManager.subscribeForPeriodicPacket(auxHk.getSid(), false, 30.0, false);
return HasReturnvaluesIF::RETURN_OK;
}
ReturnValue_t ACUHandler::childCommandHook(DeviceCommandId_t cmd, const uint8_t *commandData,
size_t commandDataLen) {
switch (cmd) {
case PRINT_CHANNEL_STATS: {
printChannelStats();
return RETURN_OK;
}
default: {
return DeviceHandlerIF::COMMAND_NOT_IMPLEMENTED;
}
void ACUHandler::printChannelStats() {
PoolReadGuard pg(&coreHk);
sif::info << "ACU Info: Current [mA], Voltage [mV]" << std::endl;
for (size_t idx = 0; idx < 6; idx++) {
sif::info << std::setw(8) << std::left << "Channel " << idx << std::dec << "| "
<< static_cast<unsigned int>(coreHk.currentInChannels[idx]) << std::setw(15)
<< std::right << coreHk.voltageInChannels[idx] << std::endl;
}
}
void ACUHandler::printChannelStats() {
PoolReadGuard pg(&acuHkTableDataset);
sif::info << "ACU Info: Current [mA], Voltage [mV]" << std::endl;
sif::info << std::setw(8) << std::left << "Ch0" << std::dec << "| "
<< static_cast<unsigned int>(acuHkTableDataset.currentInChannel0.value) << std::setw(15)
<< std::right << acuHkTableDataset.voltageInChannel0.value << std::endl;
sif::info << std::setw(8) << std::left << "Ch1" << std::dec << "| "
<< static_cast<unsigned int>(acuHkTableDataset.currentInChannel1.value) << std::setw(15)
<< std::right << acuHkTableDataset.voltageInChannel1.value << std::endl;
sif::info << std::setw(8) << std::left << "Ch2" << std::dec << "| "
<< static_cast<unsigned int>(acuHkTableDataset.currentInChannel2.value) << std::setw(15)
<< std::right << acuHkTableDataset.voltageInChannel2.value << std::endl;
sif::info << std::setw(8) << std::left << "Ch3" << std::dec << "| "
<< static_cast<unsigned int>(acuHkTableDataset.currentInChannel3.value) << std::setw(15)
<< std::right << acuHkTableDataset.voltageInChannel3.value << std::endl;
sif::info << std::setw(8) << std::left << "Ch4" << std::dec << "| "
<< static_cast<unsigned int>(acuHkTableDataset.currentInChannel4.value) << std::setw(15)
<< std::right << acuHkTableDataset.voltageInChannel4.value << std::endl;
sif::info << std::setw(8) << std::left << "Ch5" << std::dec << "| "
<< static_cast<unsigned int>(acuHkTableDataset.currentInChannel5.value) << std::setw(15)
<< std::right << acuHkTableDataset.voltageInChannel5.value << std::endl;
}
void ACUHandler::setDebugMode(bool enable) { this->debugMode = enable; }
ReturnValue_t ACUHandler::printStatus(DeviceCommandId_t cmd) {
ReturnValue_t result = RETURN_OK;
switch (cmd) {
case (GOMSPACE::PRINT_SWITCH_V_I): {
PoolReadGuard pg(&coreHk);
result = pg.getReadResult();
if (result != HasReturnvaluesIF::RETURN_OK) {
break;
}
printChannelStats();
break;
}
default: {
return DeviceHandlerIF::COMMAND_NOT_SUPPORTED;
}
}
if (result != HasReturnvaluesIF::RETURN_OK) {
sif::warning << "Reading PDU1 HK table failed!" << std::endl;
}
return result;
}

View File

@ -29,24 +29,22 @@ class ACUHandler : public GomspaceDeviceHandler {
*/
virtual ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t* id) override;
virtual void fillCommandAndReplyMap() override;
ReturnValue_t printStatus(DeviceCommandId_t cmd) override;
virtual ReturnValue_t childCommandHook(DeviceCommandId_t cmd, const uint8_t* commandData,
size_t commandDataLen) override;
virtual void fillCommandAndReplyMap() override;
LocalPoolDataSetBase* getDataSetHandle(sid_t sid) override;
private:
static const DeviceCommandId_t PRINT_CHANNEL_STATS = 51;
ACU::HkTableDataset acuHkTableDataset;
ACU::CoreHk coreHk;
ACU::AuxHk auxHk;
bool debugMode = false;
/**
* @brief Function extracts the hk table information from the received csp packet and stores
* the values in the acuHkTableDataset.
*/
void parseHkTableReply(const uint8_t* packet);
ReturnValue_t parseHkTableReply(const uint8_t* packet);
/**
* @brief Prints channel statistics (current and voltage) to console

View File

@ -1,21 +1,22 @@
target_sources(${LIB_EIVE_MISSION} PRIVATE
GomspaceDeviceHandler.cpp
BpxBatteryHandler.cpp
Tmp1075Handler.cpp
PCDUHandler.cpp
P60DockHandler.cpp
PDU1Handler.cpp
PDU2Handler.cpp
ACUHandler.cpp
SyrlinksHkHandler.cpp
Max31865PT1000Handler.cpp
IMTQHandler.cpp
HeaterHandler.cpp
RadiationSensorHandler.cpp
GyroADIS1650XHandler.cpp
RwHandler.cpp
max1227.cpp
SusHandler.cpp
PayloadPcduHandler.cpp
SolarArrayDeploymentHandler.cpp
)
target_sources(
${LIB_EIVE_MISSION}
PRIVATE GomspaceDeviceHandler.cpp
BpxBatteryHandler.cpp
Tmp1075Handler.cpp
PCDUHandler.cpp
P60DockHandler.cpp
PDU1Handler.cpp
PDU2Handler.cpp
ACUHandler.cpp
SyrlinksHkHandler.cpp
Max31865PT1000Handler.cpp
Max31865EiveHandler.cpp
IMTQHandler.cpp
HeaterHandler.cpp
RadiationSensorHandler.cpp
GyroADIS1650XHandler.cpp
RwHandler.cpp
max1227.cpp
SusHandler.cpp
PayloadPcduHandler.cpp
SolarArrayDeploymentHandler.cpp)

View File

@ -366,7 +366,7 @@ ReturnValue_t GomspaceDeviceHandler::initializePduPool(
localDataPoolMap.emplace(P60System::pool::PDU_VCC, new PoolEntry<int16_t>({0}));
localDataPoolMap.emplace(P60System::pool::PDU_VBAT, new PoolEntry<int16_t>({0}));
localDataPoolMap.emplace(P60System::pool::PDU_TEMPERATURE, new PoolEntry<int16_t>({0}));
localDataPoolMap.emplace(P60System::pool::PDU_TEMPERATURE, new PoolEntry<float>({0}));
localDataPoolMap.emplace(P60System::pool::PDU_CONV_EN, new PoolEntry<uint8_t>(3));
localDataPoolMap.emplace(P60System::pool::PDU_OUT_ENABLE,
@ -472,7 +472,7 @@ ReturnValue_t GomspaceDeviceHandler::parsePduHkTable(PDU::PduCoreHk& coreHk, PDU
dataOffset += 4;
auxHk.vbat = *(packet + dataOffset) << 8 | *(packet + dataOffset + 1);
dataOffset += 4;
coreHk.temperature = *(packet + dataOffset) << 8 | *(packet + dataOffset + 1);
coreHk.temperature = (*(packet + dataOffset) << 8 | *(packet + dataOffset + 1)) * 0.1;
dataOffset += 4;
for (uint8_t idx = 0; idx < 3; idx++) {

View File

@ -424,7 +424,8 @@ ReturnValue_t GyroADIS1650XHandler::spiSendCallback(SpiComIF *comIf, SpiCookie *
GpioIF *gpioIF = comIf->getGpioInterface();
MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING;
uint32_t timeoutMs = 0;
MutexIF *mutex = comIf->getMutex(&timeoutType, &timeoutMs);
MutexIF *mutex = comIf->getCsMutex();
cookie->getMutexParams(timeoutType, timeoutMs);
if (mutex == nullptr or gpioIF == nullptr) {
#if OBSW_VERBOSE_LEVEL >= 1
sif::warning << "GyroADIS16507Handler::spiSendCallback: "

View File

@ -1,21 +1,38 @@
#include "HeaterHandler.h"
#include <fsfw/health/HealthTableIF.h>
#include <fsfw/ipc/QueueFactory.h>
#include <fsfw/objectmanager/ObjectManager.h>
#include <fsfw_hal/common/gpio/GpioCookie.h>
#include <stdexcept>
#include "devices/gpioIds.h"
#include "devices/powerSwitcherList.h"
HeaterHandler::HeaterHandler(object_id_t setObjectId_, object_id_t gpioDriverId_,
CookieIF* gpioCookie_, object_id_t mainLineSwitcherObjectId_,
uint8_t mainLineSwitch_)
HeaterHandler::HeaterHandler(object_id_t setObjectId_, GpioIF* gpioInterface_, HeaterHelper helper,
PowerSwitchIF* mainLineSwitcher_, power::Switch_t mainLineSwitch_)
: SystemObject(setObjectId_),
gpioDriverId(gpioDriverId_),
gpioCookie(gpioCookie_),
mainLineSwitcherObjectId(mainLineSwitcherObjectId_),
helper(helper),
gpioInterface(gpioInterface_),
mainLineSwitcher(mainLineSwitcher_),
mainLineSwitch(mainLineSwitch_),
actionHelper(this, nullptr) {
for (const auto& heater : helper.heaters) {
if (heater.first == nullptr) {
throw std::invalid_argument("HeaterHandler::HeaterHandler: Invalid Heater Object");
}
}
if (gpioInterface_ == nullptr) {
throw std::invalid_argument("HeaterHandler::HeaterHandler: Invalid Gpio IF");
}
if (mainLineSwitcher == nullptr) {
throw std::invalid_argument("HeaterHandler::HeaterHandler: Invalid PowerSwitchIF");
}
heaterMutex = MutexFactory::instance()->createMutex();
if (heaterMutex == nullptr) {
throw std::runtime_error("HeaterHandler::HeaterHandler: Creating Mutex failed");
}
auto mqArgs = MqArgs(setObjectId_, static_cast<void*>(this));
commandQueue = QueueFactory::instance()->createMessageQueue(
cmdQueueSize, MessageQueueMessage::MAX_MESSAGE_SIZE, &mqArgs);
@ -24,10 +41,16 @@ HeaterHandler::HeaterHandler(object_id_t setObjectId_, object_id_t gpioDriverId_
HeaterHandler::~HeaterHandler() {}
ReturnValue_t HeaterHandler::performOperation(uint8_t operationCode) {
if (operationCode == DeviceHandlerIF::PERFORM_OPERATION) {
try {
readCommandQueue();
handleActiveCommands();
return RETURN_OK;
for (const auto& heater : helper.heaters) {
heater.first->performOperation(0);
}
handleSwitchHandling();
} catch (const std::out_of_range& e) {
sif::warning << "HeaterHandler::performOperation: "
"Out of range error | "
<< e.what() << std::endl;
}
return RETURN_OK;
}
@ -43,33 +66,12 @@ ReturnValue_t HeaterHandler::initialize() {
return ObjectManagerIF::CHILD_INIT_FAILED;
}
gpioInterface = ObjectManager::instance()->get<GpioIF>(gpioDriverId);
if (gpioInterface == nullptr) {
sif::error << "HeaterHandler::initialize: Invalid Gpio interface." << std::endl;
return ObjectManagerIF::CHILD_INIT_FAILED;
}
result = gpioInterface->addGpios(dynamic_cast<GpioCookie*>(gpioCookie));
if (result != RETURN_OK) {
sif::error << "HeaterHandler::initialize: Failed to initialize Gpio interface" << std::endl;
return ObjectManagerIF::CHILD_INIT_FAILED;
}
IPCStore = ObjectManager::instance()->get<StorageManagerIF>(objects::IPC_STORE);
if (IPCStore == nullptr) {
ipcStore = ObjectManager::instance()->get<StorageManagerIF>(objects::IPC_STORE);
if (ipcStore == nullptr) {
sif::error << "HeaterHandler::initialize: IPC store not set up in factory." << std::endl;
return ObjectManagerIF::CHILD_INIT_FAILED;
}
if (mainLineSwitcherObjectId != objects::NO_OBJECT) {
mainLineSwitcher = ObjectManager::instance()->get<PowerSwitchIF>(mainLineSwitcherObjectId);
if (mainLineSwitcher == nullptr) {
sif::error << "HeaterHandler::initialize: Failed to get main line switcher. Make sure "
<< "main line switcher object is initialized." << std::endl;
return ObjectManagerIF::CHILD_INIT_FAILED;
}
}
result = actionHelper.initialize(commandQueue);
if (result != RETURN_OK) {
return ObjectManagerIF::CHILD_INIT_FAILED;
@ -79,81 +81,97 @@ ReturnValue_t HeaterHandler::initialize() {
}
ReturnValue_t HeaterHandler::initializeHeaterMap() {
HeaterCommandInfo_t heaterCommandInfo;
for (switchNr_t switchNr = 0; switchNr < heaterSwitches::NUMBER_OF_SWITCHES; switchNr++) {
std::pair status = heaterMap.emplace(switchNr, heaterCommandInfo);
if (status.second == false) {
sif::error << "HeaterHandler::initializeHeaterMap: Failed to initialize heater map"
<< std::endl;
return RETURN_FAILED;
}
for (power::Switch_t switchNr = 0; switchNr < heater::NUMBER_OF_SWITCHES; switchNr++) {
heaterVec.push_back(HeaterWrapper(helper.heaters[switchNr], SwitchState::OFF));
}
return RETURN_OK;
}
void HeaterHandler::setInitialSwitchStates() {
for (switchNr_t switchNr = 0; switchNr < heaterSwitches::NUMBER_OF_SWITCHES; switchNr++) {
switchStates[switchNr] = OFF;
}
}
void HeaterHandler::readCommandQueue() {
ReturnValue_t result = RETURN_OK;
CommandMessage command;
ReturnValue_t result = commandQueue->receiveMessage(&command);
if (result != RETURN_OK) {
return;
}
result = actionHelper.handleActionMessage(&command);
if (result == RETURN_OK) {
return;
}
do {
result = commandQueue->receiveMessage(&command);
if (result == MessageQueueIF::EMPTY) {
break;
} else if (result != RETURN_OK) {
sif::warning << "HeaterHandler::readCommandQueue: Message reception error" << std::endl;
}
result = actionHelper.handleActionMessage(&command);
if (result == RETURN_OK) {
continue;
}
} while (result == RETURN_OK);
}
ReturnValue_t HeaterHandler::executeAction(ActionId_t actionId, MessageQueueId_t commandedBy,
const uint8_t* data, size_t size) {
ReturnValue_t result;
if (actionId != SWITCH_HEATER) {
result = COMMAND_NOT_SUPPORTED;
} else {
switchNr_t switchNr = *data;
HeaterMapIter heaterMapIter = heaterMap.find(switchNr);
if (heaterMapIter != heaterMap.end()) {
if (heaterMapIter->second.active) {
return COMMAND_ALREADY_WAITING;
}
heaterMapIter->second.action = *(data + 1);
heaterMapIter->second.active = true;
heaterMapIter->second.replyQueue = commandedBy;
} else {
sif::error << "HeaterHandler::executeAction: Invalid switchNr" << std::endl;
return INVALID_SWITCH_NR;
}
result = RETURN_OK;
if (data == nullptr or size < 3) {
return HasActionsIF::INVALID_PARAMETERS;
}
return result;
if (actionId != SWITCH_HEATER) {
return COMMAND_NOT_SUPPORTED;
}
auto switchNr = data[0];
if (switchNr > 7) {
return HasActionsIF::INVALID_PARAMETERS;
}
auto& heater = heaterVec.at(switchNr);
auto actionRaw = data[1];
if (actionRaw != 0 and actionRaw != 1) {
return HasActionsIF::INVALID_PARAMETERS;
}
auto action = static_cast<SwitchAction>(data[1]);
// Always accepts OFF commands
if (action == SwitchAction::SET_SWITCH_ON) {
HasHealthIF::HealthState health = heater.healthDevice->getHealth();
if (health == HasHealthIF::FAULTY or health == HasHealthIF::PERMANENT_FAULTY or
health == HasHealthIF::NEEDS_RECOVERY) {
return HasHealthIF::OBJECT_NOT_HEALTHY;
}
CmdSourceParam cmdSource = CmdSourceParam::EXTERNAL;
uint8_t cmdSourceRaw = data[2];
if (cmdSourceRaw > 1) {
return HasActionsIF::INVALID_PARAMETERS;
}
cmdSource = static_cast<CmdSourceParam>(data[2]);
if (health == HasHealthIF::EXTERNAL_CONTROL and cmdSource == CmdSourceParam::INTERNAL) {
return HasHealthIF::IS_EXTERNALLY_CONTROLLED;
}
}
if (heater.cmdActive) {
return COMMAND_ALREADY_WAITING;
}
heater.action = action;
heater.cmdActive = true;
heater.replyQueue = commandedBy;
return RETURN_OK;
}
ReturnValue_t HeaterHandler::sendSwitchCommand(uint8_t switchNr, ReturnValue_t onOff) {
ReturnValue_t result;
store_address_t storeAddress;
uint8_t commandData[2];
uint8_t commandData[3] = {};
switch (onOff) {
case PowerSwitchIF::SWITCH_ON:
commandData[0] = switchNr;
commandData[1] = SET_SWITCH_ON;
commandData[2] = CmdSourceParam::INTERNAL;
break;
case PowerSwitchIF::SWITCH_OFF:
commandData[0] = switchNr;
commandData[1] = SET_SWITCH_OFF;
commandData[2] = CmdSourceParam::INTERNAL;
break;
default:
sif::error << "HeaterHandler::sendSwitchCommand: Invalid switch request" << std::endl;
break;
}
result = IPCStore->addData(&storeAddress, commandData, sizeof(commandData));
result = ipcStore->addData(&storeAddress, commandData, sizeof(commandData));
if (result == RETURN_OK) {
CommandMessage message;
ActionMessage::setCommand(&message, SWITCH_HEATER, storeAddress);
@ -167,16 +185,27 @@ ReturnValue_t HeaterHandler::sendSwitchCommand(uint8_t switchNr, ReturnValue_t o
return result;
}
void HeaterHandler::handleActiveCommands() {
HeaterMapIter heaterMapIter = heaterMap.begin();
for (; heaterMapIter != heaterMap.end(); heaterMapIter++) {
if (heaterMapIter->second.active) {
switch (heaterMapIter->second.action) {
void HeaterHandler::handleSwitchHandling() {
for (uint8_t idx = 0; idx < heater::NUMBER_OF_SWITCHES; idx++) {
auto health = heaterVec[idx].healthDevice->getHealth();
if (heaterVec[idx].switchState == SwitchState::ON) {
// If a heater is still on but the device was marked faulty by the operator, the SW
// will shut down the heater
if (health == HasHealthIF::FAULTY or health == HasHealthIF::PERMANENT_FAULTY) {
heaterVec[idx].cmdActive = true;
heaterVec[idx].action = SET_SWITCH_OFF;
triggerEvent(FAULTY_HEATER_WAS_ON, idx, 0);
handleSwitchOffCommand(static_cast<heater::Switchers>(idx));
continue;
}
}
if (heaterVec[idx].cmdActive) {
switch (heaterVec[idx].action) {
case SET_SWITCH_ON:
handleSwitchOnCommand(heaterMapIter);
handleSwitchOnCommand(static_cast<heater::Switchers>(idx));
break;
case SET_SWITCH_OFF:
handleSwitchOffCommand(heaterMapIter);
handleSwitchOffCommand(static_cast<heater::Switchers>(idx));
break;
default:
sif::error << "HeaterHandler::handleActiveCommands: Invalid action commanded"
@ -187,162 +216,139 @@ void HeaterHandler::handleActiveCommands() {
}
}
void HeaterHandler::handleSwitchOnCommand(HeaterMapIter heaterMapIter) {
void HeaterHandler::handleSwitchOnCommand(heater::Switchers heaterIdx) {
ReturnValue_t result = RETURN_OK;
switchNr_t switchNr;
auto& heater = heaterVec.at(heaterIdx);
/* Check if command waits for main switch being set on and whether the timeout has expired */
if (heaterMapIter->second.waitMainSwitchOn &&
heaterMapIter->second.mainSwitchCountdown.hasTimedOut()) {
if (heater.waitMainSwitchOn && heater.mainSwitchCountdown.hasTimedOut()) {
// TODO - This requires the initiation of an FDIR procedure
triggerEvent(MAIN_SWITCH_TIMEOUT);
sif::error << "HeaterHandler::handleSwitchOnCommand: Main switch setting on timeout"
<< std::endl;
heaterMapIter->second.active = false;
heaterMapIter->second.waitMainSwitchOn = false;
if (heaterMapIter->second.replyQueue != commandQueue->getId()) {
actionHelper.finish(false, heaterMapIter->second.replyQueue, heaterMapIter->second.action,
MAIN_SWITCH_SET_TIMEOUT);
heater.cmdActive = false;
heater.waitMainSwitchOn = false;
if (heater.replyQueue != commandQueue->getId()) {
actionHelper.finish(false, heater.replyQueue, heater.action, MAIN_SWITCH_SET_TIMEOUT);
}
return;
}
switchNr = heaterMapIter->first;
/* Check state of main line switch */
// Check state of main line switch
ReturnValue_t mainSwitchState = mainLineSwitcher->getSwitchState(mainLineSwitch);
if (mainSwitchState == PowerSwitchIF::SWITCH_ON) {
if (!checkSwitchState(switchNr)) {
gpioId_t gpioId = getGpioIdFromSwitchNr(switchNr);
if (checkSwitchState(heaterIdx) == SwitchState::OFF) {
gpioId_t gpioId = heater.gpioId;
result = gpioInterface->pullHigh(gpioId);
if (result != RETURN_OK) {
sif::error << "HeaterHandler::handleSwitchOnCommand: Failed to pull gpio with id " << gpioId
<< " high" << std::endl;
triggerEvent(GPIO_PULL_HIGH_FAILED, result);
} else {
switchStates[switchNr] = ON;
triggerEvent(HEATER_WENT_ON, heaterIdx, 0);
heater.switchState = ON;
}
} else {
triggerEvent(SWITCH_ALREADY_ON, switchNr);
triggerEvent(SWITCH_ALREADY_ON, heaterIdx);
}
/* There is no need to send action finish replies if the sender was the
* HeaterHandler itself. */
if (heaterMapIter->second.replyQueue != commandQueue->getId()) {
// There is no need to send action finish replies if the sender was the
// HeaterHandler itself
if (heater.replyQueue != commandQueue->getId()) {
if (result == RETURN_OK) {
actionHelper.finish(true, heaterMapIter->second.replyQueue, heaterMapIter->second.action,
result);
actionHelper.finish(true, heater.replyQueue, heater.action, result);
} else {
actionHelper.finish(false, heaterMapIter->second.replyQueue, heaterMapIter->second.action,
result);
actionHelper.finish(false, heater.replyQueue, heater.action, result);
}
}
heaterMapIter->second.active = false;
heaterMapIter->second.waitMainSwitchOn = false;
} else if (mainSwitchState == PowerSwitchIF::SWITCH_OFF &&
heaterMapIter->second.waitMainSwitchOn) {
/* Just waiting for the main switch being set on */
heater.cmdActive = false;
heater.waitMainSwitchOn = false;
} else if (mainSwitchState == PowerSwitchIF::SWITCH_OFF && heater.waitMainSwitchOn) {
// Just waiting for the main switch being set on
return;
} else if (mainSwitchState == PowerSwitchIF::SWITCH_OFF) {
mainLineSwitcher->sendSwitchCommand(mainLineSwitch, PowerSwitchIF::SWITCH_ON);
heaterMapIter->second.mainSwitchCountdown.setTimeout(mainLineSwitcher->getSwitchDelayMs());
heaterMapIter->second.waitMainSwitchOn = true;
heater.mainSwitchCountdown.setTimeout(mainLineSwitcher->getSwitchDelayMs());
heater.waitMainSwitchOn = true;
} else {
sif::debug << "HeaterHandler::handleActiveCommands: Failed to get state of"
sif::debug << "HeaterHandler::handleSwitchHandling: Failed to get state of"
<< " main line switch" << std::endl;
if (heaterMapIter->second.replyQueue != commandQueue->getId()) {
actionHelper.finish(false, heaterMapIter->second.replyQueue, heaterMapIter->second.action,
mainSwitchState);
if (heater.replyQueue != commandQueue->getId()) {
actionHelper.finish(false, heater.replyQueue, heater.action, mainSwitchState);
}
heaterMapIter->second.active = false;
heater.cmdActive = false;
}
}
void HeaterHandler::handleSwitchOffCommand(HeaterMapIter heaterMapIter) {
void HeaterHandler::handleSwitchOffCommand(heater::Switchers heaterIdx) {
ReturnValue_t result = RETURN_OK;
switchNr_t switchNr = heaterMapIter->first;
/* Check whether switch is already off */
if (checkSwitchState(switchNr)) {
gpioId_t gpioId = getGpioIdFromSwitchNr(switchNr);
auto& heater = heaterVec.at(heaterIdx);
// Check whether switch is already off
if (checkSwitchState(heaterIdx)) {
gpioId_t gpioId = heater.gpioId;
result = gpioInterface->pullLow(gpioId);
if (result != RETURN_OK) {
sif::error << "HeaterHandler::handleSwitchOffCommand: Failed to pull gpio with id" << gpioId
<< " low" << std::endl;
triggerEvent(GPIO_PULL_LOW_FAILED, result);
} else {
switchStates[switchNr] = OFF;
/* When all switches are off, also main line switch will be turned off */
auto result = heaterMutex->lockMutex();
heater.switchState = OFF;
if (result == HasReturnvaluesIF::RETURN_OK) {
heaterMutex->unlockMutex();
}
triggerEvent(HEATER_WENT_OFF, heaterIdx, 0);
// When all switches are off, also main line switch will be turned off
if (allSwitchesOff()) {
mainLineSwitcher->sendSwitchCommand(mainLineSwitch, PowerSwitchIF::SWITCH_OFF);
}
}
} else {
sif::info << "HeaterHandler::handleSwitchOffCommand: Switch already off" << std::endl;
triggerEvent(SWITCH_ALREADY_OFF, switchNr);
triggerEvent(SWITCH_ALREADY_OFF, heaterIdx);
}
if (heaterMapIter->second.replyQueue != NO_COMMANDER) {
/* Report back switch command reply if necessary */
if (heater.replyQueue != NO_COMMANDER) {
// Report back switch command reply if necessary
if (result == HasReturnvaluesIF::RETURN_OK) {
actionHelper.finish(true, heaterMapIter->second.replyQueue, heaterMapIter->second.action,
result);
actionHelper.finish(true, heater.replyQueue, heater.action, result);
} else {
actionHelper.finish(false, heaterMapIter->second.replyQueue, heaterMapIter->second.action,
result);
actionHelper.finish(false, heater.replyQueue, heater.action, result);
}
}
heaterMapIter->second.active = false;
heater.cmdActive = false;
}
bool HeaterHandler::checkSwitchState(int switchNr) { return switchStates[switchNr]; }
HeaterHandler::SwitchState HeaterHandler::checkSwitchState(heater::Switchers switchNr) const {
MutexGuard mg(heaterMutex);
return heaterVec.at(switchNr).switchState;
}
bool HeaterHandler::allSwitchesOff() {
bool allSwitchesOrd = false;
MutexGuard mg(heaterMutex);
/* Or all switches. As soon one switch is on, allSwitchesOrd will be true */
for (switchNr_t switchNr = 0; switchNr < heaterSwitches::NUMBER_OF_SWITCHES; switchNr++) {
allSwitchesOrd = allSwitchesOrd || switchStates[switchNr];
for (power::Switch_t switchNr = 0; switchNr < heater::NUMBER_OF_SWITCHES; switchNr++) {
allSwitchesOrd = allSwitchesOrd || heaterVec.at(switchNr).switchState;
}
return !allSwitchesOrd;
}
gpioId_t HeaterHandler::getGpioIdFromSwitchNr(int switchNr) {
gpioId_t gpioId = 0xFFFF;
switch (switchNr) {
case heaterSwitches::HEATER_0:
gpioId = gpioIds::HEATER_0;
break;
case heaterSwitches::HEATER_1:
gpioId = gpioIds::HEATER_1;
break;
case heaterSwitches::HEATER_2:
gpioId = gpioIds::HEATER_2;
break;
case heaterSwitches::HEATER_3:
gpioId = gpioIds::HEATER_3;
break;
case heaterSwitches::HEATER_4:
gpioId = gpioIds::HEATER_4;
break;
case heaterSwitches::HEATER_5:
gpioId = gpioIds::HEATER_5;
break;
case heaterSwitches::HEATER_6:
gpioId = gpioIds::HEATER_6;
break;
case heaterSwitches::HEATER_7:
gpioId = gpioIds::HEATER_7;
break;
default:
sif::error << "HeaterHandler::getGpioIdFromSwitchNr: Unknown heater switch number"
<< std::endl;
break;
}
return gpioId;
}
MessageQueueId_t HeaterHandler::getCommandQueue() const { return commandQueue->getId(); }
ReturnValue_t HeaterHandler::sendFuseOnCommand(uint8_t fuseNr) { return RETURN_OK; }
ReturnValue_t HeaterHandler::getSwitchState(uint8_t switchNr) const { return 0; }
ReturnValue_t HeaterHandler::getSwitchState(uint8_t switchNr) const {
ReturnValue_t mainSwitchState = mainLineSwitcher->getSwitchState(mainLineSwitch);
if (mainSwitchState == PowerSwitchIF::SWITCH_OFF) {
return PowerSwitchIF::SWITCH_OFF;
}
if (switchNr > 7) {
return PowerSwitchIF::RETURN_FAILED;
}
if (checkSwitchState(static_cast<heater::Switchers>(switchNr)) == SwitchState::ON) {
return PowerSwitchIF::SWITCH_ON;
}
return PowerSwitchIF::SWITCH_OFF;
}
ReturnValue_t HeaterHandler::getFuseState(uint8_t fuseNr) const { return 0; }
uint32_t HeaterHandler::getSwitchDelayMs(void) const { return 0; }
uint32_t HeaterHandler::getSwitchDelayMs(void) const { return 2000; }

View File

@ -4,6 +4,9 @@
#include <fsfw/action/HasActionsIF.h>
#include <fsfw/devicehandlers/CookieIF.h>
#include <fsfw/devicehandlers/DeviceHandlerIF.h>
#include <fsfw/devicehandlers/HealthDevice.h>
#include <fsfw/health/HasHealthIF.h>
#include <fsfw/health/HealthHelper.h>
#include <fsfw/objectmanager/SystemObject.h>
#include <fsfw/power/PowerSwitchIF.h>
#include <fsfw/returnvalues/HasReturnvaluesIF.h>
@ -11,10 +14,21 @@
#include <fsfw/timemanager/Countdown.h>
#include <fsfw_hal/common/gpio/GpioIF.h>
#include <unordered_map>
#include <vector>
#include <array>
#include "devices/heaterSwitcherList.h"
class PowerSwitchIF;
class HealthTableIF;
using HeaterPair = std::pair<HealthDevice*, gpioId_t>;
struct HeaterHelper {
public:
HeaterHelper(std::array<HeaterPair, heater::NUMBER_OF_SWITCHES> heaters) : heaters(heaters) {}
std::array<HeaterPair, heater::NUMBER_OF_SWITCHES> heaters = {};
};
/**
* @brief This class intends the control of heaters.
*
@ -33,42 +47,49 @@ class HeaterHandler : public ExecutableObjectIF,
static const ReturnValue_t MAIN_SWITCH_SET_TIMEOUT = MAKE_RETURN_CODE(0xA4);
static const ReturnValue_t COMMAND_ALREADY_WAITING = MAKE_RETURN_CODE(0xA5);
enum CmdSourceParam : uint8_t { INTERNAL = 0, EXTERNAL = 1 };
/** Device command IDs */
static const DeviceCommandId_t SWITCH_HEATER = 0x0;
HeaterHandler(object_id_t setObjectId, object_id_t gpioDriverId, CookieIF* gpioCookie,
object_id_t mainLineSwitcherObjectId, uint8_t mainLineSwitch);
HeaterHandler(object_id_t setObjectId, GpioIF* gpioInterface_, HeaterHelper helper,
PowerSwitchIF* mainLineSwitcherObjectId, power::Switch_t mainLineSwitch);
virtual ~HeaterHandler();
virtual ReturnValue_t performOperation(uint8_t operationCode = 0) override;
ReturnValue_t performOperation(uint8_t operationCode = 0) override;
virtual ReturnValue_t sendSwitchCommand(uint8_t switchNr, ReturnValue_t onOff) override;
virtual ReturnValue_t sendFuseOnCommand(uint8_t fuseNr) override;
ReturnValue_t sendSwitchCommand(uint8_t switchNr, ReturnValue_t onOff) override;
ReturnValue_t sendFuseOnCommand(uint8_t fuseNr) override;
/**
* @brief This function will be called from the Heater object to check
* the current switch state.
*/
virtual ReturnValue_t getSwitchState(uint8_t switchNr) const override;
virtual ReturnValue_t getFuseState(uint8_t fuseNr) const override;
virtual uint32_t getSwitchDelayMs(void) const override;
ReturnValue_t getSwitchState(uint8_t switchNr) const override;
ReturnValue_t getFuseState(uint8_t fuseNr) const override;
uint32_t getSwitchDelayMs(void) const override;
virtual MessageQueueId_t getCommandQueue() const override;
virtual ReturnValue_t executeAction(ActionId_t actionId, MessageQueueId_t commandedBy,
const uint8_t* data, size_t size) override;
virtual ReturnValue_t initialize() override;
MessageQueueId_t getCommandQueue() const override;
ReturnValue_t executeAction(ActionId_t actionId, MessageQueueId_t commandedBy,
const uint8_t* data, size_t size) override;
ReturnValue_t initialize() override;
private:
static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::HEATER_HANDLER;
static const Event GPIO_PULL_HIGH_FAILED = MAKE_EVENT(0, severity::LOW);
static const Event GPIO_PULL_LOW_FAILED = MAKE_EVENT(1, severity::LOW);
static const Event SWITCH_ALREADY_ON = MAKE_EVENT(2, severity::LOW);
static const Event SWITCH_ALREADY_OFF = MAKE_EVENT(3, severity::LOW);
static const Event MAIN_SWITCH_TIMEOUT = MAKE_EVENT(4, severity::LOW);
static constexpr Event GPIO_PULL_HIGH_FAILED = MAKE_EVENT(0, severity::LOW);
static constexpr Event GPIO_PULL_LOW_FAILED = MAKE_EVENT(1, severity::LOW);
static constexpr Event HEATER_WENT_ON = event::makeEvent(SUBSYSTEM_ID, 2, severity::INFO);
static constexpr Event HEATER_WENT_OFF = event::makeEvent(SUBSYSTEM_ID, 3, severity::INFO);
static constexpr Event SWITCH_ALREADY_ON = MAKE_EVENT(4, severity::LOW);
static constexpr Event SWITCH_ALREADY_OFF = MAKE_EVENT(5, severity::LOW);
static constexpr Event MAIN_SWITCH_TIMEOUT = MAKE_EVENT(6, severity::MEDIUM);
//! A faulty heater was one. The SW will autonomously attempt to shut it down. P1: Heater Index
static constexpr Event FAULTY_HEATER_WAS_ON = event::makeEvent(SUBSYSTEM_ID, 7, severity::LOW);
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.
@ -80,54 +101,46 @@ class HeaterHandler : public ExecutableObjectIF,
* @param waitSwitchOn True if the command is waiting for the main switch being set on.
* @param mainSwitchCountdown Sets timeout to wait for main switch being set on.
*/
typedef struct HeaterCommandInfo {
uint8_t action;
MessageQueueId_t replyQueue;
bool active = false;
struct HeaterWrapper {
HeaterWrapper(HeaterPair pair, SwitchState initState)
: healthDevice(pair.first), gpioId(pair.second), switchState(initState) {}
HealthDevice* healthDevice = nullptr;
gpioId_t gpioId = gpio::NO_GPIO;
SwitchAction action = SwitchAction::NONE;
MessageQueueId_t replyQueue = MessageQueueIF::NO_QUEUE;
bool cmdActive = false;
SwitchState switchState = SwitchState::OFF;
bool waitMainSwitchOn = false;
Countdown mainSwitchCountdown;
} HeaterCommandInfo_t;
};
enum SwitchAction { SET_SWITCH_OFF, SET_SWITCH_ON };
using HeaterMap = std::vector<HeaterWrapper>;
using switchNr_t = uint8_t;
using HeaterMap = std::unordered_map<switchNr_t, HeaterCommandInfo_t>;
using HeaterMapIter = HeaterMap::iterator;
HeaterMap heaterVec = {};
HeaterMap heaterMap;
MutexIF* heaterMutex = nullptr;
bool switchStates[heaterSwitches::NUMBER_OF_SWITCHES];
HeaterHelper helper;
/** Size of command queue */
size_t cmdQueueSize = 20;
/**
* The object ID of the GPIO driver which enables and disables the
* heaters.
*/
object_id_t gpioDriverId;
CookieIF* gpioCookie;
GpioIF* gpioInterface = nullptr;
/** Queue to receive messages from other objects. */
MessageQueueIF* commandQueue = nullptr;
object_id_t mainLineSwitcherObjectId;
/** Switch number of the heater power supply switch */
uint8_t mainLineSwitch;
/**
* Power switcher object which controls the 8V main line of the heater
* logic on the TCS board.
*/
PowerSwitchIF* mainLineSwitcher = nullptr;
/** Switch number of the heater power supply switch */
power::Switch_t mainLineSwitch;
ActionHelper actionHelper;
StorageManagerIF* IPCStore = nullptr;
StorageManagerIF* ipcStore = nullptr;
void readCommandQueue();
@ -135,18 +148,12 @@ class HeaterHandler : public ExecutableObjectIF,
* @brief Returns the state of a switch (ON - true, or OFF - false).
* @param switchNr The number of the switch to check.
*/
bool checkSwitchState(int switchNr);
/**
* @brief Returns the ID of the GPIO related to a heater identified by the switch number
* which is defined in the heaterSwitches list.
*/
gpioId_t getGpioIdFromSwitchNr(int switchNr);
SwitchState checkSwitchState(heater::Switchers switchNr) const;
/**
* @brief This function runs commands waiting for execution.
*/
void handleActiveCommands();
void handleSwitchHandling();
ReturnValue_t initializeHeaterMap();
@ -155,9 +162,9 @@ class HeaterHandler : public ExecutableObjectIF,
*/
void setInitialSwitchStates();
void handleSwitchOnCommand(HeaterMapIter heaterMapIter);
void handleSwitchOnCommand(heater::Switchers heaterIdx);
void handleSwitchOffCommand(HeaterMapIter heaterMapIter);
void handleSwitchOffCommand(heater::Switchers heaterIdx);
/**
* @brief Checks if all switches are off.

View File

@ -63,7 +63,9 @@ ReturnValue_t IMTQHandler::buildNormalDeviceCommand(DeviceCommandId_t* id) {
return buildCommandFromCommand(*id, NULL, 0);
}
ReturnValue_t IMTQHandler::buildTransitionDeviceCommand(DeviceCommandId_t* id) { return RETURN_OK; }
ReturnValue_t IMTQHandler::buildTransitionDeviceCommand(DeviceCommandId_t* id) {
return NOTHING_TO_SEND;
}
ReturnValue_t IMTQHandler::buildCommandFromCommand(DeviceCommandId_t deviceCommand,
const uint8_t* commandData,
@ -606,6 +608,7 @@ ReturnValue_t IMTQHandler::initializeLocalDataPool(localpool::DataPool& localDat
poolManager.subscribeForPeriodicPacket(engHkDataset.getSid(), false, 10.0, true);
poolManager.subscribeForPeriodicPacket(calMtmMeasurementSet.getSid(), false, 10.0, true);
poolManager.subscribeForPeriodicPacket(rawMtmMeasurementSet.getSid(), false, 10.0, true);
return HasReturnvaluesIF::RETURN_OK;
}
@ -687,6 +690,8 @@ void IMTQHandler::fillEngHkDataset(const uint8_t* packet) {
offset += 2;
engHkDataset.mcuTemperature = (*(packet + offset + 1) << 8 | *(packet + offset));
engHkDataset.setValidity(true, true);
if (debugMode) {
#if OBSW_VERBOSE_LEVEL >= 1
sif::info << "IMTQ digital voltage: " << engHkDataset.digitalVoltageMv << " mV" << std::endl;

View File

@ -0,0 +1,195 @@
#include "Max31865EiveHandler.h"
#include <fsfw/datapool/PoolReadGuard.h>
Max31865EiveHandler::Max31865EiveHandler(object_id_t objectId, object_id_t comIF,
CookieIF* comCookie)
: DeviceHandlerBase(objectId, comIF, comCookie, nullptr),
sensorDataset(this, EiveMax31855::RtdCommands::EXCHANGE_SET_ID),
debugDivider(5) {
structLen = exchangeStruct.getSerializedSize();
}
void Max31865EiveHandler::doStartUp() {
updatePeriodicReply(true, EiveMax31855::RtdCommands::EXCHANGE_SET_ID);
if (state == InternalState::NONE or state == InternalState::INACTIVE) {
if (instantNormal) {
state = InternalState::ACTIVE;
} else {
state = InternalState::ON;
}
transitionOk = false;
}
if ((state == InternalState::ON or state == InternalState::ACTIVE) and transitionOk) {
if (instantNormal) {
setMode(MODE_NORMAL);
} else {
setMode(MODE_ON);
}
}
}
void Max31865EiveHandler::doShutDown() {
updatePeriodicReply(false, EiveMax31855::RtdCommands::EXCHANGE_SET_ID);
if (state == InternalState::NONE or state == InternalState::ACTIVE or
state == InternalState::ON) {
state = InternalState::INACTIVE;
transitionOk = false;
} else {
transitionOk = true;
}
if (state == InternalState::INACTIVE and transitionOk) {
setMode(_MODE_POWER_DOWN);
}
}
ReturnValue_t Max31865EiveHandler::buildNormalDeviceCommand(DeviceCommandId_t* id) {
//*id = EiveMax31855::RtdCommands::EXCHANGE_SET_ID;
return NOTHING_TO_SEND;
}
ReturnValue_t Max31865EiveHandler::buildTransitionDeviceCommand(DeviceCommandId_t* id) {
ReturnValue_t result = NOTHING_TO_SEND;
if (state == InternalState::ON) {
*id = EiveMax31855::RtdCommands::ON;
result = buildCommandFromCommand(*id, nullptr, 0);
}
if (state == InternalState::ACTIVE) {
*id = EiveMax31855::RtdCommands::ACTIVE;
result = buildCommandFromCommand(*id, nullptr, 0);
}
if (state == InternalState::INACTIVE) {
*id = EiveMax31855::RtdCommands::OFF;
result = buildCommandFromCommand(*id, nullptr, 0);
}
return result;
}
ReturnValue_t Max31865EiveHandler::buildCommandFromCommand(DeviceCommandId_t deviceCommand,
const uint8_t* commandData,
size_t commandDataLen) {
auto cmdTyped = static_cast<EiveMax31855::RtdCommands>(deviceCommand);
switch (cmdTyped) {
case (EiveMax31855::RtdCommands::ON):
case (EiveMax31855::RtdCommands::ACTIVE):
case (EiveMax31855::RtdCommands::OFF): {
simpleCommand(cmdTyped);
break;
}
case (EiveMax31855::RtdCommands::LOW_THRESHOLD):
case (EiveMax31855::RtdCommands::HIGH_TRESHOLD): {
break;
}
case (EiveMax31855::RtdCommands::CFG): {
break;
}
default:
return NOTHING_TO_SEND;
}
return RETURN_OK;
}
void Max31865EiveHandler::setInstantNormal(bool instantNormal) {
this->instantNormal = instantNormal;
}
void Max31865EiveHandler::setDebugMode(bool enable, uint32_t divider) {
this->debugMode = enable;
debugDivider.setDivider(divider);
}
void Max31865EiveHandler::simpleCommand(EiveMax31855::RtdCommands cmd) {
cmdBuf[0] = static_cast<uint8_t>(cmd);
rawPacket = cmdBuf.data();
rawPacketLen = 1;
}
void Max31865EiveHandler::doTransition(Mode_t modeFrom, Submode_t subModeFrom) {
if (mode == _MODE_TO_NORMAL) {
if (state != InternalState::ACTIVE) {
state = InternalState::ACTIVE;
transitionOk = false;
} else if (transitionOk) {
setMode(MODE_NORMAL);
}
} else {
DeviceHandlerBase::doTransition(modeFrom, subModeFrom);
}
}
void Max31865EiveHandler::fillCommandAndReplyMap() {
insertInCommandMap(EiveMax31855::RtdCommands::ON);
insertInCommandMap(EiveMax31855::RtdCommands::ACTIVE);
insertInCommandMap(EiveMax31855::RtdCommands::OFF);
insertInReplyMap(EiveMax31855::RtdCommands::EXCHANGE_SET_ID, 200, &sensorDataset, 0, true);
}
ReturnValue_t Max31865EiveHandler::scanForReply(const uint8_t* start, size_t remainingSize,
DeviceCommandId_t* foundId, size_t* foundLen) {
if (mode == _MODE_POWER_ON or mode == _MODE_WAIT_ON) {
return IGNORE_FULL_PACKET;
}
if (remainingSize != structLen) {
sif::error << "Invalid reply from RTD reader detected, reply size " << remainingSize
<< " not equal to exchange struct size " << structLen << std::endl;
return DeviceHandlerIF::INVALID_DATA;
}
*foundId = EiveMax31855::RtdCommands::EXCHANGE_SET_ID;
*foundLen = remainingSize;
return RETURN_OK;
}
ReturnValue_t Max31865EiveHandler::interpretDeviceReply(DeviceCommandId_t id,
const uint8_t* packet) {
size_t deserTmp = structLen;
auto result = exchangeStruct.deSerialize(&packet, &deserTmp, SerializeIF::Endianness::MACHINE);
if (result != RETURN_OK) {
return result;
}
if (mode == _MODE_TO_NORMAL and exchangeStruct.active and state == InternalState::ACTIVE) {
transitionOk = true;
}
if (mode == _MODE_START_UP and exchangeStruct.configured and state == InternalState::ON) {
transitionOk = true;
}
// Calculate resistance
float rtdValue = exchangeStruct.adcCode * EiveMax31855::RTD_RREF_PT1000 / INT16_MAX;
// calculate approximation
float approxTemp = exchangeStruct.adcCode / 32.0 - 256.0;
PoolReadGuard pg(&sensorDataset);
if (pg.getReadResult() != HasReturnvaluesIF::RETURN_OK) {
sif::warning << "Max31865EiveHandler: Failed to read sensor dataset" << std::endl;
sensorDataset.temperatureCelcius.setValid(false);
return RETURN_OK;
}
sensorDataset.temperatureCelcius = approxTemp;
sensorDataset.temperatureCelcius.setValid(true);
if (debugMode) {
if (debugDivider.checkAndIncrement()) {
sif::info << "Max31865: " << std::setw(20) << std::left << locString << std::right
<< " | R[Ohm] " << rtdValue << " Ohms | Approx T[C]: " << approxTemp << std::endl;
}
}
return RETURN_OK;
}
uint32_t Max31865EiveHandler::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { return 2000; }
ReturnValue_t Max31865EiveHandler::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}));
poolManager.subscribeForPeriodicPacket(sensorDataset.getSid(), false, 30.0, false);
return RETURN_OK;
}
void Max31865EiveHandler::setDeviceInfo(uint8_t idx_, std::string location_) {
idx = idx_;
locString = std::move(location_);
}
ReturnValue_t Max31865EiveHandler::initialize() { return DeviceHandlerBase::initialize(); }

View File

@ -0,0 +1,47 @@
#ifndef MISSION_DEVICES_MAX31865EIVEHANDLER_H_
#define MISSION_DEVICES_MAX31865EIVEHANDLER_H_
#include <fsfw/devicehandlers/DeviceHandlerBase.h>
#include <fsfw/globalfunctions/PeriodicOperationDivider.h>
#include "devicedefinitions/Max31865Definitions.h"
class Max31865EiveHandler : public DeviceHandlerBase {
public:
Max31865EiveHandler(object_id_t objectId, object_id_t comIF, CookieIF* comCookie);
void setInstantNormal(bool instantNormal);
void setDebugMode(bool enable, uint32_t divider);
void setDeviceInfo(uint8_t idx, std::string location);
private:
void doStartUp() override;
void doShutDown() override;
void doTransition(Mode_t modeFrom, Submode_t subModeFrom) override;
ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t* id) override;
ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t* id) override;
void fillCommandAndReplyMap() override;
ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, const uint8_t* commandData,
size_t commandDataLen) override;
ReturnValue_t scanForReply(const uint8_t* start, size_t remainingSize, DeviceCommandId_t* foundId,
size_t* foundLen) override;
ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t* packet) override;
uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override;
ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap,
LocalDataPoolManager& poolManager) override;
ReturnValue_t initialize() override;
void simpleCommand(EiveMax31855::RtdCommands cmd);
std::array<uint8_t, 12> cmdBuf = {};
uint8_t idx = 0;
std::string locString = "Unknown";
EiveMax31855::ReadOutStruct exchangeStruct;
bool debugMode = false;
size_t structLen = 0;
bool instantNormal = false;
MAX31865::Max31865Set sensorDataset;
PeriodicOperationDivider debugDivider;
enum class InternalState { NONE, ON, ACTIVE, INACTIVE } state = InternalState::NONE;
bool transitionOk = false;
};
#endif /* MISSION_DEVICES_MAX31865EIVEHANDLER_H_ */

View File

@ -8,7 +8,7 @@
Max31865PT1000Handler::Max31865PT1000Handler(object_id_t objectId, object_id_t comIF,
CookieIF *comCookie)
: DeviceHandlerBase(objectId, comIF, comCookie),
sensorDataset(this),
sensorDataset(this, MAX31865::REQUEST_RTD),
sensorDatasetSid(sensorDataset.getSid()) {
#if OBSW_VERBOSE_LEVEL >= 1
debugDivider = new PeriodicOperationDivider(10);
@ -93,13 +93,13 @@ void Max31865PT1000Handler::doShutDown() {
ReturnValue_t Max31865PT1000Handler::buildNormalDeviceCommand(DeviceCommandId_t *id) {
if (internalState == InternalState::RUNNING) {
*id = Max31865Definitions::REQUEST_RTD;
*id = MAX31865::REQUEST_RTD;
return buildCommandFromCommand(*id, nullptr, 0);
} else if (internalState == InternalState::REQUEST_FAULT_BYTE) {
*id = Max31865Definitions::REQUEST_FAULT_BYTE;
*id = MAX31865::REQUEST_FAULT_BYTE;
return buildCommandFromCommand(*id, nullptr, 0);
} else if (internalState == InternalState::CLEAR_FAULT_BYTE) {
*id = Max31865Definitions::CLEAR_FAULT_BYTE;
*id = MAX31865::CLEAR_FAULT_BYTE;
return buildCommandFromCommand(*id, nullptr, 0);
} else {
return DeviceHandlerBase::NOTHING_TO_SEND;
@ -113,32 +113,32 @@ ReturnValue_t Max31865PT1000Handler::buildTransitionDeviceCommand(DeviceCommandI
case (InternalState::RUNNING):
return DeviceHandlerBase::NOTHING_TO_SEND;
case (InternalState::CONFIGURE): {
*id = Max31865Definitions::CONFIG_CMD;
*id = MAX31865::CONFIG_CMD;
uint8_t config[1] = {DEFAULT_CONFIG};
return buildCommandFromCommand(*id, config, 1);
}
case (InternalState::REQUEST_CONFIG): {
*id = Max31865Definitions::REQUEST_CONFIG;
*id = MAX31865::REQUEST_CONFIG;
return buildCommandFromCommand(*id, nullptr, 0);
}
case (InternalState::CONFIG_HIGH_THRESHOLD): {
*id = Max31865Definitions::WRITE_HIGH_THRESHOLD;
*id = MAX31865::WRITE_HIGH_THRESHOLD;
return buildCommandFromCommand(*id, nullptr, 0);
}
case (InternalState::REQUEST_HIGH_THRESHOLD): {
*id = Max31865Definitions::REQUEST_HIGH_THRESHOLD;
*id = MAX31865::REQUEST_HIGH_THRESHOLD;
return buildCommandFromCommand(*id, nullptr, 0);
}
case (InternalState::CONFIG_LOW_THRESHOLD): {
*id = Max31865Definitions::WRITE_LOW_THRESHOLD;
*id = MAX31865::WRITE_LOW_THRESHOLD;
return buildCommandFromCommand(*id, nullptr, 0);
}
case (InternalState::REQUEST_LOW_THRESHOLD): {
*id = Max31865Definitions::REQUEST_LOW_THRESHOLD;
*id = MAX31865::REQUEST_LOW_THRESHOLD;
return buildCommandFromCommand(*id, nullptr, 0);
}
case (InternalState::CLEAR_FAULT_BYTE): {
*id = Max31865Definitions::CLEAR_FAULT_BYTE;
*id = MAX31865::CLEAR_FAULT_BYTE;
return buildCommandFromCommand(*id, nullptr, 0);
}
@ -156,10 +156,11 @@ ReturnValue_t Max31865PT1000Handler::buildCommandFromCommand(DeviceCommandId_t d
const uint8_t *commandData,
size_t commandDataLen) {
switch (deviceCommand) {
case (Max31865Definitions::CONFIG_CMD): {
commandBuffer[0] = static_cast<uint8_t>(Max31865Definitions::CONFIG_CMD);
case (MAX31865::CONFIG_CMD): {
commandBuffer[0] = static_cast<uint8_t>(MAX31865::CONFIG_CMD);
if (commandDataLen == 1) {
commandBuffer[1] = commandData[0];
currentCfg = commandData[0];
DeviceHandlerBase::rawPacketLen = 2;
DeviceHandlerBase::rawPacket = commandBuffer.data();
return HasReturnvaluesIF::RETURN_OK;
@ -167,54 +168,54 @@ ReturnValue_t Max31865PT1000Handler::buildCommandFromCommand(DeviceCommandId_t d
return DeviceHandlerIF::NO_COMMAND_DATA;
}
}
case (Max31865Definitions::CLEAR_FAULT_BYTE): {
commandBuffer[0] = static_cast<uint8_t>(Max31865Definitions::CONFIG_CMD);
commandBuffer[1] = Max31865Definitions::CLEAR_FAULT_BIT_VAL;
case (MAX31865::CLEAR_FAULT_BYTE): {
commandBuffer[0] = static_cast<uint8_t>(MAX31865::CONFIG_CMD);
commandBuffer[1] = currentCfg | MAX31865::CLEAR_FAULT_BIT_VAL;
DeviceHandlerBase::rawPacketLen = 2;
DeviceHandlerBase::rawPacket = commandBuffer.data();
return HasReturnvaluesIF::RETURN_OK;
}
case (Max31865Definitions::REQUEST_CONFIG): {
commandBuffer[0] = static_cast<uint8_t>(Max31865Definitions::REQUEST_CONFIG);
case (MAX31865::REQUEST_CONFIG): {
commandBuffer[0] = static_cast<uint8_t>(MAX31865::REQUEST_CONFIG);
commandBuffer[1] = 0x00; // dummy byte
DeviceHandlerBase::rawPacketLen = 2;
DeviceHandlerBase::rawPacket = commandBuffer.data();
return HasReturnvaluesIF::RETURN_OK;
}
case (Max31865Definitions::WRITE_HIGH_THRESHOLD): {
commandBuffer[0] = static_cast<uint8_t>(Max31865Definitions::WRITE_HIGH_THRESHOLD);
case (MAX31865::WRITE_HIGH_THRESHOLD): {
commandBuffer[0] = static_cast<uint8_t>(MAX31865::WRITE_HIGH_THRESHOLD);
commandBuffer[1] = static_cast<uint8_t>(HIGH_THRESHOLD >> 8);
commandBuffer[2] = static_cast<uint8_t>(HIGH_THRESHOLD & 0xFF);
DeviceHandlerBase::rawPacketLen = 3;
DeviceHandlerBase::rawPacket = commandBuffer.data();
return HasReturnvaluesIF::RETURN_OK;
}
case (Max31865Definitions::REQUEST_HIGH_THRESHOLD): {
commandBuffer[0] = static_cast<uint8_t>(Max31865Definitions::REQUEST_HIGH_THRESHOLD);
case (MAX31865::REQUEST_HIGH_THRESHOLD): {
commandBuffer[0] = static_cast<uint8_t>(MAX31865::REQUEST_HIGH_THRESHOLD);
commandBuffer[1] = 0x00; // dummy byte
commandBuffer[2] = 0x00; // dummy byte
DeviceHandlerBase::rawPacketLen = 3;
DeviceHandlerBase::rawPacket = commandBuffer.data();
return HasReturnvaluesIF::RETURN_OK;
}
case (Max31865Definitions::WRITE_LOW_THRESHOLD): {
commandBuffer[0] = static_cast<uint8_t>(Max31865Definitions::WRITE_LOW_THRESHOLD);
case (MAX31865::WRITE_LOW_THRESHOLD): {
commandBuffer[0] = static_cast<uint8_t>(MAX31865::WRITE_LOW_THRESHOLD);
commandBuffer[1] = static_cast<uint8_t>(LOW_THRESHOLD >> 8);
commandBuffer[2] = static_cast<uint8_t>(LOW_THRESHOLD & 0xFF);
DeviceHandlerBase::rawPacketLen = 3;
DeviceHandlerBase::rawPacket = commandBuffer.data();
return HasReturnvaluesIF::RETURN_OK;
}
case (Max31865Definitions::REQUEST_LOW_THRESHOLD): {
commandBuffer[0] = static_cast<uint8_t>(Max31865Definitions::REQUEST_LOW_THRESHOLD);
case (MAX31865::REQUEST_LOW_THRESHOLD): {
commandBuffer[0] = static_cast<uint8_t>(MAX31865::REQUEST_LOW_THRESHOLD);
commandBuffer[1] = 0x00; // dummy byte
commandBuffer[2] = 0x00; // dummy byte
DeviceHandlerBase::rawPacketLen = 3;
DeviceHandlerBase::rawPacket = commandBuffer.data();
return HasReturnvaluesIF::RETURN_OK;
}
case (Max31865Definitions::REQUEST_RTD): {
commandBuffer[0] = static_cast<uint8_t>(Max31865Definitions::REQUEST_RTD);
case (MAX31865::REQUEST_RTD): {
commandBuffer[0] = static_cast<uint8_t>(MAX31865::REQUEST_RTD);
// two dummy bytes
commandBuffer[1] = 0x00;
commandBuffer[2] = 0x00;
@ -222,8 +223,8 @@ ReturnValue_t Max31865PT1000Handler::buildCommandFromCommand(DeviceCommandId_t d
DeviceHandlerBase::rawPacket = commandBuffer.data();
return HasReturnvaluesIF::RETURN_OK;
}
case (Max31865Definitions::REQUEST_FAULT_BYTE): {
commandBuffer[0] = static_cast<uint8_t>(Max31865Definitions::REQUEST_FAULT_BYTE);
case (MAX31865::REQUEST_FAULT_BYTE): {
commandBuffer[0] = static_cast<uint8_t>(MAX31865::REQUEST_FAULT_BYTE);
commandBuffer[1] = 0x00;
DeviceHandlerBase::rawPacketLen = 2;
DeviceHandlerBase::rawPacket = commandBuffer.data();
@ -236,15 +237,15 @@ ReturnValue_t Max31865PT1000Handler::buildCommandFromCommand(DeviceCommandId_t d
}
void Max31865PT1000Handler::fillCommandAndReplyMap() {
insertInCommandAndReplyMap(Max31865Definitions::CONFIG_CMD, 3);
insertInCommandAndReplyMap(Max31865Definitions::REQUEST_CONFIG, 3);
insertInCommandAndReplyMap(Max31865Definitions::WRITE_LOW_THRESHOLD, 3);
insertInCommandAndReplyMap(Max31865Definitions::REQUEST_LOW_THRESHOLD, 3);
insertInCommandAndReplyMap(Max31865Definitions::WRITE_HIGH_THRESHOLD, 3);
insertInCommandAndReplyMap(Max31865Definitions::REQUEST_HIGH_THRESHOLD, 3);
insertInCommandAndReplyMap(Max31865Definitions::REQUEST_RTD, 3, &sensorDataset);
insertInCommandAndReplyMap(Max31865Definitions::REQUEST_FAULT_BYTE, 3);
insertInCommandAndReplyMap(Max31865Definitions::CLEAR_FAULT_BYTE, 3);
insertInCommandAndReplyMap(MAX31865::CONFIG_CMD, 3);
insertInCommandAndReplyMap(MAX31865::REQUEST_CONFIG, 3);
insertInCommandAndReplyMap(MAX31865::WRITE_LOW_THRESHOLD, 3);
insertInCommandAndReplyMap(MAX31865::REQUEST_LOW_THRESHOLD, 3);
insertInCommandAndReplyMap(MAX31865::WRITE_HIGH_THRESHOLD, 3);
insertInCommandAndReplyMap(MAX31865::REQUEST_HIGH_THRESHOLD, 3);
insertInCommandAndReplyMap(MAX31865::REQUEST_RTD, 3, &sensorDataset);
insertInCommandAndReplyMap(MAX31865::REQUEST_FAULT_BYTE, 3);
insertInCommandAndReplyMap(MAX31865::CLEAR_FAULT_BYTE, 3);
}
ReturnValue_t Max31865PT1000Handler::scanForReply(const uint8_t *start, size_t remainingSize,
@ -253,7 +254,7 @@ ReturnValue_t Max31865PT1000Handler::scanForReply(const uint8_t *start, size_t r
size_t configReplySize = 2;
if (remainingSize == rtdReplySize and internalState == InternalState::RUNNING) {
*foundId = Max31865Definitions::REQUEST_RTD;
*foundId = MAX31865::REQUEST_RTD;
*foundLen = rtdReplySize;
return RETURN_OK;
}
@ -262,24 +263,24 @@ ReturnValue_t Max31865PT1000Handler::scanForReply(const uint8_t *start, size_t r
switch (internalState) {
case (InternalState::CONFIG_HIGH_THRESHOLD): {
*foundLen = 3;
*foundId = Max31865Definitions::WRITE_HIGH_THRESHOLD;
*foundId = MAX31865::WRITE_HIGH_THRESHOLD;
commandExecuted = true;
return RETURN_OK;
}
case (InternalState::REQUEST_HIGH_THRESHOLD): {
*foundLen = 3;
*foundId = Max31865Definitions::REQUEST_HIGH_THRESHOLD;
*foundId = MAX31865::REQUEST_HIGH_THRESHOLD;
return RETURN_OK;
}
case (InternalState::CONFIG_LOW_THRESHOLD): {
*foundLen = 3;
*foundId = Max31865Definitions::WRITE_LOW_THRESHOLD;
*foundId = MAX31865::WRITE_LOW_THRESHOLD;
commandExecuted = true;
return RETURN_OK;
}
case (InternalState::REQUEST_LOW_THRESHOLD): {
*foundLen = 3;
*foundId = Max31865Definitions::REQUEST_LOW_THRESHOLD;
*foundId = MAX31865::REQUEST_LOW_THRESHOLD;
return RETURN_OK;
}
default: {
@ -293,13 +294,13 @@ ReturnValue_t Max31865PT1000Handler::scanForReply(const uint8_t *start, size_t r
if (internalState == InternalState::CONFIGURE) {
commandExecuted = true;
*foundLen = configReplySize;
*foundId = Max31865Definitions::CONFIG_CMD;
*foundId = MAX31865::CONFIG_CMD;
} else if (internalState == InternalState::REQUEST_FAULT_BYTE) {
*foundId = Max31865Definitions::REQUEST_FAULT_BYTE;
*foundId = MAX31865::REQUEST_FAULT_BYTE;
*foundLen = 2;
internalState = InternalState::RUNNING;
} else if (internalState == InternalState::CLEAR_FAULT_BYTE) {
*foundId = Max31865Definitions::CLEAR_FAULT_BYTE;
*foundId = MAX31865::CLEAR_FAULT_BYTE;
*foundLen = 2;
if (mode == _MODE_START_UP) {
commandExecuted = true;
@ -307,7 +308,7 @@ ReturnValue_t Max31865PT1000Handler::scanForReply(const uint8_t *start, size_t r
internalState = InternalState::RUNNING;
}
} else {
*foundId = Max31865Definitions::REQUEST_CONFIG;
*foundId = MAX31865::REQUEST_CONFIG;
*foundLen = configReplySize;
}
}
@ -318,7 +319,7 @@ ReturnValue_t Max31865PT1000Handler::scanForReply(const uint8_t *start, size_t r
ReturnValue_t Max31865PT1000Handler::interpretDeviceReply(DeviceCommandId_t id,
const uint8_t *packet) {
switch (id) {
case (Max31865Definitions::REQUEST_CONFIG): {
case (MAX31865::REQUEST_CONFIG): {
if (packet[1] != DEFAULT_CONFIG) {
if (warningSwitch) {
#if FSFW_CPP_OSTREAM_ENABLED == 1
@ -342,7 +343,7 @@ ReturnValue_t Max31865PT1000Handler::interpretDeviceReply(DeviceCommandId_t id,
}
break;
}
case (Max31865Definitions::REQUEST_LOW_THRESHOLD): {
case (MAX31865::REQUEST_LOW_THRESHOLD): {
uint16_t readLowThreshold = packet[1] << 8 | packet[2];
if (readLowThreshold != LOW_THRESHOLD) {
#if FSFW_VERBOSE_LEVEL >= 1
@ -360,8 +361,8 @@ ReturnValue_t Max31865PT1000Handler::interpretDeviceReply(DeviceCommandId_t id,
commandExecuted = true;
break;
}
case (Max31865Definitions::REQUEST_HIGH_THRESHOLD): {
uint16_t readHighThreshold = packet[1] << 8 | packet[2];
case (MAX31865::REQUEST_HIGH_THRESHOLD): {
uint16_t readHighThreshold = (packet[1] << 8) | packet[2];
if (readHighThreshold != HIGH_THRESHOLD) {
#if FSFW_VERBOSE_LEVEL >= 1
#if FSFW_CPP_OSTREAM_ENABLED == 1
@ -378,13 +379,13 @@ ReturnValue_t Max31865PT1000Handler::interpretDeviceReply(DeviceCommandId_t id,
commandExecuted = true;
break;
}
case (Max31865Definitions::REQUEST_RTD): {
case (MAX31865::REQUEST_RTD): {
// first bit of LSB reply byte is the fault bit
uint8_t faultBit = packet[2] & 0b0000'0001;
bool faultBit = packet[2] & 0b0000'0001;
if (resetFaultBit) {
internalState = InternalState::CLEAR_FAULT_BYTE;
resetFaultBit = false;
} else if (faultBit == 1) {
} else if (shouldFaultStatusBeRequested(faultBit)) {
// Maybe we should attempt to restart it?
internalState = InternalState::REQUEST_FAULT_BYTE;
resetFaultBit = true;
@ -393,9 +394,8 @@ ReturnValue_t Max31865PT1000Handler::interpretDeviceReply(DeviceCommandId_t id,
// RTD value consists of last seven bits of the LSB reply byte and
// the MSB reply byte
uint16_t adcCode = ((packet[1] << 8) | packet[2]) >> 1;
// do something with rtd value, will propably be stored in
// dataset.
float rtdValue = adcCode * RTD_RREF_PT1000 / INT16_MAX;
// Calculate resistance
float rtdValue = adcCode * EiveMax31855::RTD_RREF_PT1000 / INT16_MAX;
// calculate approximation
float approxTemp = adcCode / 32.0 - 256.0;
@ -403,9 +403,9 @@ ReturnValue_t Max31865PT1000Handler::interpretDeviceReply(DeviceCommandId_t id,
#if OBSW_VERBOSE_LEVEL >= 1
if (debugDivider->checkAndIncrement()) {
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::info << "Max31865: ObjID " << std::hex << this->getObjectId() << " | RTD "
<< std::dec << static_cast<int>(deviceIdx) << ": R[Ohm] " << rtdValue
<< " Ohms | Approx T[C]: " << approxTemp << std::endl;
sif::info << "Max31865: " << std::setw(24) << std::left << locString << std::right
<< " | R[Ohm] " << rtdValue << " Ohms | Approx T[C]: " << approxTemp
<< std::endl;
#else
sif::printInfo("Max31685: Measured resistance is %f Ohms\n", rtdValue);
sif::printInfo("Approximated temperature is %f C\n", approxTemp);
@ -438,58 +438,57 @@ ReturnValue_t Max31865PT1000Handler::interpretDeviceReply(DeviceCommandId_t id,
sensorDataset.temperatureCelcius = approxTemp;
break;
}
case (Max31865Definitions::REQUEST_FAULT_BYTE): {
faultByte = packet[1];
case (MAX31865::REQUEST_FAULT_BYTE): {
currentFaultStatus = packet[1];
bool faultStatusChanged = (currentFaultStatus != lastFaultStatus);
// Spam protection
if (faultStatusChanged or
((currentFaultStatus == lastFaultStatus) and (sameFaultStatusCounter < 3))) {
// TODO: Think about triggering an event here
#if OBSW_VERBOSE_LEVEL >= 1
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::warning << "Max31865PT1000Handler::interpretDeviceReply: Object ID: " << std::hex
<< this->getObjectId()
<< ": Fault byte"
" is: 0b"
<< std::bitset<8>(faultByte) << std::endl;
sif::warning << "Max31865PT1000Handler::interpretDeviceReply: Object ID: " << std::hex
<< this->getObjectId() << ": Fault byte is: 0b"
<< std::bitset<8>(currentFaultStatus) << std::endl;
#else
sif::printWarning(
"Max31865PT1000Handler::interpretDeviceReply: Fault byte"
" is: 0b" BYTE_TO_BINARY_PATTERN "\n",
BYTE_TO_BINARY(faultByte));
sif::printWarning(
"Max31865PT1000Handler::interpretDeviceReply: Fault byte"
" is: 0b" BYTE_TO_BINARY_PATTERN "\n",
BYTE_TO_BINARY(faultByte));
#endif
#endif
ReturnValue_t result = sensorDataset.read();
if (faultStatusChanged) {
sameFaultStatusCounter = 0;
} else {
sameFaultStatusCounter++;
}
}
if (faultStatusChanged) {
lastFaultStatus = currentFaultStatus;
}
PoolReadGuard pg(&sensorDataset);
auto result = pg.getReadResult();
if (result != HasReturnvaluesIF::RETURN_OK) {
// Configuration error
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::debug << "Max31865PT1000Handler::interpretDeviceReply: Object ID: " << std::hex
<< this->getObjectId()
<< ":"
"Error reading dataset!"
<< std::endl;
sif::warning << "Max31865PT1000Handler::interpretDeviceReply: Object ID: " << std::hex
<< this->getObjectId() << ": Error reading dataset" << std::endl;
#else
sif::printDebug(
"Max31865PT1000Handler::interpretDeviceReply: "
"Error reading dataset!\n");
sif::printWarning("Max31865PT1000Handler::interpretDeviceReply: Error reading dataset\n");
#endif
return result;
}
if (faultStatusChanged) {
sensorDataset.lastErrorByte.setValid(true);
sensorDataset.lastErrorByte = lastFaultStatus;
}
sensorDataset.errorByte.setValid(true);
sensorDataset.errorByte = faultByte;
if (faultByte != 0) {
sensorDataset.errorByte = currentFaultStatus;
if (currentFaultStatus != 0) {
sensorDataset.temperatureCelcius.setValid(false);
}
result = sensorDataset.commit();
if (result != HasReturnvaluesIF::RETURN_OK) {
// Configuration error
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::debug << "Max31865PT1000Handler::interpretDeviceReply: Object ID: " << std::hex
<< this->getObjectId() << ": Error commiting dataset!" << std::endl;
#else
sif::printDebug(
"Max31865PT1000Handler::interpretDeviceReply: "
"Error commiting dataset!\n");
#endif
return result;
}
break;
}
default:
@ -498,11 +497,8 @@ ReturnValue_t Max31865PT1000Handler::interpretDeviceReply(DeviceCommandId_t id,
return HasReturnvaluesIF::RETURN_OK;
}
void Max31865PT1000Handler::debugInterface(uint8_t positionTracker, object_id_t objectId,
uint32_t parameter) {}
uint32_t Max31865PT1000Handler::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) {
return 25000;
return 5000;
}
ReturnValue_t Max31865PT1000Handler::getSwitches(const uint8_t **switches,
@ -512,10 +508,12 @@ ReturnValue_t Max31865PT1000Handler::getSwitches(const uint8_t **switches,
ReturnValue_t Max31865PT1000Handler::initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
LocalDataPoolManager &poolManager) {
localDataPoolMap.emplace(Max31865Definitions::PoolIds::RTD_VALUE, new PoolEntry<float>({0}));
localDataPoolMap.emplace(Max31865Definitions::PoolIds::TEMPERATURE_C,
new PoolEntry<float>({0}, 1, true));
localDataPoolMap.emplace(Max31865Definitions::PoolIds::FAULT_BYTE, new PoolEntry<uint8_t>({0}));
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}));
poolManager.subscribeForPeriodicPacket(sensorDataset.getSid(), false, 30.0, false);
return HasReturnvaluesIF::RETURN_OK;
}
@ -526,10 +524,23 @@ void Max31865PT1000Handler::setInstantNormal(bool instantNormal) {
void Max31865PT1000Handler::modeChanged() {
if (mode == MODE_OFF) {
lastFaultStatus = 0;
currentFaultStatus = 0;
sameFaultStatusCounter = 0;
internalState = InternalState::NONE;
}
}
void Max31865PT1000Handler::setDeviceIdx(uint8_t idx) { deviceIdx = idx; }
void Max31865PT1000Handler::setDeviceInfo(uint8_t idx, std::string locString_) {
deviceIdx = idx;
locString = std::move(locString_);
}
void Max31865PT1000Handler::setDebugMode(bool enable) { this->debugMode = enable; }
bool Max31865PT1000Handler::shouldFaultStatusBeRequested(bool faultBit) {
if ((sameFaultStatusCounter < 3) and faultBit) {
return true;
}
return false;
}

View File

@ -48,7 +48,7 @@ class Max31865PT1000Handler : public DeviceHandlerBase {
static constexpr uint8_t DEFAULT_CONFIG = 0b11000001;
void setInstantNormal(bool instantNormal);
void setDeviceIdx(uint8_t idx);
void setDeviceInfo(uint8_t idx, std::string locString);
/**
* Expected temperature range is -100 C and 100 C.
@ -61,7 +61,6 @@ class Max31865PT1000Handler : public DeviceHandlerBase {
static constexpr uint16_t HIGH_THRESHOLD = 11298; // = 100 C
static constexpr uint16_t LOW_THRESHOLD = 4902; // = -100 C
static constexpr float RTD_RREF_PT1000 = 4020.0; //!< Ohm
static constexpr float RTD_RESISTANCE0_PT1000 = 1000.0; //!< Ohm
protected:
// DeviceHandlerBase abstract function implementation
@ -77,12 +76,10 @@ class Max31865PT1000Handler : public DeviceHandlerBase {
ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) override;
uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override;
ReturnValue_t getSwitches(const uint8_t **switches, uint8_t *numberOfSwitches) override;
void debugInterface(uint8_t positionTracker = 0, object_id_t objectId = 0,
uint32_t parameter = 0) override;
ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
LocalDataPoolManager &poolManager) override;
void modeChanged() override;
bool shouldFaultStatusBeRequested(bool faultBit);
private:
uint8_t switchId = 0;
@ -109,11 +106,15 @@ class Max31865PT1000Handler : public DeviceHandlerBase {
bool resetFaultBit = false;
dur_millis_t startTime = 0;
uint8_t faultByte = 0;
uint8_t currentCfg = 0;
uint8_t currentFaultStatus = 0;
uint8_t lastFaultStatus = 0;
uint16_t sameFaultStatusCounter = 0;
std::string locString;
uint8_t deviceIdx = 0;
std::array<uint8_t, 3> commandBuffer{0};
Max31865Definitions::Max31865Set sensorDataset;
MAX31865::Max31865Set sensorDataset;
sid_t sensorDatasetSid;
#if OBSW_VERBOSE_LEVEL >= 1

View File

@ -57,9 +57,9 @@ void P60DockHandler::parseHkTableReply(const uint8_t *packet) {
dataOffset += 3;
}
coreHk.temperature1 = *(packet + dataOffset) << 8 | *(packet + dataOffset + 1);
coreHk.temperature1 = (*(packet + dataOffset) << 8 | *(packet + dataOffset + 1)) * 0.1;
dataOffset += 4;
coreHk.temperature2 = *(packet + dataOffset) << 8 | *(packet + dataOffset + 1);
coreHk.temperature2 = (*(packet + dataOffset) << 8 | *(packet + dataOffset + 1)) * 0.1;
dataOffset += 4;
auxHk.bootcause = *(packet + dataOffset) << 24 |
@ -180,8 +180,8 @@ ReturnValue_t P60DockHandler::initializeLocalDataPool(localpool::DataPool &local
localDataPoolMap.emplace(pool::P60_OUTPUT_ENABLE, &outputEnables);
localDataPoolMap.emplace(pool::P60DOCK_TEMPERATURE_1, new PoolEntry<int16_t>({0}));
localDataPoolMap.emplace(pool::P60DOCK_TEMPERATURE_2, new PoolEntry<int16_t>({0}));
localDataPoolMap.emplace(pool::P60DOCK_TEMPERATURE_1, new PoolEntry<float>({0}));
localDataPoolMap.emplace(pool::P60DOCK_TEMPERATURE_2, new PoolEntry<float>({0}));
localDataPoolMap.emplace(pool::P60DOCK_BOOT_CAUSE, new PoolEntry<uint32_t>({0}));
localDataPoolMap.emplace(pool::P60DOCK_BOOT_CNT, new PoolEntry<uint32_t>({0}));
@ -251,7 +251,7 @@ ReturnValue_t P60DockHandler::printStatus(DeviceCommandId_t cmd) {
return HasReturnvaluesIF::RETURN_OK;
}
default: {
return HasReturnvaluesIF::RETURN_FAILED;
return DeviceHandlerIF::COMMAND_NOT_SUPPORTED;
}
}
sif::warning << "Reading P60 Dock HK table failed" << std::endl;

View File

@ -122,7 +122,7 @@ ReturnValue_t PDU1Handler::printStatus(DeviceCommandId_t cmd) {
break;
}
default: {
return HasReturnvaluesIF::RETURN_FAILED;
return DeviceHandlerIF::COMMAND_NOT_SUPPORTED;
}
}
if (result != HasReturnvaluesIF::RETURN_OK) {

View File

@ -76,7 +76,7 @@ ReturnValue_t PDU2Handler::printStatus(DeviceCommandId_t cmd) {
break;
}
default: {
return HasReturnvaluesIF::RETURN_FAILED;
return DeviceHandlerIF::COMMAND_NOT_SUPPORTED;
}
}
if (result != HasReturnvaluesIF::RETURN_OK) {

View File

@ -490,10 +490,9 @@ void PayloadPcduHandler::checkAdcValues() {
void PayloadPcduHandler::checkJsonFileInit() {
if (not jsonFileInitComplete) {
sd::SdCard prefSd;
sdcMan->getPreferredSdCard(prefSd);
if (sdcMan->isSdCardMounted(prefSd)) {
params.initialize(sdcMan->getCurrentMountPrefix(prefSd));
sd::SdCard activeSd = sdcMan->getActiveSdCard();
if (sdcMan->isSdCardMounted(activeSd)) {
params.initialize(sdcMan->getCurrentMountPrefix());
jsonFileInitComplete = true;
}
}
@ -716,7 +715,7 @@ ReturnValue_t PayloadPcduHandler::transferAsTwo(SpiComIF* comIf, SpiCookie* cook
GpioIF* gpioIF = comIf->getGpioInterface();
MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING;
uint32_t timeoutMs = 0;
MutexIF* mutex = comIf->getMutex(&timeoutType, &timeoutMs);
MutexIF* mutex = comIf->getCsMutex();
if (mutex == nullptr or gpioIF == nullptr) {
#if OBSW_VERBOSE_LEVEL >= 1
sif::warning << "GyroADIS16507Handler::spiSendCallback: "
@ -727,6 +726,7 @@ ReturnValue_t PayloadPcduHandler::transferAsTwo(SpiComIF* comIf, SpiCookie* cook
}
if (gpioId != gpio::NO_GPIO) {
cookie->getMutexParams(timeoutType, timeoutMs);
result = mutex->lockMutex(timeoutType, timeoutMs);
if (result != RETURN_OK) {
#if FSFW_CPP_OSTREAM_ENABLED == 1

View File

@ -158,18 +158,18 @@ ReturnValue_t RadiationSensorHandler::interpretDeviceReply(DeviceCommandId_t id,
int16_t tempRaw = ((packet[offset] & 0x0f) << 8) | packet[offset + 1];
dataset.temperatureCelcius = tempRaw * 0.125;
offset += 2;
dataset.ain0 = (*(packet + offset) << 8 | *(packet + offset + 1));
dataset.ain0 = (*(packet + offset) << 8) | *(packet + offset + 1);
offset += 2;
dataset.ain1 = (*(packet + offset) << 8 | *(packet + offset + 1));
dataset.ain1 = (*(packet + offset) << 8) | *(packet + offset + 1);
offset += 6;
dataset.ain4 = (*(packet + offset) << 8 | *(packet + offset + 1));
dataset.ain4 = (*(packet + offset) << 8) | *(packet + offset + 1);
offset += 2;
dataset.ain5 = (*(packet + offset) << 8 | *(packet + offset + 1));
dataset.ain5 = (*(packet + offset) << 8) | *(packet + offset + 1);
offset += 2;
dataset.ain6 = (*(packet + offset) << 8 | *(packet + offset + 1));
dataset.ain6 = (*(packet + offset) << 8) | *(packet + offset + 1);
offset += 2;
dataset.ain7 = (*(packet + offset) << 8 | *(packet + offset + 1));
dataset.ain7 = (*(packet + offset) << 8) | *(packet + offset + 1);
dataset.setValidity(true, true);
if (printPeriodicData) {
sif::info << "Radiation sensor temperature: " << dataset.temperatureCelcius << " °C"
<< std::dec << std::endl;

View File

@ -279,6 +279,7 @@ ReturnValue_t RwHandler::initializeLocalDataPool(localpool::DataPool& localDataP
localDataPoolMap.emplace(RwDefinitions::SPI_TOTAL_ERRORS, new PoolEntry<uint32_t>({0}));
poolManager.subscribeForPeriodicPacket(statusSet.getSid(), false, 5.0, true);
poolManager.subscribeForPeriodicPacket(tmDataset.getSid(), false, 30.0, false);
poolManager.subscribeForPeriodicPacket(lastResetStatusSet.getSid(), false, 30.0, false);
return RETURN_OK;
}

View File

@ -160,11 +160,11 @@ ReturnValue_t SusHandler::interpretDeviceReply(DeviceCommandId_t id, const uint8
}
case SUS::READ_INT_TIMED_CONVERSIONS: {
PoolReadGuard readSet(&dataset);
dataset.temperatureCelcius = max1227::getTemperature(((packet[0] & 0x0f) << 8) | packet[1]);
for (uint8_t idx = 0; idx < 6; idx++) {
dataset.channels[idx] = packet[idx * 2 + 2] << 8 | packet[idx * 2 + 3];
}
dataset.setValidity(true, true);
printDataset();
break;
}
@ -173,6 +173,7 @@ ReturnValue_t SusHandler::interpretDeviceReply(DeviceCommandId_t id, const uint8
for (uint8_t idx = 0; idx < 6; idx++) {
dataset.channels[idx] = packet[idx * 2 + 1] << 8 | packet[idx * 2 + 2];
}
dataset.channels.setValid(true);
// Read temperature in next read cycle
if (clkMode == ClkModes::EXT_CLOCKED_WITH_TEMP) {
comState = ComStates::EXT_CLOCKED_TEMP;
@ -183,6 +184,7 @@ ReturnValue_t SusHandler::interpretDeviceReply(DeviceCommandId_t id, const uint8
case (SUS::READ_EXT_TIMED_TEMPS): {
PoolReadGuard readSet(&dataset);
dataset.temperatureCelcius = max1227::getTemperature(((packet[23] & 0x0f) << 8) | packet[24]);
dataset.temperatureCelcius.setValid(true);
comState = ComStates::EXT_CLOCKED_CONVERSIONS;
break;
}

View File

@ -361,8 +361,8 @@ ReturnValue_t SyrlinksHkHandler::interpretDeviceReply(DeviceCommandId_t id, cons
rawTempBasebandBoard |= convertHexStringToUint8(
reinterpret_cast<const char*>(packet + syrlinks::MESSAGE_HEADER_SIZE));
tempBasebandBoard = calcTempVal(rawTempBasebandBoard);
temperatureSet.temperatureBasebandBoard = tempBasebandBoard;
PoolReadGuard rg(&temperatureSet);
temperatureSet.temperatureBasebandBoard = tempBasebandBoard;
if (debugMode) {
sif::info << "Syrlinks temperature baseband board: " << tempBasebandBoard << " °C"
<< std::endl;

View File

@ -93,8 +93,12 @@ ReturnValue_t Tmp1075Handler::interpretDeviceReply(DeviceCommandId_t id, const u
ReturnValue_t result = dataset.read();
if (result == HasReturnvaluesIF::RETURN_OK) {
dataset.temperatureCelcius = tempValue;
dataset.setValidity(true, true);
dataset.commit();
}
else {
dataset.setValidity(false, true);
}
break;
}

View File

@ -14,7 +14,7 @@ static constexpr uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::GPS_HANDLER;
static constexpr Event GPS_FIX_CHANGE = event::makeEvent(SUBSYSTEM_ID, 0, severity::INFO);
static constexpr DeviceCommandId_t GPS_REPLY = 0;
static constexpr DeviceCommandId_t TRIGGER_RESET_PIN = 5;
static constexpr DeviceCommandId_t TRIGGER_RESET_PIN_GNSS = 5;
static constexpr uint32_t DATASET_ID = 0;

View File

@ -38,7 +38,8 @@ static const DeviceCommandId_t PARAM_GET = 0; //!< [EXPORT] : [COMMAND]
static const DeviceCommandId_t PARAM_SET = 255; //!< [EXPORT] : [COMMAND]
static const DeviceCommandId_t REQUEST_HK_TABLE = 16; //!< [EXPORT] : [COMMAND]
//!< [EXPORT] : [COMMAND] Print switch states, voltages and currents to the console
//! [EXPORT] : [COMMAND] Print switch states, voltages and currents to the console
//! For the ACU device, only print voltages and currents of the 6 ACU channels
static const DeviceCommandId_t PRINT_SWITCH_V_I = 32;
static const DeviceCommandId_t PRINT_LATCHUPS = 33;
@ -55,7 +56,8 @@ enum class SetIds : uint32_t {
PDU_2_AUX = 4,
P60_CORE = 5,
P60_AUX = 6,
ACU = 7
ACU_CORE = 7,
ACU_AUX = 8
};
namespace pool {
@ -129,67 +131,24 @@ enum Ids : lp_id_t {
PDU_WDT_CSP_LEFT2,
/** ACU Ids */
ACU_CURRENT_IN_CHANNEL0,
ACU_CURRENT_IN_CHANNEL1,
ACU_CURRENT_IN_CHANNEL2,
ACU_CURRENT_IN_CHANNEL3,
ACU_CURRENT_IN_CHANNEL4,
ACU_CURRENT_IN_CHANNEL5,
ACU_VOLTAGE_IN_CHANNEL0,
ACU_VOLTAGE_IN_CHANNEL1,
ACU_VOLTAGE_IN_CHANNEL2,
ACU_VOLTAGE_IN_CHANNEL3,
ACU_VOLTAGE_IN_CHANNEL4,
ACU_VOLTAGE_IN_CHANNEL5,
ACU_CURRENT_IN_CHANNELS,
ACU_VOLTAGE_IN_CHANNELS,
ACU_VCC,
ACU_VBAT,
ACU_TEMPERATURE_1,
ACU_TEMPERATURE_2,
ACU_TEMPERATURE_3,
ACU_TEMPERATURES,
ACU_MPPT_MODE,
ACU_VBOOST_CHANNEL0,
ACU_VBOOST_CHANNEL1,
ACU_VBOOST_CHANNEL2,
ACU_VBOOST_CHANNEL3,
ACU_VBOOST_CHANNEL4,
ACU_VBOOST_CHANNEL5,
ACU_POWER_CHANNEL0,
ACU_POWER_CHANNEL1,
ACU_POWER_CHANNEL2,
ACU_POWER_CHANNEL3,
ACU_POWER_CHANNEL4,
ACU_POWER_CHANNEL5,
ACU_DAC_EN_0,
ACU_DAC_EN_1,
ACU_DAC_EN_2,
ACU_DAC_RAW_0,
ACU_DAC_RAW_1,
ACU_DAC_RAW_2,
ACU_DAC_RAW_3,
ACU_DAC_RAW_4,
ACU_DAC_RAW_5,
ACU_VBOOST_IN_CHANNELS,
ACU_POWER_IN_CHANNELS,
ACU_DAC_ENABLES,
ACU_DAC_RAW_CHANNELS,
ACU_BOOTCAUSE,
ACU_BOOTCNT,
ACU_UPTIME,
ACU_RESET_CAUSE,
ACU_MPPT_TIME,
ACU_MPPT_PERIOD,
ACU_DEVICE_0,
ACU_DEVICE_1,
ACU_DEVICE_2,
ACU_DEVICE_3,
ACU_DEVICE_4,
ACU_DEVICE_5,
ACU_DEVICE_6,
ACU_DEVICE_7,
ACU_DEVICE_0_STATUS,
ACU_DEVICE_1_STATUS,
ACU_DEVICE_2_STATUS,
ACU_DEVICE_3_STATUS,
ACU_DEVICE_4_STATUS,
ACU_DEVICE_5_STATUS,
ACU_DEVICE_6_STATUS,
ACU_DEVICE_7_STATUS,
ACU_DEVICES,
ACU_DEVICES_STATUS,
ACU_WDT_CNT_GND,
ACU_WDT_GND_LEFT,
};
@ -285,10 +244,10 @@ class CoreHkSet : public StaticLocalDataSet<16> {
lp_var_t<uint16_t> batteryVoltage =
lp_var_t<uint16_t>(sid.objectId, P60System::pool::P60DOCK_BATTERY_VOLTAGE, this);
lp_var_t<int16_t> temperature1 =
lp_var_t<int16_t>(sid.objectId, P60System::pool::P60DOCK_TEMPERATURE_1, this);
lp_var_t<int16_t> temperature2 =
lp_var_t<int16_t>(sid.objectId, P60System::pool::P60DOCK_TEMPERATURE_2, this);
lp_var_t<float> temperature1 =
lp_var_t<float>(sid.objectId, P60System::pool::P60DOCK_TEMPERATURE_1, this);
lp_var_t<float> temperature2 =
lp_var_t<float>(sid.objectId, P60System::pool::P60DOCK_TEMPERATURE_2, this);
};
/**
* @brief This class defines a dataset for the hk table of the P60 Dock.
@ -409,8 +368,8 @@ class PduCoreHk : public StaticLocalDataSet<9> {
/** Battery mode: 1 = Critical, 2 = Safe, 3 = Normal, 4 = Full */
lp_var_t<uint8_t> battMode =
lp_var_t<uint8_t>(sid.objectId, P60System::pool::PDU_BATT_MODE, this);
lp_var_t<int16_t> temperature =
lp_var_t<int16_t>(sid.objectId, P60System::pool::PDU_TEMPERATURE, this);
lp_var_t<float> temperature =
lp_var_t<float>(sid.objectId, P60System::pool::PDU_TEMPERATURE, this);
};
/**
@ -592,143 +551,76 @@ static const uint16_t MAX_HKTABLE_ADDRESS = 120;
static const uint8_t HK_TABLE_ENTRIES = 64;
static const uint16_t HK_TABLE_REPLY_SIZE = 262;
/**
* @brief This class defines a dataset for the hk table of the ACU.
*/
class HkTableDataset : public StaticLocalDataSet<HK_TABLE_ENTRIES> {
class CoreHk : public StaticLocalDataSet<14> {
public:
HkTableDataset(HasLocalDataPoolIF* owner)
: StaticLocalDataSet(owner, static_cast<uint32_t>(::P60System::SetIds::ACU)) {}
CoreHk(HasLocalDataPoolIF* owner)
: StaticLocalDataSet(owner, static_cast<uint32_t>(::P60System::SetIds::ACU_CORE)) {}
HkTableDataset(object_id_t objectId)
: StaticLocalDataSet(sid_t(objectId, static_cast<uint32_t>(::P60System::SetIds::ACU))) {}
lp_var_t<int16_t> currentInChannel0 =
lp_var_t<int16_t>(sid.objectId, P60System::pool::ACU_CURRENT_IN_CHANNEL0, this);
lp_var_t<int16_t> currentInChannel1 =
lp_var_t<int16_t>(sid.objectId, P60System::pool::ACU_CURRENT_IN_CHANNEL1, this);
lp_var_t<int16_t> currentInChannel2 =
lp_var_t<int16_t>(sid.objectId, P60System::pool::ACU_CURRENT_IN_CHANNEL2, this);
lp_var_t<int16_t> currentInChannel3 =
lp_var_t<int16_t>(sid.objectId, P60System::pool::ACU_CURRENT_IN_CHANNEL3, this);
lp_var_t<int16_t> currentInChannel4 =
lp_var_t<int16_t>(sid.objectId, P60System::pool::ACU_CURRENT_IN_CHANNEL4, this);
lp_var_t<int16_t> currentInChannel5 =
lp_var_t<int16_t>(sid.objectId, P60System::pool::ACU_CURRENT_IN_CHANNEL5, this);
lp_var_t<uint16_t> voltageInChannel0 =
lp_var_t<uint16_t>(sid.objectId, P60System::pool::ACU_VOLTAGE_IN_CHANNEL0, this);
lp_var_t<uint16_t> voltageInChannel1 =
lp_var_t<uint16_t>(sid.objectId, P60System::pool::ACU_VOLTAGE_IN_CHANNEL1, this);
lp_var_t<uint16_t> voltageInChannel2 =
lp_var_t<uint16_t>(sid.objectId, P60System::pool::ACU_VOLTAGE_IN_CHANNEL2, this);
lp_var_t<uint16_t> voltageInChannel3 =
lp_var_t<uint16_t>(sid.objectId, P60System::pool::ACU_VOLTAGE_IN_CHANNEL3, this);
lp_var_t<uint16_t> voltageInChannel4 =
lp_var_t<uint16_t>(sid.objectId, P60System::pool::ACU_VOLTAGE_IN_CHANNEL4, this);
lp_var_t<uint16_t> voltageInChannel5 =
lp_var_t<uint16_t>(sid.objectId, P60System::pool::ACU_VOLTAGE_IN_CHANNEL5, this);
lp_var_t<uint16_t> vcc = lp_var_t<uint16_t>(sid.objectId, P60System::pool::ACU_VCC, this);
lp_var_t<uint16_t> vbat = lp_var_t<uint16_t>(sid.objectId, P60System::pool::ACU_VBAT, this);
lp_var_t<int16_t> temperature1 =
lp_var_t<int16_t>(sid.objectId, P60System::pool::ACU_TEMPERATURE_1, this);
lp_var_t<int16_t> temperature2 =
lp_var_t<int16_t>(sid.objectId, P60System::pool::ACU_TEMPERATURE_2, this);
lp_var_t<int16_t> temperature3 =
lp_var_t<int16_t>(sid.objectId, P60System::pool::ACU_TEMPERATURE_3, this);
CoreHk(object_id_t objectId)
: StaticLocalDataSet(sid_t(objectId, static_cast<uint32_t>(::P60System::SetIds::ACU_CORE))) {}
lp_var_t<uint8_t> mpptMode =
lp_var_t<uint8_t>(sid.objectId, P60System::pool::ACU_MPPT_MODE, this);
lp_var_t<uint16_t> vboostInChannel0 =
lp_var_t<uint16_t>(sid.objectId, P60System::pool::ACU_VBOOST_CHANNEL0, this);
lp_var_t<uint16_t> vboostInChannel1 =
lp_var_t<uint16_t>(sid.objectId, P60System::pool::ACU_VBOOST_CHANNEL1, this);
lp_var_t<uint16_t> vboostInChannel2 =
lp_var_t<uint16_t>(sid.objectId, P60System::pool::ACU_VBOOST_CHANNEL2, this);
lp_var_t<uint16_t> vboostInChannel3 =
lp_var_t<uint16_t>(sid.objectId, P60System::pool::ACU_VBOOST_CHANNEL3, this);
lp_var_t<uint16_t> vboostInChannel4 =
lp_var_t<uint16_t>(sid.objectId, P60System::pool::ACU_VBOOST_CHANNEL4, this);
lp_var_t<uint16_t> vboostInChannel5 =
lp_var_t<uint16_t>(sid.objectId, P60System::pool::ACU_VBOOST_CHANNEL5, this);
lp_vec_t<int16_t, 6> currentInChannels =
lp_vec_t<int16_t, 6>(sid.objectId, P60System::pool::ACU_CURRENT_IN_CHANNELS, this);
lp_vec_t<uint16_t, 6> voltageInChannels =
lp_vec_t<uint16_t, 6>(sid.objectId, P60System::pool::ACU_VOLTAGE_IN_CHANNELS, this);
lp_var_t<uint16_t> powerInChannel0 =
lp_var_t<uint16_t>(sid.objectId, P60System::pool::ACU_POWER_CHANNEL0, this);
lp_var_t<uint16_t> powerInChannel1 =
lp_var_t<uint16_t>(sid.objectId, P60System::pool::ACU_POWER_CHANNEL1, this);
lp_var_t<uint16_t> powerInChannel2 =
lp_var_t<uint16_t>(sid.objectId, P60System::pool::ACU_POWER_CHANNEL2, this);
lp_var_t<uint16_t> powerInChannel3 =
lp_var_t<uint16_t>(sid.objectId, P60System::pool::ACU_POWER_CHANNEL3, this);
lp_var_t<uint16_t> powerInChannel4 =
lp_var_t<uint16_t>(sid.objectId, P60System::pool::ACU_POWER_CHANNEL4, this);
lp_var_t<uint16_t> powerInChannel5 =
lp_var_t<uint16_t>(sid.objectId, P60System::pool::ACU_POWER_CHANNEL5, this);
lp_var_t<uint16_t> vcc = lp_var_t<uint16_t>(sid.objectId, P60System::pool::ACU_VCC, this);
lp_var_t<uint16_t> vbat = lp_var_t<uint16_t>(sid.objectId, P60System::pool::ACU_VBAT, this);
lp_var_t<uint8_t> dac0Enable =
lp_var_t<uint8_t>(sid.objectId, P60System::pool::ACU_DAC_EN_0, this);
lp_var_t<uint8_t> dac1Enable =
lp_var_t<uint8_t>(sid.objectId, P60System::pool::ACU_DAC_EN_1, this);
lp_var_t<uint8_t> dac2Enable =
lp_var_t<uint8_t>(sid.objectId, P60System::pool::ACU_DAC_EN_2, this);
lp_vec_t<uint16_t, 6> vboostInChannels =
lp_vec_t<uint16_t, 6>(sid.objectId, P60System::pool::ACU_VBOOST_IN_CHANNELS, this);
lp_vec_t<uint16_t, 6> powerInChannels =
lp_vec_t<uint16_t, 6>(sid.objectId, P60System::pool::ACU_POWER_IN_CHANNELS, this);
lp_var_t<uint16_t> dacRawChannelVal0 =
lp_var_t<uint16_t>(sid.objectId, P60System::pool::ACU_DAC_RAW_0, this);
lp_var_t<uint16_t> dacRawChannelVal1 =
lp_var_t<uint16_t>(sid.objectId, P60System::pool::ACU_DAC_RAW_1, this);
lp_var_t<uint16_t> dacRawChannelVal2 =
lp_var_t<uint16_t>(sid.objectId, P60System::pool::ACU_DAC_RAW_2, this);
lp_var_t<uint16_t> dacRawChannelVal3 =
lp_var_t<uint16_t>(sid.objectId, P60System::pool::ACU_DAC_RAW_3, this);
lp_var_t<uint16_t> dacRawChannelVal4 =
lp_var_t<uint16_t>(sid.objectId, P60System::pool::ACU_DAC_RAW_4, this);
lp_var_t<uint16_t> dacRawChannelVal5 =
lp_var_t<uint16_t>(sid.objectId, P60System::pool::ACU_DAC_RAW_5, this);
lp_vec_t<float, 3> temperatures =
lp_vec_t<float, 3>(sid.objectId, P60System::pool::ACU_TEMPERATURES, this);
lp_var_t<uint32_t> bootCause =
lp_var_t<uint32_t>(sid.objectId, P60System::pool::ACU_BOOTCAUSE, this);
lp_var_t<uint32_t> bootcnt = lp_var_t<uint32_t>(sid.objectId, P60System::pool::ACU_BOOTCNT, this);
lp_var_t<uint32_t> uptime = lp_var_t<uint32_t>(sid.objectId, P60System::pool::ACU_UPTIME, this);
lp_var_t<uint16_t> resetCause =
lp_var_t<uint16_t>(sid.objectId, P60System::pool::ACU_RESET_CAUSE, this);
lp_var_t<uint16_t> mpptTime =
lp_var_t<uint16_t>(sid.objectId, P60System::pool::ACU_MPPT_TIME, this);
lp_var_t<uint16_t> mpptPeriod =
lp_var_t<uint16_t>(sid.objectId, P60System::pool::ACU_MPPT_PERIOD, this);
};
/**
* @brief This class defines a dataset for the hk table of the ACU.
*/
class AuxHk : public StaticLocalDataSet<12> {
public:
AuxHk(HasLocalDataPoolIF* owner)
: StaticLocalDataSet(owner, static_cast<uint32_t>(::P60System::SetIds::ACU_AUX)) {}
lp_var_t<uint8_t> device0 = lp_var_t<uint8_t>(sid.objectId, P60System::pool::ACU_DEVICE_0, this);
lp_var_t<uint8_t> device1 = lp_var_t<uint8_t>(sid.objectId, P60System::pool::ACU_DEVICE_1, this);
lp_var_t<uint8_t> device2 = lp_var_t<uint8_t>(sid.objectId, P60System::pool::ACU_DEVICE_2, this);
lp_var_t<uint8_t> device3 = lp_var_t<uint8_t>(sid.objectId, P60System::pool::ACU_DEVICE_3, this);
lp_var_t<uint8_t> device4 = lp_var_t<uint8_t>(sid.objectId, P60System::pool::ACU_DEVICE_4, this);
lp_var_t<uint8_t> device5 = lp_var_t<uint8_t>(sid.objectId, P60System::pool::ACU_DEVICE_5, this);
lp_var_t<uint8_t> device6 = lp_var_t<uint8_t>(sid.objectId, P60System::pool::ACU_DEVICE_6, this);
lp_var_t<uint8_t> device7 = lp_var_t<uint8_t>(sid.objectId, P60System::pool::ACU_DEVICE_7, this);
AuxHk(object_id_t objectId)
: StaticLocalDataSet(sid_t(objectId, static_cast<uint32_t>(::P60System::SetIds::ACU_AUX))) {}
lp_var_t<uint8_t> device0Status =
lp_var_t<uint8_t>(sid.objectId, P60System::pool::ACU_DEVICE_0_STATUS, this);
lp_var_t<uint8_t> device1Status =
lp_var_t<uint8_t>(sid.objectId, P60System::pool::ACU_DEVICE_1_STATUS, this);
lp_var_t<uint8_t> device2Status =
lp_var_t<uint8_t>(sid.objectId, P60System::pool::ACU_DEVICE_2_STATUS, this);
lp_var_t<uint8_t> device3Status =
lp_var_t<uint8_t>(sid.objectId, P60System::pool::ACU_DEVICE_3_STATUS, this);
lp_var_t<uint8_t> device4Status =
lp_var_t<uint8_t>(sid.objectId, P60System::pool::ACU_DEVICE_4_STATUS, this);
lp_var_t<uint8_t> device5Status =
lp_var_t<uint8_t>(sid.objectId, P60System::pool::ACU_DEVICE_5_STATUS, this);
lp_var_t<uint8_t> device6Status =
lp_var_t<uint8_t>(sid.objectId, P60System::pool::ACU_DEVICE_6_STATUS, this);
lp_var_t<uint8_t> device7Status =
lp_var_t<uint8_t>(sid.objectId, P60System::pool::ACU_DEVICE_7_STATUS, this);
lp_vec_t<uint8_t, 3> dacEnables =
lp_vec_t<uint8_t, 3>(sid.objectId, P60System::pool::ACU_DAC_ENABLES, this);
lp_vec_t<uint16_t, 6> dacRawChannelVals =
lp_vec_t<uint16_t, 6>(sid.objectId, P60System::pool::ACU_DAC_RAW_CHANNELS, this);
lp_var_t<uint32_t> bootCause =
lp_var_t<uint32_t>(sid.objectId, P60System::pool::ACU_BOOTCAUSE, this);
lp_var_t<uint16_t> resetCause =
lp_var_t<uint16_t>(sid.objectId, P60System::pool::ACU_RESET_CAUSE, this);
lp_var_t<uint32_t> wdtCntGnd =
lp_var_t<uint32_t>(sid.objectId, P60System::pool::ACU_WDT_CNT_GND, this);
lp_var_t<uint32_t> wdtGndLeft =
lp_var_t<uint32_t>(sid.objectId, P60System::pool::ACU_WDT_GND_LEFT, this);
/**
* There are 8 devices on the PDU. FRAM, ADCs, temperature sensor etc. Each device is
* identified by an ID. Refer also to gs-man-nanopower-p60-pdu-200-1.pdf on pages 17 and 18.
*/
lp_vec_t<uint8_t, 8> deviceTypes =
lp_vec_t<uint8_t, 8>(sid.objectId, P60System::pool::ACU_DEVICES, this);
/** The status of each device. 0 = None, 1 = Ok, 2 = Error, 3 = Not found */
lp_vec_t<uint8_t, 8> devicesStatus =
lp_vec_t<uint8_t, 8>(sid.objectId, P60System::pool::ACU_DEVICES_STATUS, this);
};
} // namespace ACU

View File

@ -7,20 +7,48 @@
#include "objects/systemObjectList.h"
namespace Max31865Definitions {
namespace MAX31865 {
enum PoolIds : lp_id_t { RTD_VALUE, TEMPERATURE_C, FAULT_BYTE };
enum class PoolIds : lp_id_t { RTD_VALUE, TEMPERATURE_C, LAST_FAULT_BYTE, FAULT_BYTE };
enum Wires : unsigned int { TWO_WIRE = 0, THREE_WIRE = 1, FOUR_WIRE = 0 };
enum ConvMode : unsigned int { NORM_OFF = 0, AUTO = 1 };
enum Bias : unsigned int { OFF = 0, ON = 1 };
enum FilterSel : unsigned int { FIFTY_HERTZ = 1, SIXTY_HERTZ = 0 };
enum CfgBitPos {
FILTER_SEL = 0,
FAULT_STATUS_CLEAR = 1,
FDCC = 2,
WIRE_SEL = 4,
ONE_SHOT = 5,
CONV_MODE = 6,
BIAS_SEL = 7
};
static constexpr uint32_t WARMUP_MS = 100;
static constexpr uint8_t WRITE_BIT = 0b10000000;
enum Regs : uint8_t {
CONFIG = 0x00,
RTD = 0x01,
HIGH_THRESHOLD = 0x03,
LOW_THRESHOLD = 0x05,
FAULT_BYTE = 0x07
};
static constexpr DeviceCommandId_t CONFIG_CMD = 0x80;
static constexpr DeviceCommandId_t WRITE_HIGH_THRESHOLD = 0x83;
static constexpr DeviceCommandId_t WRITE_LOW_THRESHOLD = 0x85;
static constexpr DeviceCommandId_t REQUEST_CONFIG = 0x00;
static constexpr DeviceCommandId_t REQUEST_RTD = 0x01;
static constexpr DeviceCommandId_t REQUEST_HIGH_THRESHOLD = 0x03;
static constexpr DeviceCommandId_t REQUEST_LOW_THRESHOLD = 0x05;
static constexpr DeviceCommandId_t REQUEST_FAULT_BYTE = 0x07;
static constexpr DeviceCommandId_t REQUEST_CONFIG = CONFIG;
static constexpr DeviceCommandId_t REQUEST_RTD = RTD;
static constexpr DeviceCommandId_t REQUEST_HIGH_THRESHOLD = HIGH_THRESHOLD;
static constexpr DeviceCommandId_t REQUEST_LOW_THRESHOLD = LOW_THRESHOLD;
static constexpr DeviceCommandId_t REQUEST_FAULT_BYTE = FAULT_BYTE;
static constexpr DeviceCommandId_t CLEAR_FAULT_BYTE = 0x08;
static constexpr uint32_t MAX31865_SET_ID = REQUEST_RTD;
@ -28,26 +56,82 @@ static constexpr uint8_t CLEAR_FAULT_BIT_VAL = 0b0000'0010;
static constexpr size_t MAX_REPLY_SIZE = 5;
class Max31865Set : public StaticLocalDataSet<sizeof(float) + sizeof(uint8_t)> {
class Max31865Set : public StaticLocalDataSet<4> {
public:
/**
* Constructor used by owner and data creators like device handlers.
* @param owner
* @param setId
*/
Max31865Set(HasLocalDataPoolIF* owner) : StaticLocalDataSet(owner, MAX31865_SET_ID) {}
Max31865Set(HasLocalDataPoolIF* owner, uint32_t setId) : StaticLocalDataSet(owner, setId) {}
/**
* Constructor used by data users like controllers.
* @param sid
*/
Max31865Set(object_id_t objectId) : StaticLocalDataSet(sid_t(objectId, MAX31865_SET_ID)) {}
Max31865Set(object_id_t objectId, uint32_t setId) : StaticLocalDataSet(sid_t(objectId, setId)) {}
lp_var_t<float> rtdValue = lp_var_t<float>(sid.objectId, PoolIds::RTD_VALUE, this);
lp_var_t<float> temperatureCelcius = lp_var_t<float>(sid.objectId, PoolIds::TEMPERATURE_C, this);
lp_var_t<uint8_t> errorByte = lp_var_t<uint8_t>(sid.objectId, PoolIds::FAULT_BYTE, this);
lp_var_t<float> rtdValue =
lp_var_t<float>(sid.objectId, static_cast<lp_id_t>(PoolIds::RTD_VALUE), this);
lp_var_t<float> temperatureCelcius =
lp_var_t<float>(sid.objectId, static_cast<lp_id_t>(PoolIds::TEMPERATURE_C), this);
lp_var_t<uint8_t> lastErrorByte =
lp_var_t<uint8_t>(sid.objectId, static_cast<lp_id_t>(PoolIds::LAST_FAULT_BYTE), this);
lp_var_t<uint8_t> errorByte =
lp_var_t<uint8_t>(sid.objectId, static_cast<lp_id_t>(PoolIds::FAULT_BYTE), this);
};
} // namespace Max31865Definitions
} // namespace MAX31865
namespace EiveMax31855 {
static constexpr float RTD_RREF_PT1000 = 4020.0; //!< Ohm
static constexpr uint8_t NUM_RTDS = 16;
enum RtdCommands : DeviceCommandId_t {
ON = 0,
EXCHANGE_SET_ID = MAX31865::REQUEST_RTD,
ACTIVE = 2,
LOW_THRESHOLD = 3,
HIGH_TRESHOLD = 4,
OFF = 5,
CFG = 6,
NUM_CMDS
};
class ReadOutStruct : public SerialLinkedListAdapter<SerializeIF> {
public:
ReadOutStruct() { setLinks(); }
ReadOutStruct(bool active, uint32_t spiErrCnt, bool faultBitSet, uint8_t faultVal,
uint16_t rtdVal)
: active(active),
adcCode(rtdVal),
faultBitSet(faultBitSet),
faultValue(faultVal),
spiErrorCount(spiErrCnt) {
setLinks();
}
//! RTD was set on and is configured, but is not periodically polled
SerializeElement<bool> configured = false;
//! RTD is active and polled periodically
SerializeElement<bool> active = false;
SerializeElement<uint16_t> adcCode = 0;
SerializeElement<bool> faultBitSet = false;
SerializeElement<uint8_t> faultValue = 0;
SerializeElement<uint32_t> spiErrorCount = 0;
private:
void setLinks() {
setStart(&configured);
configured.setNext(&active);
active.setNext(&adcCode);
adcCode.setNext(&faultBitSet);
faultBitSet.setNext(&faultValue);
faultValue.setNext(&spiErrorCount);
};
};
}; // namespace EiveMax31855
#endif /* MISSION_DEVICES_DEVICEDEFINITIONS_MAX13865DEFINITIONS_H_ */

View File

@ -61,7 +61,7 @@ static const uint8_t MAX_CMD_SIZE = 32;
static const uint8_t POOL_ENTRIES = 7;
enum Max1227PoolIds : lp_id_t { TEMPERATURE_C, CHANNEL_VEC };
enum SusPoolIds : lp_id_t { TEMPERATURE_C, CHANNEL_VEC };
class SusDataset : public StaticLocalDataSet<POOL_ENTRIES> {
public:

View File

@ -1,5 +1 @@
target_sources(${LIB_EIVE_MISSION} PRIVATE
NVMParameterBase.cpp
)
target_sources(${LIB_EIVE_MISSION} PRIVATE NVMParameterBase.cpp)

View File

@ -8,9 +8,11 @@
class SdCardMountedIF {
public:
virtual ~SdCardMountedIF(){};
virtual std::string getCurrentMountPrefix(sd::SdCard prefSdCardPtr = sd::SdCard::NONE) = 0;
virtual std::string getCurrentMountPrefix() const = 0;
virtual bool isSdCardMounted(sd::SdCard sdCard) = 0;
virtual ReturnValue_t getPreferredSdCard(sd::SdCard& sdCard) const = 0;
virtual sd::SdCard getPreferredSdCard() const = 0;
virtual void setActiveSdCard(sd::SdCard sdCard) = 0;
virtual sd::SdCard getActiveSdCard() const = 0;
private:
};

View File

@ -1,16 +1,15 @@
target_sources(${LIB_EIVE_MISSION} PRIVATE
EiveSystem.cpp
AcsSubsystem.cpp
ComSubsystem.cpp
PayloadSubsystem.cpp
AcsBoardAssembly.cpp
RwAssembly.cpp
SusAssembly.cpp
DualLanePowerStateMachine.cpp
PowerStateMachineBase.cpp
DualLaneAssemblyBase.cpp
TcsBoardAssembly.cpp
)
target_sources(
${LIB_EIVE_MISSION}
PRIVATE EiveSystem.cpp
AcsSubsystem.cpp
ComSubsystem.cpp
PayloadSubsystem.cpp
AcsBoardAssembly.cpp
RwAssembly.cpp
SusAssembly.cpp
DualLanePowerStateMachine.cpp
PowerStateMachineBase.cpp
DualLaneAssemblyBase.cpp
TcsBoardAssembly.cpp)
add_subdirectory(fdir)

View File

@ -10,7 +10,7 @@ TcsBoardAssembly::TcsBoardAssembly(object_id_t objectId, object_id_t parentId,
eventQueue = QueueFactory::instance()->createMessageQueue(24);
ModeListEntry entry;
for (uint8_t idx = 0; idx < NUMBER_RTDS; idx++) {
entry.setObject(helper.rtdIds[idx]);
entry.setObject(helper.rtdInfos[idx].first);
entry.setMode(MODE_OFF);
entry.setSubmode(SUBMODE_NONE);
entry.setInheritSubmode(false);
@ -56,7 +56,7 @@ ReturnValue_t TcsBoardAssembly::checkChildrenStateOn(Mode_t wantedMode, Submode_
int devsInWrongMode = 0;
try {
for (uint8_t idx = 0; idx < NUMBER_RTDS; idx++) {
if (childrenMap.at(helper.rtdIds[idx]).mode != wantedMode) {
if (childrenMap.at(helper.rtdInfos[idx].first).mode != wantedMode) {
devsInWrongMode++;
}
}
@ -92,8 +92,8 @@ ReturnValue_t TcsBoardAssembly::isModeCombinationValid(Mode_t mode, Submode_t su
ReturnValue_t TcsBoardAssembly::initialize() {
ReturnValue_t result = RETURN_OK;
for (const auto& obj : helper.rtdIds) {
result = registerChild(obj);
for (const auto& obj : helper.rtdInfos) {
result = registerChild(obj.first);
if (result != HasReturnvaluesIF::RETURN_OK) {
return result;
}
@ -125,8 +125,8 @@ ReturnValue_t TcsBoardAssembly::handleNormalOrOnModeCmd(Mode_t mode, Submode_t s
object_id_t objId = 0;
try {
for (uint8_t idx = 0; idx < NUMBER_RTDS; idx++) {
devMode = childrenMap.at(helper.rtdIds[idx]).mode;
objId = helper.rtdIds[idx];
devMode = childrenMap.at(helper.rtdInfos[idx].first).mode;
objId = helper.rtdInfos[idx].first;
if (mode == devMode) {
modeTable[idx].setMode(mode);
} else if (mode == DeviceHandlerIF::MODE_NORMAL) {

View File

@ -6,9 +6,10 @@
#include <fsfw/power/PowerSwitcher.h>
struct TcsBoardHelper {
TcsBoardHelper(std::array<object_id_t, 16> rtdIds) : rtdIds(rtdIds) {}
TcsBoardHelper(std::array<std::pair<object_id_t, std::string>, 16> rtdInfos)
: rtdInfos(std::move(rtdInfos)) {}
std::array<object_id_t, 16> rtdIds = {};
std::array<std::pair<object_id_t, std::string>, 16> rtdInfos = {};
};
class TcsBoardAssembly : public AssemblyBase, public ConfirmsFailuresIF {

View File

@ -1,7 +1,3 @@
target_sources(${LIB_EIVE_MISSION} PRIVATE
AcsBoardFdir.cpp
RtdFdir.cpp
SusFdir.cpp
SyrlinksFdir.cpp
GomspacePowerFdir.cpp
)
target_sources(
${LIB_EIVE_MISSION} PRIVATE AcsBoardFdir.cpp RtdFdir.cpp SusFdir.cpp
SyrlinksFdir.cpp GomspacePowerFdir.cpp)

View File

@ -3,5 +3,3 @@ target_sources(${LIB_EIVE_MISSION} PRIVATE
VirtualChannel.cpp
TmFunnel.cpp
)

View File

@ -1,3 +1,4 @@
<<<<<<< HEAD
target_sources(${LIB_EIVE_MISSION} PRIVATE
Timestamp.cpp
ProgressPrinter.cpp
@ -5,3 +6,7 @@ target_sources(${LIB_EIVE_MISSION} PRIVATE
)
=======
target_sources(${LIB_EIVE_MISSION} PRIVATE TmFunnel.cpp Timestamp.cpp
ProgressPrinter.cpp Filenaming.cpp)
>>>>>>> meier/thermal-controller-fix

View File

@ -1,5 +1,6 @@
#include "ProgressPrinter.h"
#include <cmath>
#include <iomanip>
#include "fsfw/serviceinterface/ServiceInterfaceStream.h"
@ -16,4 +17,9 @@ void ProgressPrinter::print(uint32_t currentStep) {
<< std::endl;
nextProgressPrint += percentageResolution;
}
if (nextProgressPrint - progressInPercent < 0) {
nextProgressPrint =
(std::floor(progressInPercent / percentageResolution) * percentageResolution) +
percentageResolution;
}
}