Merge remote-tracking branch 'origin/develop' into irini
All checks were successful
EIVE/eive-obsw/pipeline/head This commit looks good
All checks were successful
EIVE/eive-obsw/pipeline/head This commit looks good
This commit is contained in:
commit
563e13765d
2
.gitmodules
vendored
2
.gitmodules
vendored
@ -11,7 +11,7 @@
|
|||||||
path = thirdparty/lwgps
|
path = thirdparty/lwgps
|
||||||
url = https://github.com/rmspacefish/lwgps.git
|
url = https://github.com/rmspacefish/lwgps.git
|
||||||
[submodule "generators/fsfwgen"]
|
[submodule "generators/fsfwgen"]
|
||||||
path = generators/fsfwgen
|
path = generators/deps/fsfwgen
|
||||||
url = https://egit.irs.uni-stuttgart.de/fsfw/fsfw-gen.git
|
url = https://egit.irs.uni-stuttgart.de/fsfw/fsfw-gen.git
|
||||||
[submodule "thirdparty/arcsec_star_tracker"]
|
[submodule "thirdparty/arcsec_star_tracker"]
|
||||||
path = thirdparty/arcsec_star_tracker
|
path = thirdparty/arcsec_star_tracker
|
||||||
|
14
CHANGELOG.md
14
CHANGELOG.md
@ -10,10 +10,18 @@ list yields a list of all related PRs for each release.
|
|||||||
|
|
||||||
# [unreleased]
|
# [unreleased]
|
||||||
|
|
||||||
# [v1.12.0]
|
# [v1.12.1] 05.07.2022
|
||||||
|
|
||||||
|
- Disable periodic TCS controller HK generation by default
|
||||||
|
|
||||||
|
# [v1.12.0] 04.07.2022
|
||||||
|
|
||||||
## Added
|
## Added
|
||||||
|
|
||||||
|
- Dummy components to run OBSW without relying on external hardware
|
||||||
|
PR: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/266
|
||||||
|
- Basic Thermal Controller
|
||||||
|
PR: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/266
|
||||||
- PUS11 TC scheduler
|
- PUS11 TC scheduler
|
||||||
PR: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/259
|
PR: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/259
|
||||||
- Regular reboot command
|
- Regular reboot command
|
||||||
@ -37,6 +45,8 @@ list yields a list of all related PRs for each release.
|
|||||||
|
|
||||||
- `q7s-cp.py` bugfix
|
- `q7s-cp.py` bugfix
|
||||||
PR: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/256
|
PR: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/256
|
||||||
|
- Generator scripts output now produce platform-independent artifacts
|
||||||
|
PR: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/267
|
||||||
|
|
||||||
### Heater
|
### Heater
|
||||||
|
|
||||||
@ -48,6 +58,8 @@ list yields a list of all related PRs for each release.
|
|||||||
|
|
||||||
## Changed
|
## Changed
|
||||||
|
|
||||||
|
- CCSDS handler improvements
|
||||||
|
PR: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/268
|
||||||
- Build unittest as default side product of hosted builds
|
- Build unittest as default side product of hosted builds
|
||||||
PR: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/244
|
PR: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/244
|
||||||
- Let CI/CD build host build and run unittest side product in same step
|
- Let CI/CD build host build and run unittest side product in same step
|
||||||
|
@ -178,6 +178,7 @@ set(LIB_CXX_FS -lstdc++fs)
|
|||||||
set(LIB_CATCH2 Catch2)
|
set(LIB_CATCH2 Catch2)
|
||||||
set(LIB_GPS gps)
|
set(LIB_GPS gps)
|
||||||
set(LIB_JSON_NAME nlohmann_json::nlohmann_json)
|
set(LIB_JSON_NAME nlohmann_json::nlohmann_json)
|
||||||
|
set(LIB_DUMMIES dummies)
|
||||||
|
|
||||||
# Set path names
|
# Set path names
|
||||||
set(FSFW_PATH fsfw)
|
set(FSFW_PATH fsfw)
|
||||||
@ -185,6 +186,7 @@ set(TEST_PATH test)
|
|||||||
set(UNITTEST_PATH unittest)
|
set(UNITTEST_PATH unittest)
|
||||||
set(LINUX_PATH linux)
|
set(LINUX_PATH linux)
|
||||||
set(COMMON_PATH common)
|
set(COMMON_PATH common)
|
||||||
|
set(DUMMY_PATH dummies)
|
||||||
set(WATCHDOG_PATH watchdog)
|
set(WATCHDOG_PATH watchdog)
|
||||||
set(COMMON_CONFIG_PATH ${COMMON_PATH}/config)
|
set(COMMON_CONFIG_PATH ${COMMON_PATH}/config)
|
||||||
set(UNITTEST_CFG_PATH ${UNITTEST_PATH}/testcfg)
|
set(UNITTEST_CFG_PATH ${UNITTEST_PATH}/testcfg)
|
||||||
@ -315,6 +317,7 @@ elseif(CMAKE_CXX_COMPILER_ID STREQUAL "MSVC")
|
|||||||
endif()
|
endif()
|
||||||
|
|
||||||
add_library(${LIB_EIVE_MISSION})
|
add_library(${LIB_EIVE_MISSION})
|
||||||
|
add_library(${LIB_DUMMIES})
|
||||||
|
|
||||||
# Add main executable
|
# Add main executable
|
||||||
add_executable(${OBSW_NAME})
|
add_executable(${OBSW_NAME})
|
||||||
@ -360,6 +363,7 @@ if(ADD_CSP_LIB)
|
|||||||
endif()
|
endif()
|
||||||
|
|
||||||
add_subdirectory(${COMMON_PATH})
|
add_subdirectory(${COMMON_PATH})
|
||||||
|
add_subdirectory(${DUMMY_PATH})
|
||||||
|
|
||||||
add_subdirectory(${LIB_LWGPS_PATH})
|
add_subdirectory(${LIB_LWGPS_PATH})
|
||||||
add_subdirectory(${FSFW_PATH})
|
add_subdirectory(${FSFW_PATH})
|
||||||
@ -433,14 +437,16 @@ endif()
|
|||||||
target_link_libraries(${LIB_EIVE_MISSION}
|
target_link_libraries(${LIB_EIVE_MISSION}
|
||||||
PUBLIC ${LIB_FSFW_NAME} ${LIB_LWGPS_NAME} ${LIB_OS_NAME})
|
PUBLIC ${LIB_FSFW_NAME} ${LIB_LWGPS_NAME} ${LIB_OS_NAME})
|
||||||
|
|
||||||
target_link_libraries(${OBSW_NAME} PRIVATE ${LIB_EIVE_MISSION})
|
target_link_libraries(${LIB_DUMMIES} PUBLIC ${LIB_FSFW_NAME} ${LIB_JSON_NAME})
|
||||||
|
|
||||||
|
target_link_libraries(${OBSW_NAME} PRIVATE ${LIB_EIVE_MISSION} ${LIB_DUMMIES})
|
||||||
|
|
||||||
if(TGT_BSP MATCHES "arm/q7s")
|
if(TGT_BSP MATCHES "arm/q7s")
|
||||||
target_link_libraries(${LIB_EIVE_MISSION} PUBLIC ${LIB_GPS} ${LIB_ARCSEC})
|
target_link_libraries(${LIB_EIVE_MISSION} PUBLIC ${LIB_GPS} ${LIB_ARCSEC})
|
||||||
endif()
|
endif()
|
||||||
|
|
||||||
target_link_libraries(${UNITTEST_NAME} PRIVATE Catch2 ${LIB_EIVE_MISSION}
|
target_link_libraries(${UNITTEST_NAME} PRIVATE Catch2 ${LIB_EIVE_MISSION}
|
||||||
rapidcsv)
|
rapidcsv ${LIB_DUMMIES})
|
||||||
|
|
||||||
if(TGT_BSP MATCHES "arm/egse")
|
if(TGT_BSP MATCHES "arm/egse")
|
||||||
target_link_libraries(${OBSW_NAME} PRIVATE ${LIB_ARCSEC})
|
target_link_libraries(${OBSW_NAME} PRIVATE ${LIB_ARCSEC})
|
||||||
@ -465,6 +471,10 @@ target_include_directories(
|
|||||||
${LIB_EIVE_MISSION} PUBLIC ${CMAKE_CURRENT_SOURCE_DIR} ${FSFW_CONFIG_PATH}
|
${LIB_EIVE_MISSION} PUBLIC ${CMAKE_CURRENT_SOURCE_DIR} ${FSFW_CONFIG_PATH}
|
||||||
${CMAKE_CURRENT_BINARY_DIR} ${LIB_ARCSEC_PATH})
|
${CMAKE_CURRENT_BINARY_DIR} ${LIB_ARCSEC_PATH})
|
||||||
|
|
||||||
|
target_include_directories(
|
||||||
|
${LIB_DUMMIES} PUBLIC ${CMAKE_CURRENT_SOURCE_DIR} ${FSFW_CONFIG_PATH}
|
||||||
|
${CMAKE_CURRENT_BINARY_DIR})
|
||||||
|
|
||||||
if(TGT_BSP MATCHES "arm/q7s" OR TGT_BSP MATCHES "arm/egse")
|
if(TGT_BSP MATCHES "arm/q7s" OR TGT_BSP MATCHES "arm/egse")
|
||||||
target_include_directories(${LIB_EIVE_MISSION} PUBLIC ${ARCSEC_LIB_PATH})
|
target_include_directories(${LIB_EIVE_MISSION} PUBLIC ${ARCSEC_LIB_PATH})
|
||||||
endif()
|
endif()
|
||||||
|
@ -1,6 +1,7 @@
|
|||||||
#include "InitMission.h"
|
#include "InitMission.h"
|
||||||
|
|
||||||
#include <OBSWConfig.h>
|
#include <OBSWConfig.h>
|
||||||
|
#include <bsp_hosted/fsfwconfig/pollingsequence/DummyPst.h>
|
||||||
#include <fsfw/objectmanager/ObjectManager.h>
|
#include <fsfw/objectmanager/ObjectManager.h>
|
||||||
#include <fsfw/objectmanager/ObjectManagerIF.h>
|
#include <fsfw/objectmanager/ObjectManagerIF.h>
|
||||||
#include <fsfw/returnvalues/HasReturnvaluesIF.h>
|
#include <fsfw/returnvalues/HasReturnvaluesIF.h>
|
||||||
@ -89,9 +90,13 @@ void initmission::initTasks() {
|
|||||||
sif::error << "Object add component failed" << std::endl;
|
sif::error << "Object add component failed" << std::endl;
|
||||||
}
|
}
|
||||||
|
|
||||||
PeriodicTaskIF* pusEvents = factory->createPeriodicTask(
|
PeriodicTaskIF* eventHandling = factory->createPeriodicTask(
|
||||||
"PUS_EVENTS", 60, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc);
|
"EVENTS", 60, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc);
|
||||||
result = pusVerification->addComponent(objects::PUS_SERVICE_5_EVENT_REPORTING);
|
result = eventHandling->addComponent(objects::EVENT_MANAGER);
|
||||||
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
|
initmission::printAddObjectError("EVENT_MNGR", objects::EVENT_MANAGER);
|
||||||
|
}
|
||||||
|
result = eventHandling->addComponent(objects::PUS_SERVICE_5_EVENT_REPORTING);
|
||||||
if (result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
initmission::printAddObjectError("PUS5", objects::PUS_SERVICE_5_EVENT_REPORTING);
|
initmission::printAddObjectError("PUS5", objects::PUS_SERVICE_5_EVENT_REPORTING);
|
||||||
}
|
}
|
||||||
@ -106,6 +111,10 @@ void initmission::initTasks() {
|
|||||||
if (result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
initmission::printAddObjectError("PUS9", objects::PUS_SERVICE_9_TIME_MGMT);
|
initmission::printAddObjectError("PUS9", objects::PUS_SERVICE_9_TIME_MGMT);
|
||||||
}
|
}
|
||||||
|
result = pusHighPrio->addComponent(objects::PUS_SERVICE_3_HOUSEKEEPING);
|
||||||
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
|
initmission::printAddObjectError("PUS3", objects::PUS_SERVICE_3_HOUSEKEEPING);
|
||||||
|
}
|
||||||
|
|
||||||
PeriodicTaskIF* pusMedPrio = factory->createPeriodicTask(
|
PeriodicTaskIF* pusMedPrio = factory->createPeriodicTask(
|
||||||
"PUS_MED_PRIO", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.8, missedDeadlineFunc);
|
"PUS_MED_PRIO", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.8, missedDeadlineFunc);
|
||||||
@ -129,9 +138,34 @@ void initmission::initTasks() {
|
|||||||
initmission::printAddObjectError("PUS17", objects::PUS_SERVICE_17_TEST);
|
initmission::printAddObjectError("PUS17", objects::PUS_SERVICE_17_TEST);
|
||||||
}
|
}
|
||||||
|
|
||||||
PeriodicTaskIF* testTask = factory->createPeriodicTask(
|
PeriodicTaskIF* thermalTask = factory->createPeriodicTask(
|
||||||
"TEST_TASK", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, missedDeadlineFunc);
|
"THERMAL_CTL_TASK", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.0, missedDeadlineFunc);
|
||||||
static_cast<void>(testTask);
|
result = thermalTask->addComponent(objects::RTD_0_IC3_PLOC_HEATSPREADER);
|
||||||
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
|
initmission::printAddObjectError("RTD_0_dummy", objects::RTD_0_IC3_PLOC_HEATSPREADER);
|
||||||
|
}
|
||||||
|
result = thermalTask->addComponent(objects::SUS_0_N_LOC_XFYFZM_PT_XF);
|
||||||
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
|
initmission::printAddObjectError("SUS_0_dummy", objects::SUS_0_N_LOC_XFYFZM_PT_XF);
|
||||||
|
}
|
||||||
|
|
||||||
|
result = thermalTask->addComponent(objects::CORE_CONTROLLER);
|
||||||
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
|
initmission::printAddObjectError("Core controller dummy", objects::CORE_CONTROLLER);
|
||||||
|
}
|
||||||
|
|
||||||
|
result = thermalTask->addComponent(objects::THERMAL_CONTROLLER);
|
||||||
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
|
initmission::printAddObjectError("THERMAL_CONTROLLER", objects::THERMAL_CONTROLLER);
|
||||||
|
}
|
||||||
|
|
||||||
|
FixedTimeslotTaskIF* pstTask = factory->createFixedTimeslotTask(
|
||||||
|
"DUMMY_PST", 75, PeriodicTaskIF::MINIMUM_STACK_SIZE * 4, 0.5, missedDeadlineFunc);
|
||||||
|
result = dummy_pst::pst(pstTask);
|
||||||
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
|
sif::error << "Failed to add dummy pst to fixed timeslot task" << std::endl;
|
||||||
|
}
|
||||||
|
|
||||||
#if OBSW_ADD_TEST_CODE == 1
|
#if OBSW_ADD_TEST_CODE == 1
|
||||||
result = testTask->addComponent(objects::TEST_TASK);
|
result = testTask->addComponent(objects::TEST_TASK);
|
||||||
if (result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
@ -145,11 +179,14 @@ void initmission::initTasks() {
|
|||||||
tmtcPollingTask->startTask();
|
tmtcPollingTask->startTask();
|
||||||
|
|
||||||
pusVerification->startTask();
|
pusVerification->startTask();
|
||||||
pusEvents->startTask();
|
eventHandling->startTask();
|
||||||
pusHighPrio->startTask();
|
pusHighPrio->startTask();
|
||||||
pusMedPrio->startTask();
|
pusMedPrio->startTask();
|
||||||
pusLowPrio->startTask();
|
pusLowPrio->startTask();
|
||||||
|
|
||||||
|
pstTask->startTask();
|
||||||
|
thermalTask->startTask();
|
||||||
|
|
||||||
#if OBSW_ADD_TEST_CODE == 1
|
#if OBSW_ADD_TEST_CODE == 1
|
||||||
testTask->startTask();
|
testTask->startTask();
|
||||||
#endif /* OBSW_ADD_TEST_CODE == 1 */
|
#endif /* OBSW_ADD_TEST_CODE == 1 */
|
||||||
|
@ -2,8 +2,9 @@
|
|||||||
|
|
||||||
#include <fsfw/tmtcservices/CommandingServiceBase.h>
|
#include <fsfw/tmtcservices/CommandingServiceBase.h>
|
||||||
#include <fsfw/tmtcservices/PusServiceBase.h>
|
#include <fsfw/tmtcservices/PusServiceBase.h>
|
||||||
|
#include <mission/controller/ThermalController.h>
|
||||||
#include <mission/core/GenericFactory.h>
|
#include <mission/core/GenericFactory.h>
|
||||||
#include <mission/utility/TmFunnel.h>
|
#include <mission/tmtc/TmFunnel.h>
|
||||||
#include <objects/systemObjectList.h>
|
#include <objects/systemObjectList.h>
|
||||||
#include <tmtc/apid.h>
|
#include <tmtc/apid.h>
|
||||||
#include <tmtc/pusIds.h>
|
#include <tmtc/pusIds.h>
|
||||||
@ -25,6 +26,24 @@
|
|||||||
#include <test/testtasks/TestTask.h>
|
#include <test/testtasks/TestTask.h>
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#include <dummies/AcuDummy.h>
|
||||||
|
#include <dummies/BpxDummy.h>
|
||||||
|
#include <dummies/ComCookieDummy.h>
|
||||||
|
#include <dummies/ComIFDummy.h>
|
||||||
|
#include <dummies/CoreControllerDummy.h>
|
||||||
|
#include <dummies/GyroAdisDummy.h>
|
||||||
|
#include <dummies/GyroL3GD20Dummy.h>
|
||||||
|
#include <dummies/ImtqDummy.h>
|
||||||
|
#include <dummies/MgmLIS3MDLDummy.h>
|
||||||
|
#include <dummies/P60DockDummy.h>
|
||||||
|
#include <dummies/PduDummy.h>
|
||||||
|
#include <dummies/PlPcduDummy.h>
|
||||||
|
#include <dummies/RwDummy.h>
|
||||||
|
#include <dummies/StarTrackerDummy.h>
|
||||||
|
#include <dummies/SusDummy.h>
|
||||||
|
#include <dummies/SyrlinksDummy.h>
|
||||||
|
#include <dummies/TemperatureSensorsDummy.h>
|
||||||
|
|
||||||
void Factory::setStaticFrameworkObjectIds() {
|
void Factory::setStaticFrameworkObjectIds() {
|
||||||
PusServiceBase::packetSource = objects::PUS_PACKET_DISTRIBUTOR;
|
PusServiceBase::packetSource = objects::PUS_PACKET_DISTRIBUTOR;
|
||||||
PusServiceBase::packetDestination = objects::TM_FUNNEL;
|
PusServiceBase::packetDestination = objects::TM_FUNNEL;
|
||||||
@ -44,5 +63,31 @@ void ObjectFactory::produce(void* args) {
|
|||||||
Factory::setStaticFrameworkObjectIds();
|
Factory::setStaticFrameworkObjectIds();
|
||||||
ObjectFactory::produceGenericObjects();
|
ObjectFactory::produceGenericObjects();
|
||||||
|
|
||||||
new TestTask(objects::TEST_TASK);
|
new ComIFDummy(objects::DUMMY_COM_IF);
|
||||||
|
ComCookieDummy* comCookieDummy = new ComCookieDummy();
|
||||||
|
new BpxDummy(objects::BPX_BATT_HANDLER, objects::DUMMY_COM_IF, comCookieDummy);
|
||||||
|
new CoreControllerDummy(objects::CORE_CONTROLLER);
|
||||||
|
new RwDummy(objects::RW1, objects::DUMMY_COM_IF, comCookieDummy);
|
||||||
|
new RwDummy(objects::RW2, objects::DUMMY_COM_IF, comCookieDummy);
|
||||||
|
new RwDummy(objects::RW3, objects::DUMMY_COM_IF, comCookieDummy);
|
||||||
|
new RwDummy(objects::RW4, objects::DUMMY_COM_IF, comCookieDummy);
|
||||||
|
new StarTrackerDummy(objects::STAR_TRACKER, objects::DUMMY_COM_IF, comCookieDummy);
|
||||||
|
new SyrlinksDummy(objects::SYRLINKS_HK_HANDLER, objects::DUMMY_COM_IF, comCookieDummy);
|
||||||
|
new ImtqDummy(objects::IMTQ_HANDLER, objects::DUMMY_COM_IF, comCookieDummy);
|
||||||
|
new AcuDummy(objects::ACU_HANDLER, objects::DUMMY_COM_IF, comCookieDummy);
|
||||||
|
new PduDummy(objects::PDU1_HANDLER, objects::DUMMY_COM_IF, comCookieDummy);
|
||||||
|
new PduDummy(objects::PDU2_HANDLER, objects::DUMMY_COM_IF, comCookieDummy);
|
||||||
|
new P60DockDummy(objects::P60DOCK_HANDLER, objects::DUMMY_COM_IF, comCookieDummy);
|
||||||
|
new GyroAdisDummy(objects::GYRO_0_ADIS_HANDLER, objects::DUMMY_COM_IF, comCookieDummy);
|
||||||
|
new GyroL3GD20Dummy(objects::GYRO_1_L3G_HANDLER, objects::DUMMY_COM_IF, comCookieDummy);
|
||||||
|
new GyroAdisDummy(objects::GYRO_2_ADIS_HANDLER, objects::DUMMY_COM_IF, comCookieDummy);
|
||||||
|
new GyroL3GD20Dummy(objects::GYRO_3_L3G_HANDLER, objects::DUMMY_COM_IF, comCookieDummy);
|
||||||
|
new MgmLIS3MDLDummy(objects::MGM_0_LIS3_HANDLER, objects::DUMMY_COM_IF, comCookieDummy);
|
||||||
|
new MgmLIS3MDLDummy(objects::MGM_2_LIS3_HANDLER, objects::DUMMY_COM_IF, comCookieDummy);
|
||||||
|
new PlPcduDummy(objects::PLPCDU_HANDLER, objects::DUMMY_COM_IF, comCookieDummy);
|
||||||
|
new TemperatureSensorsDummy();
|
||||||
|
new SusDummy();
|
||||||
|
new ThermalController(objects::THERMAL_CONTROLLER, objects::NO_OBJECT);
|
||||||
|
|
||||||
|
// new TestTask(objects::TEST_TASK);
|
||||||
}
|
}
|
||||||
|
@ -1 +1 @@
|
|||||||
target_sources(${TARGET_NAME} PUBLIC ArduinoComIF.cpp ArduinoCookie.cpp)
|
target_sources(${OBSW_NAME} PUBLIC ArduinoComIF.cpp ArduinoCookie.cpp)
|
||||||
|
@ -13,3 +13,5 @@ if(EXISTS "${CMAKE_CURRENT_SOURCE_DIR}/objects/translateObjects.cpp")
|
|||||||
target_sources(${OBSW_NAME} PRIVATE events/translateEvents.cpp)
|
target_sources(${OBSW_NAME} PRIVATE events/translateEvents.cpp)
|
||||||
target_sources(${UNITTEST_NAME} PRIVATE events/translateEvents.cpp)
|
target_sources(${UNITTEST_NAME} PRIVATE events/translateEvents.cpp)
|
||||||
endif()
|
endif()
|
||||||
|
|
||||||
|
add_subdirectory(pollingsequence)
|
||||||
|
@ -31,8 +31,8 @@
|
|||||||
#if FSFW_OBJ_EVENT_TRANSLATION == 1
|
#if FSFW_OBJ_EVENT_TRANSLATION == 1
|
||||||
//! Specify whether info events are printed too.
|
//! Specify whether info events are printed too.
|
||||||
#define FSFW_DEBUG_INFO 1
|
#define FSFW_DEBUG_INFO 1
|
||||||
#include "objects/translateObjects.h"
|
|
||||||
#include "events/translateEvents.h"
|
#include "events/translateEvents.h"
|
||||||
|
#include "objects/translateObjects.h"
|
||||||
#else
|
#else
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@ -70,6 +70,6 @@ static constexpr size_t FSFW_PRINT_BUFFER_SIZE = 124;
|
|||||||
|
|
||||||
static constexpr size_t FSFW_MAX_TM_PACKET_SIZE = 2048;
|
static constexpr size_t FSFW_MAX_TM_PACKET_SIZE = 2048;
|
||||||
|
|
||||||
}
|
} // namespace fsfwconfig
|
||||||
|
|
||||||
#endif /* CONFIG_FSFWCONFIG_H_ */
|
#endif /* CONFIG_FSFWCONFIG_H_ */
|
||||||
|
@ -22,10 +22,11 @@ enum sourceObjects : uint32_t {
|
|||||||
|
|
||||||
TEST_TASK = 0x42694269,
|
TEST_TASK = 0x42694269,
|
||||||
DUMMY_INTERFACE = 0xCAFECAFE,
|
DUMMY_INTERFACE = 0xCAFECAFE,
|
||||||
DUMMY_HANDLER = 0x4400AFFE,
|
DUMMY_HANDLER = 0x44000001,
|
||||||
|
|
||||||
/* 0x49 ('I') for Communication Interfaces **/
|
/* 0x49 ('I') for Communication Interfaces **/
|
||||||
ARDUINO_COM_IF = 0x49000001
|
ARDUINO_COM_IF = 0x49000001,
|
||||||
|
|
||||||
|
DUMMY_COM_IF = 0x49000002
|
||||||
};
|
};
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -6,6 +6,8 @@
|
|||||||
*/
|
*/
|
||||||
#include "translateObjects.h"
|
#include "translateObjects.h"
|
||||||
|
|
||||||
|
#include "systemObjectList.h"
|
||||||
|
|
||||||
const char *TEST_TASK_STRING = "TEST_TASK";
|
const char *TEST_TASK_STRING = "TEST_TASK";
|
||||||
const char *DUMMY_HANDLER_STRING = "DUMMY_HANDLER";
|
const char *DUMMY_HANDLER_STRING = "DUMMY_HANDLER";
|
||||||
const char *ARDUINO_COM_IF_STRING = "ARDUINO_COM_IF";
|
const char *ARDUINO_COM_IF_STRING = "ARDUINO_COM_IF";
|
||||||
@ -36,6 +38,7 @@ const char *IPC_STORE_STRING = "IPC_STORE";
|
|||||||
const char *TIME_STAMPER_STRING = "TIME_STAMPER";
|
const char *TIME_STAMPER_STRING = "TIME_STAMPER";
|
||||||
const char *FSFW_OBJECTS_END_STRING = "FSFW_OBJECTS_END";
|
const char *FSFW_OBJECTS_END_STRING = "FSFW_OBJECTS_END";
|
||||||
const char *DUMMY_INTERFACE_STRING = "DUMMY_INTERFACE";
|
const char *DUMMY_INTERFACE_STRING = "DUMMY_INTERFACE";
|
||||||
|
const char *THERMAL_CONTROLLER_STRING = "THERMAL_CONTROLLER";
|
||||||
const char *NO_OBJECT_STRING = "NO_OBJECT";
|
const char *NO_OBJECT_STRING = "NO_OBJECT";
|
||||||
|
|
||||||
const char *translateObject(object_id_t object) {
|
const char *translateObject(object_id_t object) {
|
||||||
@ -100,6 +103,8 @@ const char *translateObject(object_id_t object) {
|
|||||||
return FSFW_OBJECTS_END_STRING;
|
return FSFW_OBJECTS_END_STRING;
|
||||||
case 0xCAFECAFE:
|
case 0xCAFECAFE:
|
||||||
return DUMMY_INTERFACE_STRING;
|
return DUMMY_INTERFACE_STRING;
|
||||||
|
case objects::THERMAL_CONTROLLER:
|
||||||
|
return THERMAL_CONTROLLER_STRING;
|
||||||
case 0xFFFFFFFF:
|
case 0xFFFFFFFF:
|
||||||
return NO_OBJECT_STRING;
|
return NO_OBJECT_STRING;
|
||||||
default:
|
default:
|
||||||
|
1
bsp_hosted/fsfwconfig/pollingsequence/CMakeLists.txt
Normal file
1
bsp_hosted/fsfwconfig/pollingsequence/CMakeLists.txt
Normal file
@ -0,0 +1 @@
|
|||||||
|
target_sources(${OBSW_NAME} PRIVATE DummyPst.cpp)
|
140
bsp_hosted/fsfwconfig/pollingsequence/DummyPst.cpp
Normal file
140
bsp_hosted/fsfwconfig/pollingsequence/DummyPst.cpp
Normal file
@ -0,0 +1,140 @@
|
|||||||
|
#include "DummyPst.h"
|
||||||
|
|
||||||
|
#include <fsfw/devicehandlers/DeviceHandlerIF.h>
|
||||||
|
#include <fsfw/serviceinterface/ServiceInterfaceStream.h>
|
||||||
|
#include <fsfw/tasks/FixedTimeslotTaskIF.h>
|
||||||
|
#include <objects/systemObjectList.h>
|
||||||
|
|
||||||
|
ReturnValue_t dummy_pst::pst(FixedTimeslotTaskIF *thisSequence) {
|
||||||
|
uint32_t length = thisSequence->getPeriodMs();
|
||||||
|
|
||||||
|
thisSequence->addSlot(objects::BPX_BATT_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
|
||||||
|
thisSequence->addSlot(objects::BPX_BATT_HANDLER, length * 0, DeviceHandlerIF::SEND_WRITE);
|
||||||
|
thisSequence->addSlot(objects::BPX_BATT_HANDLER, length * 0, DeviceHandlerIF::GET_WRITE);
|
||||||
|
thisSequence->addSlot(objects::BPX_BATT_HANDLER, length * 0, DeviceHandlerIF::SEND_READ);
|
||||||
|
thisSequence->addSlot(objects::BPX_BATT_HANDLER, length * 0, DeviceHandlerIF::GET_READ);
|
||||||
|
|
||||||
|
thisSequence->addSlot(objects::RW1, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
|
||||||
|
thisSequence->addSlot(objects::RW1, length * 0, DeviceHandlerIF::SEND_WRITE);
|
||||||
|
thisSequence->addSlot(objects::RW1, length * 0, DeviceHandlerIF::GET_WRITE);
|
||||||
|
thisSequence->addSlot(objects::RW1, length * 0, DeviceHandlerIF::SEND_READ);
|
||||||
|
thisSequence->addSlot(objects::RW1, length * 0, DeviceHandlerIF::GET_READ);
|
||||||
|
|
||||||
|
thisSequence->addSlot(objects::RW2, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
|
||||||
|
thisSequence->addSlot(objects::RW2, length * 0, DeviceHandlerIF::SEND_WRITE);
|
||||||
|
thisSequence->addSlot(objects::RW2, length * 0, DeviceHandlerIF::GET_WRITE);
|
||||||
|
thisSequence->addSlot(objects::RW2, length * 0, DeviceHandlerIF::SEND_READ);
|
||||||
|
thisSequence->addSlot(objects::RW2, length * 0, DeviceHandlerIF::GET_READ);
|
||||||
|
|
||||||
|
thisSequence->addSlot(objects::RW3, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
|
||||||
|
thisSequence->addSlot(objects::RW3, length * 0, DeviceHandlerIF::SEND_WRITE);
|
||||||
|
thisSequence->addSlot(objects::RW3, length * 0, DeviceHandlerIF::GET_WRITE);
|
||||||
|
thisSequence->addSlot(objects::RW3, length * 0, DeviceHandlerIF::SEND_READ);
|
||||||
|
thisSequence->addSlot(objects::RW3, length * 0, DeviceHandlerIF::GET_READ);
|
||||||
|
|
||||||
|
thisSequence->addSlot(objects::RW4, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
|
||||||
|
thisSequence->addSlot(objects::RW4, length * 0, DeviceHandlerIF::SEND_WRITE);
|
||||||
|
thisSequence->addSlot(objects::RW4, length * 0, DeviceHandlerIF::GET_WRITE);
|
||||||
|
thisSequence->addSlot(objects::RW4, length * 0, DeviceHandlerIF::SEND_READ);
|
||||||
|
thisSequence->addSlot(objects::RW4, length * 0, DeviceHandlerIF::GET_READ);
|
||||||
|
|
||||||
|
thisSequence->addSlot(objects::STAR_TRACKER, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
|
||||||
|
thisSequence->addSlot(objects::STAR_TRACKER, length * 0, DeviceHandlerIF::SEND_WRITE);
|
||||||
|
thisSequence->addSlot(objects::STAR_TRACKER, length * 0, DeviceHandlerIF::GET_WRITE);
|
||||||
|
thisSequence->addSlot(objects::STAR_TRACKER, length * 0, DeviceHandlerIF::SEND_READ);
|
||||||
|
thisSequence->addSlot(objects::STAR_TRACKER, length * 0, DeviceHandlerIF::GET_READ);
|
||||||
|
|
||||||
|
thisSequence->addSlot(objects::SYRLINKS_HK_HANDLER, length * 0,
|
||||||
|
DeviceHandlerIF::PERFORM_OPERATION);
|
||||||
|
thisSequence->addSlot(objects::SYRLINKS_HK_HANDLER, length * 0, DeviceHandlerIF::SEND_WRITE);
|
||||||
|
thisSequence->addSlot(objects::SYRLINKS_HK_HANDLER, length * 0, DeviceHandlerIF::GET_WRITE);
|
||||||
|
thisSequence->addSlot(objects::SYRLINKS_HK_HANDLER, length * 0, DeviceHandlerIF::SEND_READ);
|
||||||
|
thisSequence->addSlot(objects::SYRLINKS_HK_HANDLER, length * 0, DeviceHandlerIF::GET_READ);
|
||||||
|
|
||||||
|
thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
|
||||||
|
thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0, DeviceHandlerIF::SEND_WRITE);
|
||||||
|
thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0, DeviceHandlerIF::GET_WRITE);
|
||||||
|
thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0, DeviceHandlerIF::SEND_READ);
|
||||||
|
thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0, DeviceHandlerIF::GET_READ);
|
||||||
|
|
||||||
|
thisSequence->addSlot(objects::ACU_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
|
||||||
|
thisSequence->addSlot(objects::ACU_HANDLER, length * 0, DeviceHandlerIF::SEND_WRITE);
|
||||||
|
thisSequence->addSlot(objects::ACU_HANDLER, length * 0, DeviceHandlerIF::GET_WRITE);
|
||||||
|
thisSequence->addSlot(objects::ACU_HANDLER, length * 0, DeviceHandlerIF::SEND_READ);
|
||||||
|
thisSequence->addSlot(objects::ACU_HANDLER, length * 0, DeviceHandlerIF::GET_READ);
|
||||||
|
|
||||||
|
thisSequence->addSlot(objects::PDU1_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
|
||||||
|
thisSequence->addSlot(objects::PDU1_HANDLER, length * 0, DeviceHandlerIF::SEND_WRITE);
|
||||||
|
thisSequence->addSlot(objects::PDU1_HANDLER, length * 0, DeviceHandlerIF::GET_WRITE);
|
||||||
|
thisSequence->addSlot(objects::PDU1_HANDLER, length * 0, DeviceHandlerIF::SEND_READ);
|
||||||
|
thisSequence->addSlot(objects::PDU1_HANDLER, length * 0, DeviceHandlerIF::GET_READ);
|
||||||
|
|
||||||
|
thisSequence->addSlot(objects::PDU2_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
|
||||||
|
thisSequence->addSlot(objects::PDU2_HANDLER, length * 0, DeviceHandlerIF::SEND_WRITE);
|
||||||
|
thisSequence->addSlot(objects::PDU2_HANDLER, length * 0, DeviceHandlerIF::GET_WRITE);
|
||||||
|
thisSequence->addSlot(objects::PDU2_HANDLER, length * 0, DeviceHandlerIF::SEND_READ);
|
||||||
|
thisSequence->addSlot(objects::PDU2_HANDLER, length * 0, DeviceHandlerIF::GET_READ);
|
||||||
|
|
||||||
|
thisSequence->addSlot(objects::P60DOCK_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
|
||||||
|
thisSequence->addSlot(objects::P60DOCK_HANDLER, length * 0, DeviceHandlerIF::SEND_WRITE);
|
||||||
|
thisSequence->addSlot(objects::P60DOCK_HANDLER, length * 0, DeviceHandlerIF::GET_WRITE);
|
||||||
|
thisSequence->addSlot(objects::P60DOCK_HANDLER, length * 0, DeviceHandlerIF::SEND_READ);
|
||||||
|
thisSequence->addSlot(objects::P60DOCK_HANDLER, length * 0, DeviceHandlerIF::GET_READ);
|
||||||
|
|
||||||
|
thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, length * 0,
|
||||||
|
DeviceHandlerIF::PERFORM_OPERATION);
|
||||||
|
thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, length * 0, DeviceHandlerIF::SEND_WRITE);
|
||||||
|
thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, length * 0, DeviceHandlerIF::GET_WRITE);
|
||||||
|
thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, length * 0, DeviceHandlerIF::SEND_READ);
|
||||||
|
thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, length * 0, DeviceHandlerIF::GET_READ);
|
||||||
|
|
||||||
|
thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0,
|
||||||
|
DeviceHandlerIF::PERFORM_OPERATION);
|
||||||
|
thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0, DeviceHandlerIF::SEND_WRITE);
|
||||||
|
thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0, DeviceHandlerIF::GET_WRITE);
|
||||||
|
thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0, DeviceHandlerIF::SEND_READ);
|
||||||
|
thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0, DeviceHandlerIF::GET_READ);
|
||||||
|
|
||||||
|
thisSequence->addSlot(objects::GYRO_2_ADIS_HANDLER, length * 0,
|
||||||
|
DeviceHandlerIF::PERFORM_OPERATION);
|
||||||
|
thisSequence->addSlot(objects::GYRO_2_ADIS_HANDLER, length * 0, DeviceHandlerIF::SEND_WRITE);
|
||||||
|
thisSequence->addSlot(objects::GYRO_2_ADIS_HANDLER, length * 0, DeviceHandlerIF::GET_WRITE);
|
||||||
|
thisSequence->addSlot(objects::GYRO_2_ADIS_HANDLER, length * 0, DeviceHandlerIF::SEND_READ);
|
||||||
|
thisSequence->addSlot(objects::GYRO_2_ADIS_HANDLER, length * 0, DeviceHandlerIF::GET_READ);
|
||||||
|
|
||||||
|
thisSequence->addSlot(objects::GYRO_3_L3G_HANDLER, length * 0,
|
||||||
|
DeviceHandlerIF::PERFORM_OPERATION);
|
||||||
|
thisSequence->addSlot(objects::GYRO_3_L3G_HANDLER, length * 0, DeviceHandlerIF::SEND_WRITE);
|
||||||
|
thisSequence->addSlot(objects::GYRO_3_L3G_HANDLER, length * 0, DeviceHandlerIF::GET_WRITE);
|
||||||
|
thisSequence->addSlot(objects::GYRO_3_L3G_HANDLER, length * 0, DeviceHandlerIF::SEND_READ);
|
||||||
|
thisSequence->addSlot(objects::GYRO_3_L3G_HANDLER, length * 0, DeviceHandlerIF::GET_READ);
|
||||||
|
|
||||||
|
thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0,
|
||||||
|
DeviceHandlerIF::PERFORM_OPERATION);
|
||||||
|
thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0, DeviceHandlerIF::SEND_WRITE);
|
||||||
|
thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0, DeviceHandlerIF::GET_WRITE);
|
||||||
|
thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0, DeviceHandlerIF::SEND_READ);
|
||||||
|
thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0, DeviceHandlerIF::GET_READ);
|
||||||
|
|
||||||
|
thisSequence->addSlot(objects::MGM_2_LIS3_HANDLER, length * 0,
|
||||||
|
DeviceHandlerIF::PERFORM_OPERATION);
|
||||||
|
thisSequence->addSlot(objects::MGM_2_LIS3_HANDLER, length * 0, DeviceHandlerIF::SEND_WRITE);
|
||||||
|
thisSequence->addSlot(objects::MGM_2_LIS3_HANDLER, length * 0, DeviceHandlerIF::GET_WRITE);
|
||||||
|
thisSequence->addSlot(objects::MGM_2_LIS3_HANDLER, length * 0, DeviceHandlerIF::SEND_READ);
|
||||||
|
thisSequence->addSlot(objects::MGM_2_LIS3_HANDLER, length * 0, DeviceHandlerIF::GET_READ);
|
||||||
|
|
||||||
|
thisSequence->addSlot(objects::PLPCDU_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
|
||||||
|
thisSequence->addSlot(objects::PLPCDU_HANDLER, length * 0, DeviceHandlerIF::SEND_WRITE);
|
||||||
|
thisSequence->addSlot(objects::PLPCDU_HANDLER, length * 0, DeviceHandlerIF::GET_WRITE);
|
||||||
|
thisSequence->addSlot(objects::PLPCDU_HANDLER, length * 0, DeviceHandlerIF::SEND_READ);
|
||||||
|
thisSequence->addSlot(objects::PLPCDU_HANDLER, length * 0, DeviceHandlerIF::GET_READ);
|
||||||
|
|
||||||
|
if (thisSequence->checkSequence() == HasReturnvaluesIF::RETURN_OK) {
|
||||||
|
return HasReturnvaluesIF::RETURN_OK;
|
||||||
|
} else {
|
||||||
|
#if FSFW_CPP_OSTREAM_ENABLED == 1
|
||||||
|
sif::error << "pst::pollingSequenceInitDefault: Sequence invalid!" << std::endl;
|
||||||
|
#endif
|
||||||
|
return HasReturnvaluesIF::RETURN_FAILED;
|
||||||
|
}
|
||||||
|
}
|
14
bsp_hosted/fsfwconfig/pollingsequence/DummyPst.h
Normal file
14
bsp_hosted/fsfwconfig/pollingsequence/DummyPst.h
Normal file
@ -0,0 +1,14 @@
|
|||||||
|
#ifndef POLLINGSEQUENCEFACTORY_H_
|
||||||
|
#define POLLINGSEQUENCEFACTORY_H_
|
||||||
|
|
||||||
|
#include <fsfw/returnvalues/HasReturnvaluesIF.h>
|
||||||
|
|
||||||
|
class FixedTimeslotTaskIF;
|
||||||
|
|
||||||
|
namespace dummy_pst {
|
||||||
|
|
||||||
|
ReturnValue_t pst(FixedTimeslotTaskIF *thisSequence);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif /* POLLINGSEQUENCEINIT_H_ */
|
@ -1,9 +1,17 @@
|
|||||||
|
#include <objects/systemObjectList.h>
|
||||||
|
|
||||||
#include <iostream>
|
#include <iostream>
|
||||||
|
|
||||||
#include "InitMission.h"
|
#include "InitMission.h"
|
||||||
#include "commonConfig.h"
|
#include "commonConfig.h"
|
||||||
#include "fsfw/FSFWVersion.h"
|
#include "fsfw/FSFWVersion.h"
|
||||||
|
#include "fsfw/controller/ControllerBase.h"
|
||||||
|
#include "fsfw/ipc/QueueFactory.h"
|
||||||
|
#include "fsfw/modes/HasModesIF.h"
|
||||||
|
#include "fsfw/modes/ModeMessage.h"
|
||||||
|
#include "fsfw/objectmanager/ObjectManager.h"
|
||||||
#include "fsfw/tasks/TaskFactory.h"
|
#include "fsfw/tasks/TaskFactory.h"
|
||||||
|
|
||||||
#ifdef WIN32
|
#ifdef WIN32
|
||||||
static const char* COMPILE_PRINTOUT = "Windows";
|
static const char* COMPILE_PRINTOUT = "Windows";
|
||||||
#elif LINUX
|
#elif LINUX
|
||||||
|
@ -17,9 +17,9 @@ static constexpr char UART_SYRLINKS_DEV[] = "/dev/ul-syrlinks";
|
|||||||
static constexpr char UART_STAR_TRACKER_DEV[] = "/dev/ul-str";
|
static constexpr char UART_STAR_TRACKER_DEV[] = "/dev/ul-str";
|
||||||
|
|
||||||
static constexpr char UIO_PDEC_REGISTERS[] = "/dev/uio0";
|
static constexpr char UIO_PDEC_REGISTERS[] = "/dev/uio0";
|
||||||
|
static constexpr char UIO_PTME[] = "/dev/uio1";
|
||||||
static constexpr char UIO_PDEC_CONFIG_MEMORY[] = "/dev/uio2";
|
static constexpr char UIO_PDEC_CONFIG_MEMORY[] = "/dev/uio2";
|
||||||
static constexpr char UIO_PDEC_RAM[] = "/dev/uio3";
|
static constexpr char UIO_PDEC_RAM[] = "/dev/uio3";
|
||||||
static constexpr char UIO_PTME[] = "/dev/uio1";
|
|
||||||
static constexpr int MAP_ID_PTME_CONFIG = 3;
|
static constexpr int MAP_ID_PTME_CONFIG = 3;
|
||||||
|
|
||||||
namespace uiomapids {
|
namespace uiomapids {
|
||||||
|
@ -155,6 +155,7 @@ void initmission::initTasks() {
|
|||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if OBSW_ADD_RTD_DEVICES == 1
|
||||||
PeriodicTaskIF* tcsPollingTask = factory->createPeriodicTask(
|
PeriodicTaskIF* tcsPollingTask = factory->createPeriodicTask(
|
||||||
"TCS_POLLING_TASK", 70, PeriodicTaskIF::MINIMUM_STACK_SIZE * 2, 0.5, missedDeadlineFunc);
|
"TCS_POLLING_TASK", 70, PeriodicTaskIF::MINIMUM_STACK_SIZE * 2, 0.5, missedDeadlineFunc);
|
||||||
result = tcsPollingTask->addComponent(objects::SPI_RTD_COM_IF);
|
result = tcsPollingTask->addComponent(objects::SPI_RTD_COM_IF);
|
||||||
@ -181,8 +182,8 @@ void initmission::initTasks() {
|
|||||||
objects::RTD_14_IC17_TCS_BOARD,
|
objects::RTD_14_IC17_TCS_BOARD,
|
||||||
objects::RTD_15_IC18_IMTQ,
|
objects::RTD_15_IC18_IMTQ,
|
||||||
};
|
};
|
||||||
#if OBSW_ADD_RTD_DEVICES == 1
|
|
||||||
tcsTask->addComponent(objects::TCS_BOARD_ASS);
|
tcsTask->addComponent(objects::TCS_BOARD_ASS);
|
||||||
|
tcsTask->addComponent(objects::THERMAL_CONTROLLER);
|
||||||
for (const auto& rtd : rtdIds) {
|
for (const auto& rtd : rtdIds) {
|
||||||
tcsTask->addComponent(rtd, DeviceHandlerIF::PERFORM_OPERATION);
|
tcsTask->addComponent(rtd, DeviceHandlerIF::PERFORM_OPERATION);
|
||||||
tcsTask->addComponent(rtd, DeviceHandlerIF::SEND_WRITE);
|
tcsTask->addComponent(rtd, DeviceHandlerIF::SEND_WRITE);
|
||||||
@ -287,10 +288,14 @@ void initmission::initTasks() {
|
|||||||
strHelperTask->startTask();
|
strHelperTask->startTask();
|
||||||
#endif /* OBSW_ADD_STAR_TRACKER == 1 */
|
#endif /* OBSW_ADD_STAR_TRACKER == 1 */
|
||||||
|
|
||||||
|
#if OBSW_ADD_ACS_HANDLERS == 1
|
||||||
acsTask->startTask();
|
acsTask->startTask();
|
||||||
|
#endif /* OBSW_ADD_ACS_HANDLERS == 1 */
|
||||||
sysTask->startTask();
|
sysTask->startTask();
|
||||||
|
#if OBSW_ADD_RTD_DEVICES == 1
|
||||||
tcsPollingTask->startTask();
|
tcsPollingTask->startTask();
|
||||||
tcsTask->startTask();
|
tcsTask->startTask();
|
||||||
|
#endif /* OBSW_ADD_RTD_DEVICES == 1 */
|
||||||
#if OBSW_ADD_PLOC_SUPERVISOR == 1
|
#if OBSW_ADD_PLOC_SUPERVISOR == 1
|
||||||
supvHelperTask->startTask();
|
supvHelperTask->startTask();
|
||||||
#endif /* OBSW_ADD_PLOC_SUPERVISOR == 1 */
|
#endif /* OBSW_ADD_PLOC_SUPERVISOR == 1 */
|
||||||
|
@ -6,7 +6,6 @@
|
|||||||
#include "bsp_q7s/callbacks/pcduSwitchCb.h"
|
#include "bsp_q7s/callbacks/pcduSwitchCb.h"
|
||||||
#include "bsp_q7s/callbacks/q7sGpioCallbacks.h"
|
#include "bsp_q7s/callbacks/q7sGpioCallbacks.h"
|
||||||
#include "bsp_q7s/callbacks/rwSpiCallback.h"
|
#include "bsp_q7s/callbacks/rwSpiCallback.h"
|
||||||
#include "bsp_q7s/core/CoreController.h"
|
|
||||||
#include "bsp_q7s/memory/FileSystemHandler.h"
|
#include "bsp_q7s/memory/FileSystemHandler.h"
|
||||||
#include "busConf.h"
|
#include "busConf.h"
|
||||||
#include "ccsdsConfig.h"
|
#include "ccsdsConfig.h"
|
||||||
@ -90,8 +89,8 @@
|
|||||||
#include "mission/devices/devicedefinitions/payloadPcduDefinitions.h"
|
#include "mission/devices/devicedefinitions/payloadPcduDefinitions.h"
|
||||||
#include "mission/system/AcsBoardAssembly.h"
|
#include "mission/system/AcsBoardAssembly.h"
|
||||||
#include "mission/tmtc/CCSDSHandler.h"
|
#include "mission/tmtc/CCSDSHandler.h"
|
||||||
|
#include "mission/tmtc/TmFunnel.h"
|
||||||
#include "mission/tmtc/VirtualChannel.h"
|
#include "mission/tmtc/VirtualChannel.h"
|
||||||
#include "mission/utility/TmFunnel.h"
|
|
||||||
|
|
||||||
ResetArgs RESET_ARGS_GNSS;
|
ResetArgs RESET_ARGS_GNSS;
|
||||||
|
|
||||||
@ -102,8 +101,12 @@ void Factory::setStaticFrameworkObjectIds() {
|
|||||||
CommandingServiceBase::defaultPacketSource = objects::PUS_PACKET_DISTRIBUTOR;
|
CommandingServiceBase::defaultPacketSource = objects::PUS_PACKET_DISTRIBUTOR;
|
||||||
CommandingServiceBase::defaultPacketDestination = objects::TM_FUNNEL;
|
CommandingServiceBase::defaultPacketDestination = objects::TM_FUNNEL;
|
||||||
|
|
||||||
|
#if OBSW_Q7S_EM == 1
|
||||||
|
DeviceHandlerBase::powerSwitcherId = objects::NO_OBJECT;
|
||||||
|
#else
|
||||||
DeviceHandlerBase::powerSwitcherId = objects::PCDU_HANDLER;
|
DeviceHandlerBase::powerSwitcherId = objects::PCDU_HANDLER;
|
||||||
// DeviceHandlerBase::powerSwitcherId = objects::NO_OBJECT;
|
#endif /* OBSW_Q7S_EM == 1 */
|
||||||
|
|
||||||
#if OBSW_TM_TO_PTME == 1
|
#if OBSW_TM_TO_PTME == 1
|
||||||
TmFunnel::downlinkDestination = objects::CCSDS_HANDLER;
|
TmFunnel::downlinkDestination = objects::CCSDS_HANDLER;
|
||||||
#else
|
#else
|
||||||
@ -475,6 +478,10 @@ void ObjectFactory::createAcsBoardComponents(LinuxLibgpioIF* gpioComIF, UartComI
|
|||||||
acsBoardHelper, gpioComIF);
|
acsBoardHelper, gpioComIF);
|
||||||
static_cast<void>(acsAss);
|
static_cast<void>(acsAss);
|
||||||
#endif /* OBSW_ADD_ACS_HANDLERS == 1 */
|
#endif /* OBSW_ADD_ACS_HANDLERS == 1 */
|
||||||
|
|
||||||
|
#if OBSW_USE_CCSDS_IP_CORE == 1
|
||||||
|
createCcsdsComponents(gpioComIF);
|
||||||
|
#endif /* OBSW_USE_CCSDS_IP_CORE == 1 */
|
||||||
}
|
}
|
||||||
|
|
||||||
void ObjectFactory::createHeaterComponents(GpioIF* gpioIF, PowerSwitchIF* pwrSwitcher,
|
void ObjectFactory::createHeaterComponents(GpioIF* gpioIF, PowerSwitchIF* pwrSwitcher,
|
||||||
@ -723,9 +730,7 @@ void ObjectFactory::createCcsdsComponents(LinuxLibgpioIF* gpioComIF) {
|
|||||||
consumer.str("PAPB VC 3");
|
consumer.str("PAPB VC 3");
|
||||||
gpio = new GpiodRegularByLineName(q7s::gpioNames::PAPB_EMPTY_SIGNAL_VC3, consumer.str());
|
gpio = new GpiodRegularByLineName(q7s::gpioNames::PAPB_EMPTY_SIGNAL_VC3, consumer.str());
|
||||||
gpioCookiePtmeIp->addGpio(gpioIds::VC3_PAPB_EMPTY, gpio);
|
gpioCookiePtmeIp->addGpio(gpioIds::VC3_PAPB_EMPTY, gpio);
|
||||||
|
|
||||||
gpioChecker(gpioComIF->addGpios(gpioCookiePtmeIp), "PTME PAPB VCs");
|
gpioChecker(gpioComIF->addGpios(gpioCookiePtmeIp), "PTME PAPB VCs");
|
||||||
|
|
||||||
// Creating virtual channel interfaces
|
// Creating virtual channel interfaces
|
||||||
VcInterfaceIF* vc0 =
|
VcInterfaceIF* vc0 =
|
||||||
new PapbVcInterface(gpioComIF, gpioIds::VC0_PAPB_BUSY, gpioIds::VC0_PAPB_EMPTY, q7s::UIO_PTME,
|
new PapbVcInterface(gpioComIF, gpioIds::VC0_PAPB_BUSY, gpioIds::VC0_PAPB_EMPTY, q7s::UIO_PTME,
|
||||||
@ -739,14 +744,12 @@ void ObjectFactory::createCcsdsComponents(LinuxLibgpioIF* gpioComIF) {
|
|||||||
VcInterfaceIF* vc3 =
|
VcInterfaceIF* vc3 =
|
||||||
new PapbVcInterface(gpioComIF, gpioIds::VC3_PAPB_BUSY, gpioIds::VC3_PAPB_EMPTY, q7s::UIO_PTME,
|
new PapbVcInterface(gpioComIF, gpioIds::VC3_PAPB_BUSY, gpioIds::VC3_PAPB_EMPTY, q7s::UIO_PTME,
|
||||||
q7s::uiomapids::PTME_VC3);
|
q7s::uiomapids::PTME_VC3);
|
||||||
|
|
||||||
// Creating ptme object and adding virtual channel interfaces
|
// Creating ptme object and adding virtual channel interfaces
|
||||||
Ptme* ptme = new Ptme(objects::PTME);
|
Ptme* ptme = new Ptme(objects::PTME);
|
||||||
ptme->addVcInterface(ccsds::VC0, vc0);
|
ptme->addVcInterface(ccsds::VC0, vc0);
|
||||||
ptme->addVcInterface(ccsds::VC1, vc1);
|
ptme->addVcInterface(ccsds::VC1, vc1);
|
||||||
ptme->addVcInterface(ccsds::VC2, vc2);
|
ptme->addVcInterface(ccsds::VC2, vc2);
|
||||||
ptme->addVcInterface(ccsds::VC3, vc3);
|
ptme->addVcInterface(ccsds::VC3, vc3);
|
||||||
|
|
||||||
AxiPtmeConfig* axiPtmeConfig =
|
AxiPtmeConfig* axiPtmeConfig =
|
||||||
new AxiPtmeConfig(objects::AXI_PTME_CONFIG, q7s::UIO_PTME, q7s::uiomapids::PTME_CONFIG);
|
new AxiPtmeConfig(objects::AXI_PTME_CONFIG, q7s::UIO_PTME, q7s::uiomapids::PTME_CONFIG);
|
||||||
PtmeConfig* ptmeConfig = new PtmeConfig(objects::PTME_CONFIG, axiPtmeConfig);
|
PtmeConfig* ptmeConfig = new PtmeConfig(objects::PTME_CONFIG, axiPtmeConfig);
|
||||||
@ -759,7 +762,6 @@ void ObjectFactory::createCcsdsComponents(LinuxLibgpioIF* gpioComIF) {
|
|||||||
CCSDSHandler* ccsdsHandler = new CCSDSHandler(
|
CCSDSHandler* ccsdsHandler = new CCSDSHandler(
|
||||||
objects::CCSDS_HANDLER, objects::PTME, objects::CCSDS_PACKET_DISTRIBUTOR, ptmeConfig,
|
objects::CCSDS_HANDLER, objects::PTME, objects::CCSDS_PACKET_DISTRIBUTOR, ptmeConfig,
|
||||||
gpioComIF, gpioIds::RS485_EN_TX_CLOCK, gpioIds::RS485_EN_TX_DATA, TRANSMITTER_TIMEOUT);
|
gpioComIF, gpioIds::RS485_EN_TX_CLOCK, gpioIds::RS485_EN_TX_DATA, TRANSMITTER_TIMEOUT);
|
||||||
|
|
||||||
VirtualChannel* vc = nullptr;
|
VirtualChannel* vc = nullptr;
|
||||||
vc = new VirtualChannel(ccsds::VC0, common::VC0_QUEUE_SIZE, objects::CCSDS_HANDLER);
|
vc = new VirtualChannel(ccsds::VC0, common::VC0_QUEUE_SIZE, objects::CCSDS_HANDLER);
|
||||||
ccsdsHandler->addVirtualChannel(ccsds::VC0, vc);
|
ccsdsHandler->addVirtualChannel(ccsds::VC0, vc);
|
||||||
@ -769,7 +771,6 @@ void ObjectFactory::createCcsdsComponents(LinuxLibgpioIF* gpioComIF) {
|
|||||||
ccsdsHandler->addVirtualChannel(ccsds::VC2, vc);
|
ccsdsHandler->addVirtualChannel(ccsds::VC2, vc);
|
||||||
vc = new VirtualChannel(ccsds::VC3, common::VC3_QUEUE_SIZE, objects::CCSDS_HANDLER);
|
vc = new VirtualChannel(ccsds::VC3, common::VC3_QUEUE_SIZE, objects::CCSDS_HANDLER);
|
||||||
ccsdsHandler->addVirtualChannel(ccsds::VC3, vc);
|
ccsdsHandler->addVirtualChannel(ccsds::VC3, vc);
|
||||||
|
|
||||||
GpioCookie* gpioCookiePdec = new GpioCookie;
|
GpioCookie* gpioCookiePdec = new GpioCookie;
|
||||||
consumer.str("");
|
consumer.str("");
|
||||||
consumer << "0x" << std::hex << objects::PDEC_HANDLER;
|
consumer << "0x" << std::hex << objects::PDEC_HANDLER;
|
||||||
@ -777,12 +778,9 @@ void ObjectFactory::createCcsdsComponents(LinuxLibgpioIF* gpioComIF) {
|
|||||||
gpio = new GpiodRegularByLineName(q7s::gpioNames::PDEC_RESET, consumer.str(), Direction::OUT,
|
gpio = new GpiodRegularByLineName(q7s::gpioNames::PDEC_RESET, consumer.str(), Direction::OUT,
|
||||||
Levels::LOW);
|
Levels::LOW);
|
||||||
gpioCookiePdec->addGpio(gpioIds::PDEC_RESET, gpio);
|
gpioCookiePdec->addGpio(gpioIds::PDEC_RESET, gpio);
|
||||||
|
|
||||||
gpioChecker(gpioComIF->addGpios(gpioCookiePdec), "PDEC");
|
gpioChecker(gpioComIF->addGpios(gpioCookiePdec), "PDEC");
|
||||||
|
|
||||||
new PdecHandler(objects::PDEC_HANDLER, objects::CCSDS_HANDLER, gpioComIF, gpioIds::PDEC_RESET,
|
new PdecHandler(objects::PDEC_HANDLER, objects::CCSDS_HANDLER, gpioComIF, gpioIds::PDEC_RESET,
|
||||||
q7s::UIO_PDEC_CONFIG_MEMORY, q7s::UIO_PDEC_RAM, q7s::UIO_PDEC_REGISTERS);
|
q7s::UIO_PDEC_CONFIG_MEMORY, q7s::UIO_PDEC_RAM, q7s::UIO_PDEC_REGISTERS);
|
||||||
|
|
||||||
GpioCookie* gpioRS485Chip = new GpioCookie;
|
GpioCookie* gpioRS485Chip = new GpioCookie;
|
||||||
gpio = new GpiodRegularByLineName(q7s::gpioNames::RS485_EN_TX_CLOCK, "RS485 Transceiver",
|
gpio = new GpiodRegularByLineName(q7s::gpioNames::RS485_EN_TX_CLOCK, "RS485 Transceiver",
|
||||||
Direction::OUT, Levels::LOW);
|
Direction::OUT, Levels::LOW);
|
||||||
@ -790,7 +788,6 @@ void ObjectFactory::createCcsdsComponents(LinuxLibgpioIF* gpioComIF) {
|
|||||||
gpio = new GpiodRegularByLineName(q7s::gpioNames::RS485_EN_TX_DATA, "RS485 Transceiver",
|
gpio = new GpiodRegularByLineName(q7s::gpioNames::RS485_EN_TX_DATA, "RS485 Transceiver",
|
||||||
Direction::OUT, Levels::LOW);
|
Direction::OUT, Levels::LOW);
|
||||||
gpioRS485Chip->addGpio(gpioIds::RS485_EN_TX_DATA, gpio);
|
gpioRS485Chip->addGpio(gpioIds::RS485_EN_TX_DATA, gpio);
|
||||||
|
|
||||||
// Default configuration enables RX channels (RXEN = LOW)
|
// Default configuration enables RX channels (RXEN = LOW)
|
||||||
gpio = new GpiodRegularByLineName(q7s::gpioNames::RS485_EN_RX_CLOCK, "RS485 Transceiver",
|
gpio = new GpiodRegularByLineName(q7s::gpioNames::RS485_EN_RX_CLOCK, "RS485 Transceiver",
|
||||||
Direction::OUT, Levels::LOW);
|
Direction::OUT, Levels::LOW);
|
||||||
@ -798,7 +795,6 @@ void ObjectFactory::createCcsdsComponents(LinuxLibgpioIF* gpioComIF) {
|
|||||||
gpio = new GpiodRegularByLineName(q7s::gpioNames::RS485_EN_RX_DATA, "RS485 Transceiver",
|
gpio = new GpiodRegularByLineName(q7s::gpioNames::RS485_EN_RX_DATA, "RS485 Transceiver",
|
||||||
Direction::OUT, Levels::LOW);
|
Direction::OUT, Levels::LOW);
|
||||||
gpioRS485Chip->addGpio(gpioIds::RS485_EN_RX_DATA, gpio);
|
gpioRS485Chip->addGpio(gpioIds::RS485_EN_RX_DATA, gpio);
|
||||||
|
|
||||||
gpioChecker(gpioComIF->addGpios(gpioRS485Chip), "RS485 Transceiver");
|
gpioChecker(gpioComIF->addGpios(gpioRS485Chip), "RS485 Transceiver");
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -38,9 +38,13 @@ void ObjectFactory::produce(void* args) {
|
|||||||
createSolarArrayDeploymentComponents();
|
createSolarArrayDeploymentComponents();
|
||||||
createPlPcduComponents(gpioComIF, spiMainComIF, pwrSwitcher);
|
createPlPcduComponents(gpioComIF, spiMainComIF, pwrSwitcher);
|
||||||
#if OBSW_ADD_SYRLINKS == 1
|
#if OBSW_ADD_SYRLINKS == 1
|
||||||
|
#if OBSW_Q7S_EM == 1
|
||||||
|
createSyrlinksComponents(nullptr);
|
||||||
|
#else
|
||||||
createSyrlinksComponents(pwrSwitcher);
|
createSyrlinksComponents(pwrSwitcher);
|
||||||
|
#endif /* OBSW_Q7S_EM == 1 */
|
||||||
#endif /* OBSW_ADD_SYRLINKS == 1 */
|
#endif /* OBSW_ADD_SYRLINKS == 1 */
|
||||||
createRtdComponents(q7s::SPI_DEFAULT_DEV, gpioComIF, pwrSwitcher);
|
createRtdComponents(q7s::SPI_DEFAULT_DEV, gpioComIF, pwrSwitcher, spiMainComIF);
|
||||||
createPayloadComponents(gpioComIF);
|
createPayloadComponents(gpioComIF);
|
||||||
|
|
||||||
#if OBSW_ADD_MGT == 1
|
#if OBSW_ADD_MGT == 1
|
||||||
|
@ -62,4 +62,5 @@ void ObjectFactory::produce(void* args) {
|
|||||||
#endif /* OBSW_ADD_TEST_CODE == 1 */
|
#endif /* OBSW_ADD_TEST_CODE == 1 */
|
||||||
|
|
||||||
createMiscComponents();
|
createMiscComponents();
|
||||||
|
createThermalController();
|
||||||
}
|
}
|
||||||
|
@ -20,9 +20,16 @@ SdCardManager* SdCardManager::INSTANCE = nullptr;
|
|||||||
|
|
||||||
SdCardManager::SdCardManager() : SystemObject(objects::SDC_MANAGER), cmdExecutor(256) {
|
SdCardManager::SdCardManager() : SystemObject(objects::SDC_MANAGER), cmdExecutor(256) {
|
||||||
mutex = MutexFactory::instance()->createMutex();
|
mutex = MutexFactory::instance()->createMutex();
|
||||||
MutexGuard mg(mutex);
|
ReturnValue_t result = mutex->lockMutex();
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
sif::error << "SdCardManager::SdCardManager: Mutex lock failed" << std::endl;
|
||||||
|
}
|
||||||
uint8_t prefSdRaw = 0;
|
uint8_t prefSdRaw = 0;
|
||||||
ReturnValue_t result = scratch::readNumber(scratch::PREFERED_SDC_KEY, prefSdRaw);
|
result = scratch::readNumber(scratch::PREFERED_SDC_KEY, prefSdRaw);
|
||||||
|
result = mutex->unlockMutex();
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
sif::error << "SdCardManager::SdCardManager: Mutex unlock failed" << std::endl;
|
||||||
|
}
|
||||||
|
|
||||||
if (result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
if (result == scratch::KEY_NOT_FOUND) {
|
if (result == scratch::KEY_NOT_FOUND) {
|
||||||
|
@ -76,12 +76,12 @@ ReturnValue_t readToFile(std::string name, std::ifstream& file, std::string& fil
|
|||||||
int result = std::system(oss.str().c_str());
|
int result = std::system(oss.str().c_str());
|
||||||
if (result != 0) {
|
if (result != 0) {
|
||||||
if (WEXITSTATUS(result) == 1) {
|
if (WEXITSTATUS(result) == 1) {
|
||||||
sif::warning << "scratch::readNumber: Key " << name << " does not exist" << std::endl;
|
sif::warning << "scratch::readToFile: Key " << name << " does not exist" << std::endl;
|
||||||
// Could not find value
|
// Could not find value
|
||||||
std::remove(filename.c_str());
|
std::remove(filename.c_str());
|
||||||
return KEY_NOT_FOUND;
|
return KEY_NOT_FOUND;
|
||||||
} else {
|
} else {
|
||||||
utility::handleSystemError(result, "scratch::readNumber");
|
utility::handleSystemError(result, "scratch::readToFile");
|
||||||
std::remove(filename.c_str());
|
std::remove(filename.c_str());
|
||||||
return HasReturnvaluesIF::RETURN_FAILED;
|
return HasReturnvaluesIF::RETURN_FAILED;
|
||||||
}
|
}
|
||||||
|
@ -107,6 +107,25 @@ void initmission::initTasks() {
|
|||||||
}
|
}
|
||||||
#endif /* OBSW_ADD_PLOC_SUPERVISOR == 1 */
|
#endif /* OBSW_ADD_PLOC_SUPERVISOR == 1 */
|
||||||
|
|
||||||
|
#if OBSW_USE_CCSDS_IP_CORE == 1
|
||||||
|
PeriodicTaskIF* ccsdsHandlerTask = factory->createPeriodicTask(
|
||||||
|
"CCSDS_HANDLER", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, missedDeadlineFunc);
|
||||||
|
result = ccsdsHandlerTask->addComponent(objects::CCSDS_HANDLER);
|
||||||
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
|
initmission::printAddObjectError("CCSDS Handler", objects::CCSDS_HANDLER);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Minimal distance between two received TCs amounts to 0.6 seconds
|
||||||
|
// If a command has not been read before the next one arrives, the old command will be
|
||||||
|
// overwritten by the PDEC.
|
||||||
|
PeriodicTaskIF* pdecHandlerTask = factory->createPeriodicTask(
|
||||||
|
"PDEC_HANDLER", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.0, missedDeadlineFunc);
|
||||||
|
result = pdecHandlerTask->addComponent(objects::PDEC_HANDLER);
|
||||||
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
|
initmission::printAddObjectError("PDEC Handler", objects::PDEC_HANDLER);
|
||||||
|
}
|
||||||
|
#endif /* OBSW_USE_CCSDS_IP_CORE == 1 */
|
||||||
|
|
||||||
auto taskStarter = [](std::vector<PeriodicTaskIF*>& taskVector, std::string name) {
|
auto taskStarter = [](std::vector<PeriodicTaskIF*>& taskVector, std::string name) {
|
||||||
for (const auto& task : taskVector) {
|
for (const auto& task : taskVector) {
|
||||||
if (task != nullptr) {
|
if (task != nullptr) {
|
||||||
@ -121,6 +140,10 @@ void initmission::initTasks() {
|
|||||||
tmtcDistributor->startTask();
|
tmtcDistributor->startTask();
|
||||||
tmtcBridgeTask->startTask();
|
tmtcBridgeTask->startTask();
|
||||||
tmtcPollingTask->startTask();
|
tmtcPollingTask->startTask();
|
||||||
|
#if OBSW_USE_CCSDS_IP_CORE == 1
|
||||||
|
pdecHandlerTask->startTask();
|
||||||
|
ccsdsHandlerTask->startTask();
|
||||||
|
#endif /* #if OBSW_USE_CCSDS_IP_CORE == 1 */
|
||||||
#if OBSW_ADD_PLOC_SUPERVISOR == 1
|
#if OBSW_ADD_PLOC_SUPERVISOR == 1
|
||||||
supvHelperTask->startTask();
|
supvHelperTask->startTask();
|
||||||
#endif /* OBSW_ADD_PLOC_SUPERVISOR == 1 */
|
#endif /* OBSW_ADD_PLOC_SUPERVISOR == 1 */
|
||||||
|
@ -3,7 +3,7 @@
|
|||||||
|
|
||||||
#include <vector>
|
#include <vector>
|
||||||
|
|
||||||
#include "fsfw/tasks/Typedef.h"
|
#include "fsfw/tasks/definitions.h"
|
||||||
|
|
||||||
class PeriodicTaskIF;
|
class PeriodicTaskIF;
|
||||||
class TaskFactory;
|
class TaskFactory;
|
||||||
|
@ -37,7 +37,6 @@
|
|||||||
#define OBSW_ENABLE_SYRLINKS_TRANSMIT_TIMEOUT 0
|
#define OBSW_ENABLE_SYRLINKS_TRANSMIT_TIMEOUT 0
|
||||||
#define OBSW_SYRLINKS_SIMULATED 1
|
#define OBSW_SYRLINKS_SIMULATED 1
|
||||||
#define OBSW_STAR_TRACKER_GROUND_CONFIG 1
|
#define OBSW_STAR_TRACKER_GROUND_CONFIG 1
|
||||||
#define OBSW_ENABLE_PERIODIC_HK 0
|
|
||||||
#define OBSW_PRINT_CORE_HK 0
|
#define OBSW_PRINT_CORE_HK 0
|
||||||
#define OBSW_INITIALIZE_SWITCHES 0
|
#define OBSW_INITIALIZE_SWITCHES 0
|
||||||
|
|
||||||
|
@ -1,10 +1,9 @@
|
|||||||
#include "ObjectFactory.h"
|
#include "ObjectFactory.h"
|
||||||
|
|
||||||
#include <devConf.h>
|
|
||||||
|
|
||||||
#include "OBSWConfig.h"
|
#include "OBSWConfig.h"
|
||||||
#include "busConf.h"
|
#include "busConf.h"
|
||||||
#include "devConf.h"
|
#include "devConf.h"
|
||||||
|
#include "ccsdsConfig.h"
|
||||||
#include "devices/addresses.h"
|
#include "devices/addresses.h"
|
||||||
#include "devices/gpioIds.h"
|
#include "devices/gpioIds.h"
|
||||||
#include "fsfw/datapoollocal/LocalDataPoolManager.h"
|
#include "fsfw/datapoollocal/LocalDataPoolManager.h"
|
||||||
@ -15,14 +14,23 @@
|
|||||||
#include "fsfw_hal/linux/i2c/I2cCookie.h"
|
#include "fsfw_hal/linux/i2c/I2cCookie.h"
|
||||||
#include "fsfw_hal/linux/uart/UartComIF.h"
|
#include "fsfw_hal/linux/uart/UartComIF.h"
|
||||||
#include "fsfw_hal/linux/uart/UartCookie.h"
|
#include "fsfw_hal/linux/uart/UartCookie.h"
|
||||||
|
#include "fsfw_hal/common/gpio/GpioCookie.h"
|
||||||
|
#include "linux/ObjectFactory.h"
|
||||||
#include "linux/devices/ploc/PlocMPSoCHandler.h"
|
#include "linux/devices/ploc/PlocMPSoCHandler.h"
|
||||||
#include "linux/devices/ploc/PlocMPSoCHelper.h"
|
#include "linux/devices/ploc/PlocMPSoCHelper.h"
|
||||||
#include "linux/devices/ploc/PlocMemoryDumper.h"
|
#include "linux/devices/ploc/PlocMemoryDumper.h"
|
||||||
#include "linux/devices/ploc/PlocSupervisorHandler.h"
|
#include "linux/devices/ploc/PlocSupervisorHandler.h"
|
||||||
#include "linux/devices/ploc/PlocSupvHelper.h"
|
#include "linux/devices/ploc/PlocSupvHelper.h"
|
||||||
|
#include "linux/obc/AxiPtmeConfig.h"
|
||||||
|
#include "linux/obc/PapbVcInterface.h"
|
||||||
|
#include "linux/obc/PdecHandler.h"
|
||||||
|
#include "linux/obc/Ptme.h"
|
||||||
|
#include "linux/obc/PtmeConfig.h"
|
||||||
#include "mission/core/GenericFactory.h"
|
#include "mission/core/GenericFactory.h"
|
||||||
#include "mission/devices/Tmp1075Handler.h"
|
#include "mission/devices/Tmp1075Handler.h"
|
||||||
#include "mission/utility/TmFunnel.h"
|
#include "mission/tmtc/TmFunnel.h"
|
||||||
|
#include "mission/tmtc/CCSDSHandler.h"
|
||||||
|
#include "mission/tmtc/VirtualChannel.h"
|
||||||
#include "objects/systemObjectList.h"
|
#include "objects/systemObjectList.h"
|
||||||
#include "test/gpio/DummyGpioIF.h"
|
#include "test/gpio/DummyGpioIF.h"
|
||||||
#include "tmtc/apid.h"
|
#include "tmtc/apid.h"
|
||||||
@ -35,7 +43,11 @@ void Factory::setStaticFrameworkObjectIds() {
|
|||||||
CommandingServiceBase::defaultPacketSource = objects::PUS_PACKET_DISTRIBUTOR;
|
CommandingServiceBase::defaultPacketSource = objects::PUS_PACKET_DISTRIBUTOR;
|
||||||
CommandingServiceBase::defaultPacketDestination = objects::TM_FUNNEL;
|
CommandingServiceBase::defaultPacketDestination = objects::TM_FUNNEL;
|
||||||
|
|
||||||
|
#if OBSW_TM_TO_PTME == 1
|
||||||
|
TmFunnel::downlinkDestination = objects::CCSDS_HANDLER;
|
||||||
|
#else
|
||||||
TmFunnel::downlinkDestination = objects::TMTC_BRIDGE;
|
TmFunnel::downlinkDestination = objects::TMTC_BRIDGE;
|
||||||
|
#endif
|
||||||
TmFunnel::storageDestination = objects::NO_OBJECT;
|
TmFunnel::storageDestination = objects::NO_OBJECT;
|
||||||
|
|
||||||
VerificationReporter::messageReceiver = objects::PUS_SERVICE_1_VERIFICATION;
|
VerificationReporter::messageReceiver = objects::PUS_SERVICE_1_VERIFICATION;
|
||||||
@ -46,6 +58,7 @@ void ObjectFactory::produce(void* args) {
|
|||||||
Factory::setStaticFrameworkObjectIds();
|
Factory::setStaticFrameworkObjectIds();
|
||||||
ObjectFactory::produceGenericObjects();
|
ObjectFactory::produceGenericObjects();
|
||||||
|
|
||||||
|
LinuxLibgpioIF* gpioComIF = new LinuxLibgpioIF(objects::GPIO_IF);;
|
||||||
new UartComIF(objects::UART_COM_IF);
|
new UartComIF(objects::UART_COM_IF);
|
||||||
|
|
||||||
#if OBSW_ADD_PLOC_MPSOC == 1
|
#if OBSW_ADD_PLOC_MPSOC == 1
|
||||||
@ -71,9 +84,10 @@ void ObjectFactory::produce(void* args) {
|
|||||||
supervisorCookie, Gpio(gpioIds::ENABLE_SUPV_UART, supvGpioIF),
|
supervisorCookie, Gpio(gpioIds::ENABLE_SUPV_UART, supvGpioIF),
|
||||||
pcdu::PDU1_CH6_PLOC_12V, supvHelper);
|
pcdu::PDU1_CH6_PLOC_12V, supvHelper);
|
||||||
|
|
||||||
new PlocMemoryDumper(objects::PLOC_MEMORY_DUMPER);
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
new PlocMemoryDumper(objects::PLOC_MEMORY_DUMPER);
|
||||||
|
|
||||||
#if OBSW_TEST_LIBGPIOD == 1
|
#if OBSW_TEST_LIBGPIOD == 1
|
||||||
#if OBSW_TEST_GPIO_OPEN_BYLABEL == 1
|
#if OBSW_TEST_GPIO_OPEN_BYLABEL == 1
|
||||||
/* Configure MIO0 as input */
|
/* Configure MIO0 as input */
|
||||||
@ -104,21 +118,6 @@ void ObjectFactory::produce(void* args) {
|
|||||||
new SusHandler(objects::SUS_0, objects::SPI_COM_IF, spiCookieSus, gpioComIF, gpioIds::CS_SUS_0);
|
new SusHandler(objects::SUS_0, objects::SPI_COM_IF, spiCookieSus, gpioComIF, gpioIds::CS_SUS_0);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if OBSW_TEST_CCSDS_BRIDGE == 1
|
|
||||||
GpioCookie* gpioCookieCcsdsIp = new GpioCookie;
|
|
||||||
GpiodRegular* papbBusyN =
|
|
||||||
new GpiodRegular(std::string("gpiochip0"), 0, std::string("PAPBBusy_VC0"));
|
|
||||||
gpioCookieCcsdsIp->addGpio(gpioIds::PAPB_BUSY_N, papbBusyN);
|
|
||||||
GpiodRegular* papbEmpty =
|
|
||||||
new GpiodRegular(std::string("gpiochip0"), 1, std::string("PAPBEmpty_VC0"));
|
|
||||||
gpioCookieCcsdsIp->addGpio(gpioIds::PAPB_EMPTY, papbEmpty);
|
|
||||||
gpioComIF->addGpios(gpioCookieCcsdsIp);
|
|
||||||
|
|
||||||
new CCSDSIPCoreBridge(objects::CCSDS_IP_CORE_BRIDGE, objects::CCSDS_PACKET_DISTRIBUTOR,
|
|
||||||
objects::TM_STORE, objects::TC_STORE, gpioComIF, std::string("/dev/uio0"),
|
|
||||||
gpioIds::PAPB_BUSY_N, gpioIds::PAPB_EMPTY);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if OBSW_TEST_RAD_SENSOR == 1
|
#if OBSW_TEST_RAD_SENSOR == 1
|
||||||
GpioCookie* gpioCookieRadSensor = new GpioCookie;
|
GpioCookie* gpioCookieRadSensor = new GpioCookie;
|
||||||
GpiodRegular* chipSelectRadSensor = new GpiodRegular(
|
GpiodRegular* chipSelectRadSensor = new GpiodRegular(
|
||||||
@ -155,4 +154,6 @@ void ObjectFactory::produce(void* args) {
|
|||||||
/* Temperature sensors */
|
/* Temperature sensors */
|
||||||
new Tmp1075Handler(objects::TMP1075_HANDLER_1, objects::I2C_COM_IF, i2cCookieTmp1075tcs1);
|
new Tmp1075Handler(objects::TMP1075_HANDLER_1, objects::I2C_COM_IF, i2cCookieTmp1075tcs1);
|
||||||
new Tmp1075Handler(objects::TMP1075_HANDLER_2, objects::I2C_COM_IF, i2cCookieTmp1075tcs2);
|
new Tmp1075Handler(objects::TMP1075_HANDLER_2, objects::I2C_COM_IF, i2cCookieTmp1075tcs2);
|
||||||
|
|
||||||
|
static_cast<void>(gpioComIF);
|
||||||
}
|
}
|
||||||
|
@ -1,7 +1,11 @@
|
|||||||
#ifndef BSP_LINUX_OBJECTFACTORY_H_
|
#ifndef BSP_LINUX_OBJECTFACTORY_H_
|
||||||
#define BSP_LINUX_OBJECTFACTORY_H_
|
#define BSP_LINUX_OBJECTFACTORY_H_
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
#include <fsfw_hal/linux/gpio/LinuxLibgpioIF.h>
|
||||||
|
|
||||||
namespace ObjectFactory {
|
namespace ObjectFactory {
|
||||||
|
static const uint32_t TRANSMITTER_TIMEOUT = 86400000; // 1 day
|
||||||
void produce(void* args);
|
void produce(void* args);
|
||||||
}; // namespace ObjectFactory
|
}; // namespace ObjectFactory
|
||||||
|
|
||||||
|
@ -3,9 +3,37 @@
|
|||||||
|
|
||||||
namespace te0720_1cfa {
|
namespace te0720_1cfa {
|
||||||
static constexpr char MPSOC_UART[] = "/dev/ttyPS1";
|
static constexpr char MPSOC_UART[] = "/dev/ttyPS1";
|
||||||
namespace baudrate {
|
|
||||||
|
|
||||||
|
static constexpr char UIO_PDEC_REGISTERS[] = "/dev/uio0";
|
||||||
|
static constexpr char UIO_PTME[] = "/dev/uio1";
|
||||||
|
static constexpr char UIO_PDEC_CONFIG_MEMORY[] = "/dev/uio2";
|
||||||
|
static constexpr char UIO_PDEC_RAM[] = "/dev/uio3";
|
||||||
|
static constexpr int MAP_ID_PTME_CONFIG = 3;
|
||||||
|
|
||||||
|
namespace uiomapids {
|
||||||
|
static const int PTME_VC0 = 0;
|
||||||
|
static const int PTME_VC1 = 1;
|
||||||
|
static const int PTME_VC2 = 2;
|
||||||
|
static const int PTME_VC3 = 3;
|
||||||
|
static const int PTME_CONFIG = 4;
|
||||||
|
} // namespace uiomapids
|
||||||
|
|
||||||
|
namespace gpioNames {
|
||||||
|
static constexpr char PAPB_BUSY_SIGNAL_VC0[] = "papb_busy_signal_vc0";
|
||||||
|
static constexpr char PAPB_EMPTY_SIGNAL_VC0[] = "papb_empty_signal_vc0";
|
||||||
|
static constexpr char PAPB_BUSY_SIGNAL_VC1[] = "papb_busy_signal_vc1";
|
||||||
|
static constexpr char PAPB_EMPTY_SIGNAL_VC1[] = "papb_empty_signal_vc1";
|
||||||
|
static constexpr char PAPB_BUSY_SIGNAL_VC2[] = "papb_busy_signal_vc2";
|
||||||
|
static constexpr char PAPB_EMPTY_SIGNAL_VC2[] = "papb_empty_signal_vc2";
|
||||||
|
static constexpr char PAPB_BUSY_SIGNAL_VC3[] = "papb_busy_signal_vc3";
|
||||||
|
static constexpr char PAPB_EMPTY_SIGNAL_VC3[] = "papb_empty_signal_vc3";
|
||||||
|
static constexpr char RS485_EN_TX_CLOCK[] = "tx_clock_enable_ltc2872";
|
||||||
|
static constexpr char RS485_EN_TX_DATA[] = "tx_data_enable_ltc2872";
|
||||||
|
static constexpr char RS485_EN_RX_CLOCK[] = "rx_clock_enable_ltc2872";
|
||||||
|
static constexpr char RS485_EN_RX_DATA[] = "rx_data_enable_ltc2872";
|
||||||
|
static constexpr char PDEC_RESET[] = "pdec_reset";
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif /* BSP_EGSE_BOARDCONFIG_BUSCONF_H_ */
|
#endif /* BSP_EGSE_BOARDCONFIG_BUSCONF_H_ */
|
||||||
|
@ -4,7 +4,7 @@
|
|||||||
const char* const SW_NAME = "eive";
|
const char* const SW_NAME = "eive";
|
||||||
|
|
||||||
#define SW_VERSION 1
|
#define SW_VERSION 1
|
||||||
#define SW_SUBVERSION 10
|
#define SW_SUBVERSION 12
|
||||||
#define SW_REVISION 1
|
#define SW_REVISION 1
|
||||||
|
|
||||||
#endif /* COMMON_CONFIG_OBSWVERSION_H_ */
|
#endif /* COMMON_CONFIG_OBSWVERSION_H_ */
|
||||||
|
42
dummies/AcuDummy.cpp
Normal file
42
dummies/AcuDummy.cpp
Normal file
@ -0,0 +1,42 @@
|
|||||||
|
#include "AcuDummy.h"
|
||||||
|
|
||||||
|
#include <mission/devices/devicedefinitions/GomspaceDefinitions.h>
|
||||||
|
|
||||||
|
AcuDummy::AcuDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie)
|
||||||
|
: DeviceHandlerBase(objectId, comif, comCookie) {}
|
||||||
|
|
||||||
|
AcuDummy::~AcuDummy() {}
|
||||||
|
|
||||||
|
void AcuDummy::doStartUp() {}
|
||||||
|
|
||||||
|
void AcuDummy::doShutDown() {}
|
||||||
|
|
||||||
|
ReturnValue_t AcuDummy::buildNormalDeviceCommand(DeviceCommandId_t *id) { return NOTHING_TO_SEND; }
|
||||||
|
|
||||||
|
ReturnValue_t AcuDummy::buildTransitionDeviceCommand(DeviceCommandId_t *id) {
|
||||||
|
return NOTHING_TO_SEND;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t AcuDummy::buildCommandFromCommand(DeviceCommandId_t deviceCommand,
|
||||||
|
const uint8_t *commandData, size_t commandDataLen) {
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t AcuDummy::scanForReply(const uint8_t *start, size_t len, DeviceCommandId_t *foundId,
|
||||||
|
size_t *foundLen) {
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t AcuDummy::interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) {
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
void AcuDummy::fillCommandAndReplyMap() {}
|
||||||
|
|
||||||
|
uint32_t AcuDummy::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { return 500; }
|
||||||
|
|
||||||
|
ReturnValue_t AcuDummy::initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
|
||||||
|
LocalDataPoolManager &poolManager) {
|
||||||
|
localDataPoolMap.emplace(P60System::pool::ACU_TEMPERATURES, new PoolEntry<float>(3));
|
||||||
|
return HasReturnvaluesIF::RETURN_OK;
|
||||||
|
}
|
33
dummies/AcuDummy.h
Normal file
33
dummies/AcuDummy.h
Normal file
@ -0,0 +1,33 @@
|
|||||||
|
#ifndef DUMMIES_ACUDUMMY_H_
|
||||||
|
#define DUMMIES_ACUDUMMY_H_
|
||||||
|
|
||||||
|
#include <fsfw/devicehandlers/DeviceHandlerBase.h>
|
||||||
|
|
||||||
|
class AcuDummy : public DeviceHandlerBase {
|
||||||
|
public:
|
||||||
|
static const DeviceCommandId_t SIMPLE_COMMAND = 1;
|
||||||
|
static const DeviceCommandId_t PERIODIC_REPLY = 2;
|
||||||
|
|
||||||
|
static const uint8_t SIMPLE_COMMAND_DATA = 1;
|
||||||
|
static const uint8_t PERIODIC_REPLY_DATA = 2;
|
||||||
|
|
||||||
|
AcuDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie);
|
||||||
|
virtual ~AcuDummy();
|
||||||
|
|
||||||
|
protected:
|
||||||
|
void doStartUp() override;
|
||||||
|
void doShutDown() override;
|
||||||
|
ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t *id) override;
|
||||||
|
ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t *id) override;
|
||||||
|
ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, const uint8_t *commandData,
|
||||||
|
size_t commandDataLen) override;
|
||||||
|
ReturnValue_t scanForReply(const uint8_t *start, size_t len, DeviceCommandId_t *foundId,
|
||||||
|
size_t *foundLen) override;
|
||||||
|
ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) override;
|
||||||
|
void fillCommandAndReplyMap() override;
|
||||||
|
uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override;
|
||||||
|
ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
|
||||||
|
LocalDataPoolManager &poolManager) override;
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif /* DUMMIES_ACUDUMMY_H_ */
|
55
dummies/BpxDummy.cpp
Normal file
55
dummies/BpxDummy.cpp
Normal file
@ -0,0 +1,55 @@
|
|||||||
|
#include "BpxDummy.h"
|
||||||
|
|
||||||
|
#include <mission/devices/devicedefinitions/BpxBatteryDefinitions.h>
|
||||||
|
|
||||||
|
BpxDummy::BpxDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie)
|
||||||
|
: DeviceHandlerBase(objectId, comif, comCookie) {}
|
||||||
|
|
||||||
|
BpxDummy::~BpxDummy() {}
|
||||||
|
|
||||||
|
void BpxDummy::doStartUp() {}
|
||||||
|
|
||||||
|
void BpxDummy::doShutDown() {}
|
||||||
|
|
||||||
|
ReturnValue_t BpxDummy::buildNormalDeviceCommand(DeviceCommandId_t *id) { return NOTHING_TO_SEND; }
|
||||||
|
|
||||||
|
ReturnValue_t BpxDummy::buildTransitionDeviceCommand(DeviceCommandId_t *id) {
|
||||||
|
return NOTHING_TO_SEND;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t BpxDummy::buildCommandFromCommand(DeviceCommandId_t deviceCommand,
|
||||||
|
const uint8_t *commandData, size_t commandDataLen) {
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t BpxDummy::scanForReply(const uint8_t *start, size_t len, DeviceCommandId_t *foundId,
|
||||||
|
size_t *foundLen) {
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t BpxDummy::interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) {
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
void BpxDummy::fillCommandAndReplyMap() {}
|
||||||
|
|
||||||
|
uint32_t BpxDummy::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { return 500; }
|
||||||
|
|
||||||
|
ReturnValue_t BpxDummy::initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
|
||||||
|
LocalDataPoolManager &poolManager) {
|
||||||
|
localDataPoolMap.emplace(BpxBattery::BATT_TEMP_1, &battTemp1);
|
||||||
|
localDataPoolMap.emplace(BpxBattery::BATT_TEMP_2, &battTemp2);
|
||||||
|
localDataPoolMap.emplace(BpxBattery::BATT_TEMP_3, &battTemp3);
|
||||||
|
localDataPoolMap.emplace(BpxBattery::BATT_TEMP_4, &battTemp4);
|
||||||
|
localDataPoolMap.emplace(BpxBattery::CHARGE_CURRENT, &chargeCurrent);
|
||||||
|
localDataPoolMap.emplace(BpxBattery::DISCHARGE_CURRENT, &dischargeCurrent);
|
||||||
|
localDataPoolMap.emplace(BpxBattery::HEATER_CURRENT, &heaterCurrent);
|
||||||
|
localDataPoolMap.emplace(BpxBattery::BATT_VOLTAGE, &battVolt);
|
||||||
|
localDataPoolMap.emplace(BpxBattery::REBOOT_COUNTER, &rebootCounter);
|
||||||
|
localDataPoolMap.emplace(BpxBattery::BOOTCAUSE, &bootCause);
|
||||||
|
|
||||||
|
localDataPoolMap.emplace(BpxBattery::BATTERY_HEATER_MODE, &battheatMode);
|
||||||
|
localDataPoolMap.emplace(BpxBattery::BATTHEAT_LOW_LIMIT, &battheatLow);
|
||||||
|
localDataPoolMap.emplace(BpxBattery::BATTHEAT_HIGH_LIMIT, &battheatHigh);
|
||||||
|
return HasReturnvaluesIF::RETURN_OK;
|
||||||
|
}
|
48
dummies/BpxDummy.h
Normal file
48
dummies/BpxDummy.h
Normal file
@ -0,0 +1,48 @@
|
|||||||
|
#ifndef DUMMIES_BPXDUMMY_H_
|
||||||
|
#define DUMMIES_BPXDUMMY_H_
|
||||||
|
|
||||||
|
#include <fsfw/devicehandlers/DeviceHandlerBase.h>
|
||||||
|
|
||||||
|
class BpxDummy : public DeviceHandlerBase {
|
||||||
|
public:
|
||||||
|
static const DeviceCommandId_t SIMPLE_COMMAND = 1;
|
||||||
|
static const DeviceCommandId_t PERIODIC_REPLY = 2;
|
||||||
|
|
||||||
|
static const uint8_t SIMPLE_COMMAND_DATA = 1;
|
||||||
|
static const uint8_t PERIODIC_REPLY_DATA = 2;
|
||||||
|
|
||||||
|
BpxDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie);
|
||||||
|
virtual ~BpxDummy();
|
||||||
|
|
||||||
|
protected:
|
||||||
|
void doStartUp() override;
|
||||||
|
void doShutDown() override;
|
||||||
|
ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t *id) override;
|
||||||
|
ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t *id) override;
|
||||||
|
ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, const uint8_t *commandData,
|
||||||
|
size_t commandDataLen) override;
|
||||||
|
ReturnValue_t scanForReply(const uint8_t *start, size_t len, DeviceCommandId_t *foundId,
|
||||||
|
size_t *foundLen) override;
|
||||||
|
ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) override;
|
||||||
|
void fillCommandAndReplyMap() override;
|
||||||
|
uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override;
|
||||||
|
ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
|
||||||
|
LocalDataPoolManager &poolManager) override;
|
||||||
|
|
||||||
|
private:
|
||||||
|
PoolEntry<uint16_t> chargeCurrent = PoolEntry<uint16_t>({0});
|
||||||
|
PoolEntry<uint16_t> dischargeCurrent = PoolEntry<uint16_t>({0});
|
||||||
|
PoolEntry<uint16_t> heaterCurrent = PoolEntry<uint16_t>({0});
|
||||||
|
PoolEntry<uint16_t> battVolt = PoolEntry<uint16_t>({0});
|
||||||
|
PoolEntry<int16_t> battTemp1 = PoolEntry<int16_t>({0});
|
||||||
|
PoolEntry<int16_t> battTemp2 = PoolEntry<int16_t>({0});
|
||||||
|
PoolEntry<int16_t> battTemp3 = PoolEntry<int16_t>({0});
|
||||||
|
PoolEntry<int16_t> battTemp4 = PoolEntry<int16_t>({0});
|
||||||
|
PoolEntry<uint32_t> rebootCounter = PoolEntry<uint32_t>({0});
|
||||||
|
PoolEntry<uint8_t> bootCause = PoolEntry<uint8_t>({0});
|
||||||
|
PoolEntry<uint8_t> battheatMode = PoolEntry<uint8_t>({0});
|
||||||
|
PoolEntry<int8_t> battheatLow = PoolEntry<int8_t>({0});
|
||||||
|
PoolEntry<int8_t> battheatHigh = PoolEntry<int8_t>({0});
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif /* DUMMIES_BPXDUMMY_H_ */
|
19
dummies/CMakeLists.txt
Normal file
19
dummies/CMakeLists.txt
Normal file
@ -0,0 +1,19 @@
|
|||||||
|
target_sources(
|
||||||
|
${LIB_DUMMIES}
|
||||||
|
PUBLIC TemperatureSensorsDummy.cpp
|
||||||
|
SusDummy.cpp
|
||||||
|
BpxDummy.cpp
|
||||||
|
ComIFDummy.cpp
|
||||||
|
ComCookieDummy.cpp
|
||||||
|
RwDummy.cpp
|
||||||
|
StarTrackerDummy.cpp
|
||||||
|
SyrlinksDummy.cpp
|
||||||
|
ImtqDummy.cpp
|
||||||
|
AcuDummy.cpp
|
||||||
|
PduDummy.cpp
|
||||||
|
P60DockDummy.cpp
|
||||||
|
GyroAdisDummy.cpp
|
||||||
|
GyroL3GD20Dummy.cpp
|
||||||
|
MgmLIS3MDLDummy.cpp
|
||||||
|
PlPcduDummy.cpp
|
||||||
|
CoreControllerDummy.cpp)
|
5
dummies/ComCookieDummy.cpp
Normal file
5
dummies/ComCookieDummy.cpp
Normal file
@ -0,0 +1,5 @@
|
|||||||
|
#include "ComCookieDummy.h"
|
||||||
|
|
||||||
|
ComCookieDummy::ComCookieDummy() {}
|
||||||
|
|
||||||
|
ComCookieDummy::~ComCookieDummy() {}
|
12
dummies/ComCookieDummy.h
Normal file
12
dummies/ComCookieDummy.h
Normal file
@ -0,0 +1,12 @@
|
|||||||
|
#ifndef TESTS_SRC_FSFW_TESTS_UNIT_DEVICEHANDLER_COMCOOKIEDUMMY_H_
|
||||||
|
#define TESTS_SRC_FSFW_TESTS_UNIT_DEVICEHANDLER_COMCOOKIEDUMMY_H_
|
||||||
|
|
||||||
|
#include "fsfw/devicehandlers/CookieIF.h"
|
||||||
|
|
||||||
|
class ComCookieDummy : public CookieIF {
|
||||||
|
public:
|
||||||
|
ComCookieDummy();
|
||||||
|
virtual ~ComCookieDummy();
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif /* TESTS_SRC_FSFW_TESTS_UNIT_DEVICEHANDLER_COMCOOKIEDUMMY_H_ */
|
21
dummies/ComIFDummy.cpp
Normal file
21
dummies/ComIFDummy.cpp
Normal file
@ -0,0 +1,21 @@
|
|||||||
|
#include "ComIFDummy.h"
|
||||||
|
|
||||||
|
ComIFDummy::ComIFDummy(object_id_t objectId) : SystemObject(objectId) {}
|
||||||
|
|
||||||
|
ComIFDummy::~ComIFDummy() {}
|
||||||
|
|
||||||
|
ReturnValue_t ComIFDummy::initializeInterface(CookieIF *cookie) { return RETURN_OK; }
|
||||||
|
|
||||||
|
ReturnValue_t ComIFDummy::sendMessage(CookieIF *cookie, const uint8_t *sendData, size_t sendLen) {
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t ComIFDummy::getSendSuccess(CookieIF *cookie) { return RETURN_OK; }
|
||||||
|
|
||||||
|
ReturnValue_t ComIFDummy::requestReceiveMessage(CookieIF *cookie, size_t requestLen) {
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t ComIFDummy::readReceivedMessage(CookieIF *cookie, uint8_t **buffer, size_t *size) {
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
26
dummies/ComIFDummy.h
Normal file
26
dummies/ComIFDummy.h
Normal file
@ -0,0 +1,26 @@
|
|||||||
|
#ifndef DUMMIES_COMIFDUMMY_H_
|
||||||
|
#define DUMMIES_COMIFDUMMY_H_
|
||||||
|
|
||||||
|
#include <fsfw/devicehandlers/DeviceCommunicationIF.h>
|
||||||
|
#include <fsfw/objectmanager/SystemObject.h>
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief The ComIFMock supports the simulation of various device communication error cases
|
||||||
|
* like incomplete or wrong replies and can be used to test the
|
||||||
|
* DeviceHandlerBase.
|
||||||
|
*/
|
||||||
|
class ComIFDummy : public DeviceCommunicationIF, public SystemObject {
|
||||||
|
public:
|
||||||
|
ComIFDummy(object_id_t objectId);
|
||||||
|
virtual ~ComIFDummy();
|
||||||
|
|
||||||
|
virtual ReturnValue_t initializeInterface(CookieIF *cookie) override;
|
||||||
|
virtual ReturnValue_t sendMessage(CookieIF *cookie, const uint8_t *sendData,
|
||||||
|
size_t sendLen) override;
|
||||||
|
virtual ReturnValue_t getSendSuccess(CookieIF *cookie) override;
|
||||||
|
virtual ReturnValue_t requestReceiveMessage(CookieIF *cookie, size_t requestLen) override;
|
||||||
|
virtual ReturnValue_t readReceivedMessage(CookieIF *cookie, uint8_t **buffer,
|
||||||
|
size_t *size) override;
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif /* DUMMIES_COMIFDUMMY_H_ */
|
55
dummies/CoreControllerDummy.cpp
Normal file
55
dummies/CoreControllerDummy.cpp
Normal file
@ -0,0 +1,55 @@
|
|||||||
|
#include "CoreControllerDummy.h"
|
||||||
|
|
||||||
|
#include <bsp_q7s/core/CoreDefinitions.h>
|
||||||
|
#include <objects/systemObjectList.h>
|
||||||
|
|
||||||
|
#include <cmath>
|
||||||
|
#include <cstdlib>
|
||||||
|
|
||||||
|
CoreControllerDummy::CoreControllerDummy(object_id_t objectId)
|
||||||
|
: ExtendedControllerBase(objectId, objects::NO_OBJECT) {}
|
||||||
|
|
||||||
|
ReturnValue_t CoreControllerDummy::initialize() {
|
||||||
|
static bool done = false;
|
||||||
|
if (not done) {
|
||||||
|
done = true;
|
||||||
|
ReturnValue_t result = ExtendedControllerBase::initialize();
|
||||||
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return HasReturnvaluesIF::RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t CoreControllerDummy::handleCommandMessage(CommandMessage* message) {
|
||||||
|
return RETURN_FAILED;
|
||||||
|
}
|
||||||
|
|
||||||
|
void CoreControllerDummy::performControlOperation() { return; }
|
||||||
|
|
||||||
|
ReturnValue_t CoreControllerDummy::initializeLocalDataPool(localpool::DataPool& localDataPoolMap,
|
||||||
|
LocalDataPoolManager& poolManager) {
|
||||||
|
localDataPoolMap.emplace(core::TEMPERATURE, new PoolEntry<float>({0}));
|
||||||
|
localDataPoolMap.emplace(core::PS_VOLTAGE, new PoolEntry<float>({0}));
|
||||||
|
localDataPoolMap.emplace(core::PL_VOLTAGE, new PoolEntry<float>({0}));
|
||||||
|
return HasReturnvaluesIF::RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
LocalPoolDataSetBase* CoreControllerDummy::getDataSetHandle(sid_t sid) {
|
||||||
|
switch (sid.ownerSetId) {
|
||||||
|
default:
|
||||||
|
return nullptr;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t CoreControllerDummy::checkModeCommand(Mode_t mode, Submode_t submode,
|
||||||
|
uint32_t* msToReachTheMode) {
|
||||||
|
if (submode != SUBMODE_NONE) {
|
||||||
|
return INVALID_SUBMODE;
|
||||||
|
}
|
||||||
|
if ((mode != MODE_OFF) && (mode != MODE_ON) && (mode != MODE_NORMAL)) {
|
||||||
|
return INVALID_MODE;
|
||||||
|
}
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
21
dummies/CoreControllerDummy.h
Normal file
21
dummies/CoreControllerDummy.h
Normal file
@ -0,0 +1,21 @@
|
|||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include <fsfw/controller/ExtendedControllerBase.h>
|
||||||
|
#include <mission/devices/devicedefinitions/SusDefinitions.h>
|
||||||
|
|
||||||
|
class CoreControllerDummy : public ExtendedControllerBase {
|
||||||
|
public:
|
||||||
|
CoreControllerDummy(object_id_t objectId);
|
||||||
|
|
||||||
|
ReturnValue_t initialize() override;
|
||||||
|
|
||||||
|
protected:
|
||||||
|
virtual ReturnValue_t handleCommandMessage(CommandMessage* message) override;
|
||||||
|
virtual void performControlOperation() override;
|
||||||
|
virtual ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap,
|
||||||
|
LocalDataPoolManager& poolManager) override;
|
||||||
|
virtual LocalPoolDataSetBase* getDataSetHandle(sid_t sid) override;
|
||||||
|
|
||||||
|
virtual ReturnValue_t checkModeCommand(Mode_t mode, Submode_t submode,
|
||||||
|
uint32_t* msToReachTheMode) override;
|
||||||
|
};
|
45
dummies/GyroAdisDummy.cpp
Normal file
45
dummies/GyroAdisDummy.cpp
Normal file
@ -0,0 +1,45 @@
|
|||||||
|
#include "GyroAdisDummy.h"
|
||||||
|
|
||||||
|
#include "mission/devices/devicedefinitions/GyroADIS1650XDefinitions.h"
|
||||||
|
|
||||||
|
GyroAdisDummy::GyroAdisDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie)
|
||||||
|
: DeviceHandlerBase(objectId, comif, comCookie) {}
|
||||||
|
|
||||||
|
GyroAdisDummy::~GyroAdisDummy() {}
|
||||||
|
|
||||||
|
void GyroAdisDummy::doStartUp() {}
|
||||||
|
|
||||||
|
void GyroAdisDummy::doShutDown() {}
|
||||||
|
|
||||||
|
ReturnValue_t GyroAdisDummy::buildNormalDeviceCommand(DeviceCommandId_t *id) {
|
||||||
|
return NOTHING_TO_SEND;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t GyroAdisDummy::buildTransitionDeviceCommand(DeviceCommandId_t *id) {
|
||||||
|
return NOTHING_TO_SEND;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t GyroAdisDummy::buildCommandFromCommand(DeviceCommandId_t deviceCommand,
|
||||||
|
const uint8_t *commandData,
|
||||||
|
size_t commandDataLen) {
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t GyroAdisDummy::scanForReply(const uint8_t *start, size_t len,
|
||||||
|
DeviceCommandId_t *foundId, size_t *foundLen) {
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t GyroAdisDummy::interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) {
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
void GyroAdisDummy::fillCommandAndReplyMap() {}
|
||||||
|
|
||||||
|
uint32_t GyroAdisDummy::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { return 500; }
|
||||||
|
|
||||||
|
ReturnValue_t GyroAdisDummy::initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
|
||||||
|
LocalDataPoolManager &poolManager) {
|
||||||
|
localDataPoolMap.emplace(ADIS1650X::TEMPERATURE, new PoolEntry<float>({0.0}));
|
||||||
|
return HasReturnvaluesIF::RETURN_OK;
|
||||||
|
}
|
33
dummies/GyroAdisDummy.h
Normal file
33
dummies/GyroAdisDummy.h
Normal file
@ -0,0 +1,33 @@
|
|||||||
|
#ifndef DUMMIES_GYROADISDUMMY_H_
|
||||||
|
#define DUMMIES_GYROADISDUMMY_H_
|
||||||
|
|
||||||
|
#include <fsfw/devicehandlers/DeviceHandlerBase.h>
|
||||||
|
|
||||||
|
class GyroAdisDummy : public DeviceHandlerBase {
|
||||||
|
public:
|
||||||
|
static const DeviceCommandId_t SIMPLE_COMMAND = 1;
|
||||||
|
static const DeviceCommandId_t PERIODIC_REPLY = 2;
|
||||||
|
|
||||||
|
static const uint8_t SIMPLE_COMMAND_DATA = 1;
|
||||||
|
static const uint8_t PERIODIC_REPLY_DATA = 2;
|
||||||
|
|
||||||
|
GyroAdisDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie);
|
||||||
|
virtual ~GyroAdisDummy();
|
||||||
|
|
||||||
|
protected:
|
||||||
|
void doStartUp() override;
|
||||||
|
void doShutDown() override;
|
||||||
|
ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t *id) override;
|
||||||
|
ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t *id) override;
|
||||||
|
ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, const uint8_t *commandData,
|
||||||
|
size_t commandDataLen) override;
|
||||||
|
ReturnValue_t scanForReply(const uint8_t *start, size_t len, DeviceCommandId_t *foundId,
|
||||||
|
size_t *foundLen) override;
|
||||||
|
ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) override;
|
||||||
|
void fillCommandAndReplyMap() override;
|
||||||
|
uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override;
|
||||||
|
ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
|
||||||
|
LocalDataPoolManager &poolManager) override;
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif /* DUMMIES_GYROADISDUMMY_H_ */
|
48
dummies/GyroL3GD20Dummy.cpp
Normal file
48
dummies/GyroL3GD20Dummy.cpp
Normal file
@ -0,0 +1,48 @@
|
|||||||
|
#include "GyroL3GD20Dummy.h"
|
||||||
|
|
||||||
|
#include "fsfw_hal/devicehandlers/devicedefinitions/GyroL3GD20Definitions.h"
|
||||||
|
|
||||||
|
GyroL3GD20Dummy::GyroL3GD20Dummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie)
|
||||||
|
: DeviceHandlerBase(objectId, comif, comCookie) {}
|
||||||
|
|
||||||
|
GyroL3GD20Dummy::~GyroL3GD20Dummy() {}
|
||||||
|
|
||||||
|
void GyroL3GD20Dummy::doStartUp() {}
|
||||||
|
|
||||||
|
void GyroL3GD20Dummy::doShutDown() {}
|
||||||
|
|
||||||
|
ReturnValue_t GyroL3GD20Dummy::buildNormalDeviceCommand(DeviceCommandId_t *id) {
|
||||||
|
return NOTHING_TO_SEND;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t GyroL3GD20Dummy::buildTransitionDeviceCommand(DeviceCommandId_t *id) {
|
||||||
|
return NOTHING_TO_SEND;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t GyroL3GD20Dummy::buildCommandFromCommand(DeviceCommandId_t deviceCommand,
|
||||||
|
const uint8_t *commandData,
|
||||||
|
size_t commandDataLen) {
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t GyroL3GD20Dummy::scanForReply(const uint8_t *start, size_t len,
|
||||||
|
DeviceCommandId_t *foundId, size_t *foundLen) {
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t GyroL3GD20Dummy::interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) {
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
void GyroL3GD20Dummy::fillCommandAndReplyMap() {}
|
||||||
|
|
||||||
|
uint32_t GyroL3GD20Dummy::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { return 500; }
|
||||||
|
|
||||||
|
ReturnValue_t GyroL3GD20Dummy::initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
|
||||||
|
LocalDataPoolManager &poolManager) {
|
||||||
|
localDataPoolMap.emplace(L3GD20H::ANG_VELOC_X, new PoolEntry<float>({0.0}));
|
||||||
|
localDataPoolMap.emplace(L3GD20H::ANG_VELOC_Y, new PoolEntry<float>({0.0}));
|
||||||
|
localDataPoolMap.emplace(L3GD20H::ANG_VELOC_Z, new PoolEntry<float>({0.0}));
|
||||||
|
localDataPoolMap.emplace(L3GD20H::TEMPERATURE, new PoolEntry<float>({0.0}));
|
||||||
|
return HasReturnvaluesIF::RETURN_OK;
|
||||||
|
}
|
33
dummies/GyroL3GD20Dummy.h
Normal file
33
dummies/GyroL3GD20Dummy.h
Normal file
@ -0,0 +1,33 @@
|
|||||||
|
#ifndef DUMMIES_GYROL3GD20DUMMY_H_
|
||||||
|
#define DUMMIES_GYROL3GD20DUMMY_H_
|
||||||
|
|
||||||
|
#include <fsfw/devicehandlers/DeviceHandlerBase.h>
|
||||||
|
|
||||||
|
class GyroL3GD20Dummy : public DeviceHandlerBase {
|
||||||
|
public:
|
||||||
|
static const DeviceCommandId_t SIMPLE_COMMAND = 1;
|
||||||
|
static const DeviceCommandId_t PERIODIC_REPLY = 2;
|
||||||
|
|
||||||
|
static const uint8_t SIMPLE_COMMAND_DATA = 1;
|
||||||
|
static const uint8_t PERIODIC_REPLY_DATA = 2;
|
||||||
|
|
||||||
|
GyroL3GD20Dummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie);
|
||||||
|
virtual ~GyroL3GD20Dummy();
|
||||||
|
|
||||||
|
protected:
|
||||||
|
void doStartUp() override;
|
||||||
|
void doShutDown() override;
|
||||||
|
ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t *id) override;
|
||||||
|
ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t *id) override;
|
||||||
|
ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, const uint8_t *commandData,
|
||||||
|
size_t commandDataLen) override;
|
||||||
|
ReturnValue_t scanForReply(const uint8_t *start, size_t len, DeviceCommandId_t *foundId,
|
||||||
|
size_t *foundLen) override;
|
||||||
|
ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) override;
|
||||||
|
void fillCommandAndReplyMap() override;
|
||||||
|
uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override;
|
||||||
|
ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
|
||||||
|
LocalDataPoolManager &poolManager) override;
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif /* DUMMIES_GYROL3GD20DUMMY_H_ */
|
43
dummies/ImtqDummy.cpp
Normal file
43
dummies/ImtqDummy.cpp
Normal file
@ -0,0 +1,43 @@
|
|||||||
|
#include "ImtqDummy.h"
|
||||||
|
|
||||||
|
#include <mission/devices/devicedefinitions/IMTQHandlerDefinitions.h>
|
||||||
|
|
||||||
|
ImtqDummy::ImtqDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie)
|
||||||
|
: DeviceHandlerBase(objectId, comif, comCookie) {}
|
||||||
|
|
||||||
|
ImtqDummy::~ImtqDummy() {}
|
||||||
|
|
||||||
|
void ImtqDummy::doStartUp() {}
|
||||||
|
|
||||||
|
void ImtqDummy::doShutDown() {}
|
||||||
|
|
||||||
|
ReturnValue_t ImtqDummy::buildNormalDeviceCommand(DeviceCommandId_t *id) { return NOTHING_TO_SEND; }
|
||||||
|
|
||||||
|
ReturnValue_t ImtqDummy::buildTransitionDeviceCommand(DeviceCommandId_t *id) {
|
||||||
|
return NOTHING_TO_SEND;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t ImtqDummy::buildCommandFromCommand(DeviceCommandId_t deviceCommand,
|
||||||
|
const uint8_t *commandData,
|
||||||
|
size_t commandDataLen) {
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t ImtqDummy::scanForReply(const uint8_t *start, size_t len, DeviceCommandId_t *foundId,
|
||||||
|
size_t *foundLen) {
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t ImtqDummy::interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) {
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
void ImtqDummy::fillCommandAndReplyMap() {}
|
||||||
|
|
||||||
|
uint32_t ImtqDummy::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { return 500; }
|
||||||
|
|
||||||
|
ReturnValue_t ImtqDummy::initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
|
||||||
|
LocalDataPoolManager &poolManager) {
|
||||||
|
localDataPoolMap.emplace(IMTQ::MCU_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
|
return HasReturnvaluesIF::RETURN_OK;
|
||||||
|
}
|
33
dummies/ImtqDummy.h
Normal file
33
dummies/ImtqDummy.h
Normal file
@ -0,0 +1,33 @@
|
|||||||
|
#ifndef DUMMIES_IMTQDUMMY_H_
|
||||||
|
#define DUMMIES_IMTQDUMMY_H_
|
||||||
|
|
||||||
|
#include <fsfw/devicehandlers/DeviceHandlerBase.h>
|
||||||
|
|
||||||
|
class ImtqDummy : public DeviceHandlerBase {
|
||||||
|
public:
|
||||||
|
static const DeviceCommandId_t SIMPLE_COMMAND = 1;
|
||||||
|
static const DeviceCommandId_t PERIODIC_REPLY = 2;
|
||||||
|
|
||||||
|
static const uint8_t SIMPLE_COMMAND_DATA = 1;
|
||||||
|
static const uint8_t PERIODIC_REPLY_DATA = 2;
|
||||||
|
|
||||||
|
ImtqDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie);
|
||||||
|
virtual ~ImtqDummy();
|
||||||
|
|
||||||
|
protected:
|
||||||
|
void doStartUp() override;
|
||||||
|
void doShutDown() override;
|
||||||
|
ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t *id) override;
|
||||||
|
ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t *id) override;
|
||||||
|
ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, const uint8_t *commandData,
|
||||||
|
size_t commandDataLen) override;
|
||||||
|
ReturnValue_t scanForReply(const uint8_t *start, size_t len, DeviceCommandId_t *foundId,
|
||||||
|
size_t *foundLen) override;
|
||||||
|
ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) override;
|
||||||
|
void fillCommandAndReplyMap() override;
|
||||||
|
uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override;
|
||||||
|
ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
|
||||||
|
LocalDataPoolManager &poolManager) override;
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif /* DUMMIES_IMTQDUMMY_H_ */
|
45
dummies/MgmLIS3MDLDummy.cpp
Normal file
45
dummies/MgmLIS3MDLDummy.cpp
Normal file
@ -0,0 +1,45 @@
|
|||||||
|
#include "MgmLIS3MDLDummy.h"
|
||||||
|
|
||||||
|
#include "fsfw_hal/devicehandlers/devicedefinitions/MgmLIS3HandlerDefs.h"
|
||||||
|
|
||||||
|
MgmLIS3MDLDummy::MgmLIS3MDLDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie)
|
||||||
|
: DeviceHandlerBase(objectId, comif, comCookie) {}
|
||||||
|
|
||||||
|
MgmLIS3MDLDummy::~MgmLIS3MDLDummy() {}
|
||||||
|
|
||||||
|
void MgmLIS3MDLDummy::doStartUp() {}
|
||||||
|
|
||||||
|
void MgmLIS3MDLDummy::doShutDown() {}
|
||||||
|
|
||||||
|
ReturnValue_t MgmLIS3MDLDummy::buildNormalDeviceCommand(DeviceCommandId_t *id) {
|
||||||
|
return NOTHING_TO_SEND;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t MgmLIS3MDLDummy::buildTransitionDeviceCommand(DeviceCommandId_t *id) {
|
||||||
|
return NOTHING_TO_SEND;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t MgmLIS3MDLDummy::buildCommandFromCommand(DeviceCommandId_t deviceCommand,
|
||||||
|
const uint8_t *commandData,
|
||||||
|
size_t commandDataLen) {
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t MgmLIS3MDLDummy::scanForReply(const uint8_t *start, size_t len,
|
||||||
|
DeviceCommandId_t *foundId, size_t *foundLen) {
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t MgmLIS3MDLDummy::interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) {
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
void MgmLIS3MDLDummy::fillCommandAndReplyMap() {}
|
||||||
|
|
||||||
|
uint32_t MgmLIS3MDLDummy::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { return 500; }
|
||||||
|
|
||||||
|
ReturnValue_t MgmLIS3MDLDummy::initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
|
||||||
|
LocalDataPoolManager &poolManager) {
|
||||||
|
localDataPoolMap.emplace(MGMLIS3MDL::TEMPERATURE_CELCIUS, new PoolEntry<float>({0.0}));
|
||||||
|
return HasReturnvaluesIF::RETURN_OK;
|
||||||
|
}
|
33
dummies/MgmLIS3MDLDummy.h
Normal file
33
dummies/MgmLIS3MDLDummy.h
Normal file
@ -0,0 +1,33 @@
|
|||||||
|
#ifndef DUMMIES_MGMLIS3MDLDUMMY_H_
|
||||||
|
#define DUMMIES_MGMLIS3MDLDUMMY_H_
|
||||||
|
|
||||||
|
#include <fsfw/devicehandlers/DeviceHandlerBase.h>
|
||||||
|
|
||||||
|
class MgmLIS3MDLDummy : public DeviceHandlerBase {
|
||||||
|
public:
|
||||||
|
static const DeviceCommandId_t SIMPLE_COMMAND = 1;
|
||||||
|
static const DeviceCommandId_t PERIODIC_REPLY = 2;
|
||||||
|
|
||||||
|
static const uint8_t SIMPLE_COMMAND_DATA = 1;
|
||||||
|
static const uint8_t PERIODIC_REPLY_DATA = 2;
|
||||||
|
|
||||||
|
MgmLIS3MDLDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie);
|
||||||
|
virtual ~MgmLIS3MDLDummy();
|
||||||
|
|
||||||
|
protected:
|
||||||
|
void doStartUp() override;
|
||||||
|
void doShutDown() override;
|
||||||
|
ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t *id) override;
|
||||||
|
ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t *id) override;
|
||||||
|
ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, const uint8_t *commandData,
|
||||||
|
size_t commandDataLen) override;
|
||||||
|
ReturnValue_t scanForReply(const uint8_t *start, size_t len, DeviceCommandId_t *foundId,
|
||||||
|
size_t *foundLen) override;
|
||||||
|
ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) override;
|
||||||
|
void fillCommandAndReplyMap() override;
|
||||||
|
uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override;
|
||||||
|
ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
|
||||||
|
LocalDataPoolManager &poolManager) override;
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif /* DUMMIES_MGMLIS3MDLDUMMY_H_ */
|
46
dummies/P60DockDummy.cpp
Normal file
46
dummies/P60DockDummy.cpp
Normal file
@ -0,0 +1,46 @@
|
|||||||
|
#include "P60DockDummy.h"
|
||||||
|
|
||||||
|
#include <mission/devices/devicedefinitions/GomspaceDefinitions.h>
|
||||||
|
|
||||||
|
P60DockDummy::P60DockDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie)
|
||||||
|
: DeviceHandlerBase(objectId, comif, comCookie) {}
|
||||||
|
|
||||||
|
P60DockDummy::~P60DockDummy() {}
|
||||||
|
|
||||||
|
void P60DockDummy::doStartUp() {}
|
||||||
|
|
||||||
|
void P60DockDummy::doShutDown() {}
|
||||||
|
|
||||||
|
ReturnValue_t P60DockDummy::buildNormalDeviceCommand(DeviceCommandId_t *id) {
|
||||||
|
return NOTHING_TO_SEND;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t P60DockDummy::buildTransitionDeviceCommand(DeviceCommandId_t *id) {
|
||||||
|
return NOTHING_TO_SEND;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t P60DockDummy::buildCommandFromCommand(DeviceCommandId_t deviceCommand,
|
||||||
|
const uint8_t *commandData,
|
||||||
|
size_t commandDataLen) {
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t P60DockDummy::scanForReply(const uint8_t *start, size_t len,
|
||||||
|
DeviceCommandId_t *foundId, size_t *foundLen) {
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t P60DockDummy::interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) {
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
void P60DockDummy::fillCommandAndReplyMap() {}
|
||||||
|
|
||||||
|
uint32_t P60DockDummy::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { return 500; }
|
||||||
|
|
||||||
|
ReturnValue_t P60DockDummy::initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
|
||||||
|
LocalDataPoolManager &poolManager) {
|
||||||
|
localDataPoolMap.emplace(P60System::pool::P60DOCK_TEMPERATURE_1, new PoolEntry<float>({0}));
|
||||||
|
localDataPoolMap.emplace(P60System::pool::P60DOCK_TEMPERATURE_2, new PoolEntry<float>({0}));
|
||||||
|
return HasReturnvaluesIF::RETURN_OK;
|
||||||
|
}
|
33
dummies/P60DockDummy.h
Normal file
33
dummies/P60DockDummy.h
Normal file
@ -0,0 +1,33 @@
|
|||||||
|
#ifndef DUMMIES_P60DOCKDUMMY_H_
|
||||||
|
#define DUMMIES_P60DOCKDUMMY_H_
|
||||||
|
|
||||||
|
#include <fsfw/devicehandlers/DeviceHandlerBase.h>
|
||||||
|
|
||||||
|
class P60DockDummy : public DeviceHandlerBase {
|
||||||
|
public:
|
||||||
|
static const DeviceCommandId_t SIMPLE_COMMAND = 1;
|
||||||
|
static const DeviceCommandId_t PERIODIC_REPLY = 2;
|
||||||
|
|
||||||
|
static const uint8_t SIMPLE_COMMAND_DATA = 1;
|
||||||
|
static const uint8_t PERIODIC_REPLY_DATA = 2;
|
||||||
|
|
||||||
|
P60DockDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie);
|
||||||
|
virtual ~P60DockDummy();
|
||||||
|
|
||||||
|
protected:
|
||||||
|
void doStartUp() override;
|
||||||
|
void doShutDown() override;
|
||||||
|
ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t *id) override;
|
||||||
|
ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t *id) override;
|
||||||
|
ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, const uint8_t *commandData,
|
||||||
|
size_t commandDataLen) override;
|
||||||
|
ReturnValue_t scanForReply(const uint8_t *start, size_t len, DeviceCommandId_t *foundId,
|
||||||
|
size_t *foundLen) override;
|
||||||
|
ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) override;
|
||||||
|
void fillCommandAndReplyMap() override;
|
||||||
|
uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override;
|
||||||
|
ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
|
||||||
|
LocalDataPoolManager &poolManager) override;
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif /* DUMMIES_P60DOCKDUMMY_H_ */
|
42
dummies/PduDummy.cpp
Normal file
42
dummies/PduDummy.cpp
Normal file
@ -0,0 +1,42 @@
|
|||||||
|
#include "PduDummy.h"
|
||||||
|
|
||||||
|
#include <mission/devices/devicedefinitions/GomspaceDefinitions.h>
|
||||||
|
|
||||||
|
PduDummy::PduDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie)
|
||||||
|
: DeviceHandlerBase(objectId, comif, comCookie) {}
|
||||||
|
|
||||||
|
PduDummy::~PduDummy() {}
|
||||||
|
|
||||||
|
void PduDummy::doStartUp() {}
|
||||||
|
|
||||||
|
void PduDummy::doShutDown() {}
|
||||||
|
|
||||||
|
ReturnValue_t PduDummy::buildNormalDeviceCommand(DeviceCommandId_t *id) { return NOTHING_TO_SEND; }
|
||||||
|
|
||||||
|
ReturnValue_t PduDummy::buildTransitionDeviceCommand(DeviceCommandId_t *id) {
|
||||||
|
return NOTHING_TO_SEND;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t PduDummy::buildCommandFromCommand(DeviceCommandId_t deviceCommand,
|
||||||
|
const uint8_t *commandData, size_t commandDataLen) {
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t PduDummy::scanForReply(const uint8_t *start, size_t len, DeviceCommandId_t *foundId,
|
||||||
|
size_t *foundLen) {
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t PduDummy::interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) {
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
void PduDummy::fillCommandAndReplyMap() {}
|
||||||
|
|
||||||
|
uint32_t PduDummy::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { return 500; }
|
||||||
|
|
||||||
|
ReturnValue_t PduDummy::initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
|
||||||
|
LocalDataPoolManager &poolManager) {
|
||||||
|
localDataPoolMap.emplace(P60System::pool::PDU_TEMPERATURE, new PoolEntry<float>({0}));
|
||||||
|
return HasReturnvaluesIF::RETURN_OK;
|
||||||
|
}
|
33
dummies/PduDummy.h
Normal file
33
dummies/PduDummy.h
Normal file
@ -0,0 +1,33 @@
|
|||||||
|
#ifndef DUMMIES_PDUDUMMY_H_
|
||||||
|
#define DUMMIES_PDUDUMMY_H_
|
||||||
|
|
||||||
|
#include <fsfw/devicehandlers/DeviceHandlerBase.h>
|
||||||
|
|
||||||
|
class PduDummy : public DeviceHandlerBase {
|
||||||
|
public:
|
||||||
|
static const DeviceCommandId_t SIMPLE_COMMAND = 1;
|
||||||
|
static const DeviceCommandId_t PERIODIC_REPLY = 2;
|
||||||
|
|
||||||
|
static const uint8_t SIMPLE_COMMAND_DATA = 1;
|
||||||
|
static const uint8_t PERIODIC_REPLY_DATA = 2;
|
||||||
|
|
||||||
|
PduDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie);
|
||||||
|
virtual ~PduDummy();
|
||||||
|
|
||||||
|
protected:
|
||||||
|
void doStartUp() override;
|
||||||
|
void doShutDown() override;
|
||||||
|
ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t *id) override;
|
||||||
|
ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t *id) override;
|
||||||
|
ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, const uint8_t *commandData,
|
||||||
|
size_t commandDataLen) override;
|
||||||
|
ReturnValue_t scanForReply(const uint8_t *start, size_t len, DeviceCommandId_t *foundId,
|
||||||
|
size_t *foundLen) override;
|
||||||
|
ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) override;
|
||||||
|
void fillCommandAndReplyMap() override;
|
||||||
|
uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override;
|
||||||
|
ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
|
||||||
|
LocalDataPoolManager &poolManager) override;
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif /* DUMMIES_PDUDUMMY_H_ */
|
45
dummies/PlPcduDummy.cpp
Normal file
45
dummies/PlPcduDummy.cpp
Normal file
@ -0,0 +1,45 @@
|
|||||||
|
#include "PlPcduDummy.h"
|
||||||
|
|
||||||
|
#include <mission/devices/devicedefinitions/GomspaceDefinitions.h>
|
||||||
|
|
||||||
|
PlPcduDummy::PlPcduDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie)
|
||||||
|
: DeviceHandlerBase(objectId, comif, comCookie) {}
|
||||||
|
|
||||||
|
PlPcduDummy::~PlPcduDummy() {}
|
||||||
|
|
||||||
|
void PlPcduDummy::doStartUp() {}
|
||||||
|
|
||||||
|
void PlPcduDummy::doShutDown() {}
|
||||||
|
|
||||||
|
ReturnValue_t PlPcduDummy::buildNormalDeviceCommand(DeviceCommandId_t *id) {
|
||||||
|
return NOTHING_TO_SEND;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t PlPcduDummy::buildTransitionDeviceCommand(DeviceCommandId_t *id) {
|
||||||
|
return NOTHING_TO_SEND;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t PlPcduDummy::buildCommandFromCommand(DeviceCommandId_t deviceCommand,
|
||||||
|
const uint8_t *commandData,
|
||||||
|
size_t commandDataLen) {
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t PlPcduDummy::scanForReply(const uint8_t *start, size_t len,
|
||||||
|
DeviceCommandId_t *foundId, size_t *foundLen) {
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t PlPcduDummy::interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) {
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
void PlPcduDummy::fillCommandAndReplyMap() {}
|
||||||
|
|
||||||
|
uint32_t PlPcduDummy::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { return 500; }
|
||||||
|
|
||||||
|
ReturnValue_t PlPcduDummy::initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
|
||||||
|
LocalDataPoolManager &poolManager) {
|
||||||
|
localDataPoolMap.emplace(plpcdu::PlPcduPoolIds::TEMP, new PoolEntry<float>({0.0}));
|
||||||
|
return HasReturnvaluesIF::RETURN_OK;
|
||||||
|
}
|
34
dummies/PlPcduDummy.h
Normal file
34
dummies/PlPcduDummy.h
Normal file
@ -0,0 +1,34 @@
|
|||||||
|
#ifndef DUMMIES_PLPCDUDUMMY_H_
|
||||||
|
#define DUMMIES_PLPCDUDUMMY_H_
|
||||||
|
|
||||||
|
#include <fsfw/devicehandlers/DeviceHandlerBase.h>
|
||||||
|
#include <mission/devices/devicedefinitions/payloadPcduDefinitions.h>
|
||||||
|
|
||||||
|
class PlPcduDummy : public DeviceHandlerBase {
|
||||||
|
public:
|
||||||
|
static const DeviceCommandId_t SIMPLE_COMMAND = 1;
|
||||||
|
static const DeviceCommandId_t PERIODIC_REPLY = 2;
|
||||||
|
|
||||||
|
static const uint8_t SIMPLE_COMMAND_DATA = 1;
|
||||||
|
static const uint8_t PERIODIC_REPLY_DATA = 2;
|
||||||
|
|
||||||
|
PlPcduDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie);
|
||||||
|
virtual ~PlPcduDummy();
|
||||||
|
|
||||||
|
protected:
|
||||||
|
void doStartUp() override;
|
||||||
|
void doShutDown() override;
|
||||||
|
ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t *id) override;
|
||||||
|
ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t *id) override;
|
||||||
|
ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, const uint8_t *commandData,
|
||||||
|
size_t commandDataLen) override;
|
||||||
|
ReturnValue_t scanForReply(const uint8_t *start, size_t len, DeviceCommandId_t *foundId,
|
||||||
|
size_t *foundLen) override;
|
||||||
|
ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) override;
|
||||||
|
void fillCommandAndReplyMap() override;
|
||||||
|
uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override;
|
||||||
|
ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
|
||||||
|
LocalDataPoolManager &poolManager) override;
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif /* DUMMIES_PLPCDUDUMMY_H_ */
|
75
dummies/RwDummy.cpp
Normal file
75
dummies/RwDummy.cpp
Normal file
@ -0,0 +1,75 @@
|
|||||||
|
#include "RwDummy.h"
|
||||||
|
|
||||||
|
#include <mission/devices/devicedefinitions/RwDefinitions.h>
|
||||||
|
|
||||||
|
RwDummy::RwDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie)
|
||||||
|
: DeviceHandlerBase(objectId, comif, comCookie) {}
|
||||||
|
|
||||||
|
RwDummy::~RwDummy() {}
|
||||||
|
|
||||||
|
void RwDummy::doStartUp() {}
|
||||||
|
|
||||||
|
void RwDummy::doShutDown() {}
|
||||||
|
|
||||||
|
ReturnValue_t RwDummy::buildNormalDeviceCommand(DeviceCommandId_t *id) { return NOTHING_TO_SEND; }
|
||||||
|
|
||||||
|
ReturnValue_t RwDummy::buildTransitionDeviceCommand(DeviceCommandId_t *id) {
|
||||||
|
return NOTHING_TO_SEND;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t RwDummy::buildCommandFromCommand(DeviceCommandId_t deviceCommand,
|
||||||
|
const uint8_t *commandData, size_t commandDataLen) {
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t RwDummy::scanForReply(const uint8_t *start, size_t len, DeviceCommandId_t *foundId,
|
||||||
|
size_t *foundLen) {
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t RwDummy::interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) {
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
void RwDummy::fillCommandAndReplyMap() {}
|
||||||
|
|
||||||
|
uint32_t RwDummy::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { return 500; }
|
||||||
|
|
||||||
|
ReturnValue_t RwDummy::initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
|
||||||
|
LocalDataPoolManager &poolManager) {
|
||||||
|
localDataPoolMap.emplace(RwDefinitions::TEMPERATURE_C, new PoolEntry<int32_t>({0}));
|
||||||
|
|
||||||
|
localDataPoolMap.emplace(RwDefinitions::CURR_SPEED, new PoolEntry<int32_t>({0}));
|
||||||
|
localDataPoolMap.emplace(RwDefinitions::REFERENCE_SPEED, new PoolEntry<int32_t>({0}));
|
||||||
|
localDataPoolMap.emplace(RwDefinitions::STATE, new PoolEntry<uint8_t>({0}));
|
||||||
|
localDataPoolMap.emplace(RwDefinitions::CLC_MODE, new PoolEntry<uint8_t>({0}));
|
||||||
|
|
||||||
|
localDataPoolMap.emplace(RwDefinitions::LAST_RESET_STATUS, new PoolEntry<uint8_t>({0}));
|
||||||
|
localDataPoolMap.emplace(RwDefinitions::CURRRENT_RESET_STATUS, new PoolEntry<uint8_t>({0}));
|
||||||
|
|
||||||
|
localDataPoolMap.emplace(RwDefinitions::TM_LAST_RESET_STATUS, new PoolEntry<uint8_t>({0}));
|
||||||
|
localDataPoolMap.emplace(RwDefinitions::TM_MCU_TEMPERATURE, new PoolEntry<int32_t>({0}));
|
||||||
|
localDataPoolMap.emplace(RwDefinitions::PRESSURE_SENSOR_TEMPERATURE, new PoolEntry<float>({0}));
|
||||||
|
localDataPoolMap.emplace(RwDefinitions::PRESSURE, new PoolEntry<float>({0}));
|
||||||
|
localDataPoolMap.emplace(RwDefinitions::TM_RW_STATE, new PoolEntry<uint8_t>({0}));
|
||||||
|
localDataPoolMap.emplace(RwDefinitions::TM_CLC_MODE, new PoolEntry<uint8_t>({0}));
|
||||||
|
localDataPoolMap.emplace(RwDefinitions::TM_RW_CURR_SPEED, new PoolEntry<int32_t>({0}));
|
||||||
|
localDataPoolMap.emplace(RwDefinitions::TM_RW_REF_SPEED, new PoolEntry<int32_t>({0}));
|
||||||
|
localDataPoolMap.emplace(RwDefinitions::INVALID_CRC_PACKETS, new PoolEntry<uint32_t>({0}));
|
||||||
|
localDataPoolMap.emplace(RwDefinitions::INVALID_LEN_PACKETS, new PoolEntry<uint32_t>({0}));
|
||||||
|
localDataPoolMap.emplace(RwDefinitions::INVALID_CMD_PACKETS, new PoolEntry<uint32_t>({0}));
|
||||||
|
localDataPoolMap.emplace(RwDefinitions::EXECUTED_REPLIES, new PoolEntry<uint32_t>({0}));
|
||||||
|
localDataPoolMap.emplace(RwDefinitions::COMMAND_REPLIES, new PoolEntry<uint32_t>({0}));
|
||||||
|
localDataPoolMap.emplace(RwDefinitions::UART_BYTES_WRITTEN, new PoolEntry<uint32_t>({0}));
|
||||||
|
localDataPoolMap.emplace(RwDefinitions::UART_BYTES_READ, new PoolEntry<uint32_t>({0}));
|
||||||
|
localDataPoolMap.emplace(RwDefinitions::UART_PARITY_ERRORS, new PoolEntry<uint32_t>({0}));
|
||||||
|
localDataPoolMap.emplace(RwDefinitions::UART_NOISE_ERRORS, new PoolEntry<uint32_t>({0}));
|
||||||
|
localDataPoolMap.emplace(RwDefinitions::UART_FRAME_ERRORS, new PoolEntry<uint32_t>({0}));
|
||||||
|
localDataPoolMap.emplace(RwDefinitions::UART_REG_OVERRUN_ERRORS, new PoolEntry<uint32_t>({0}));
|
||||||
|
localDataPoolMap.emplace(RwDefinitions::UART_TOTAL_ERRORS, new PoolEntry<uint32_t>({0}));
|
||||||
|
localDataPoolMap.emplace(RwDefinitions::SPI_BYTES_WRITTEN, new PoolEntry<uint32_t>({0}));
|
||||||
|
localDataPoolMap.emplace(RwDefinitions::SPI_BYTES_READ, new PoolEntry<uint32_t>({0}));
|
||||||
|
localDataPoolMap.emplace(RwDefinitions::SPI_REG_OVERRUN_ERRORS, new PoolEntry<uint32_t>({0}));
|
||||||
|
localDataPoolMap.emplace(RwDefinitions::SPI_TOTAL_ERRORS, new PoolEntry<uint32_t>({0}));
|
||||||
|
return HasReturnvaluesIF::RETURN_OK;
|
||||||
|
}
|
33
dummies/RwDummy.h
Normal file
33
dummies/RwDummy.h
Normal file
@ -0,0 +1,33 @@
|
|||||||
|
#ifndef DUMMIES_RWDUMMY_H_
|
||||||
|
#define DUMMIES_RWDUMMY_H_
|
||||||
|
|
||||||
|
#include <fsfw/devicehandlers/DeviceHandlerBase.h>
|
||||||
|
|
||||||
|
class RwDummy : public DeviceHandlerBase {
|
||||||
|
public:
|
||||||
|
static const DeviceCommandId_t SIMPLE_COMMAND = 1;
|
||||||
|
static const DeviceCommandId_t PERIODIC_REPLY = 2;
|
||||||
|
|
||||||
|
static const uint8_t SIMPLE_COMMAND_DATA = 1;
|
||||||
|
static const uint8_t PERIODIC_REPLY_DATA = 2;
|
||||||
|
|
||||||
|
RwDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie);
|
||||||
|
virtual ~RwDummy();
|
||||||
|
|
||||||
|
protected:
|
||||||
|
void doStartUp() override;
|
||||||
|
void doShutDown() override;
|
||||||
|
ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t *id) override;
|
||||||
|
ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t *id) override;
|
||||||
|
ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, const uint8_t *commandData,
|
||||||
|
size_t commandDataLen) override;
|
||||||
|
ReturnValue_t scanForReply(const uint8_t *start, size_t len, DeviceCommandId_t *foundId,
|
||||||
|
size_t *foundLen) override;
|
||||||
|
ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) override;
|
||||||
|
void fillCommandAndReplyMap() override;
|
||||||
|
uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override;
|
||||||
|
ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
|
||||||
|
LocalDataPoolManager &poolManager) override;
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif /* DUMMIES_RWDUMMY_H_ */
|
45
dummies/StarTrackerDummy.cpp
Normal file
45
dummies/StarTrackerDummy.cpp
Normal file
@ -0,0 +1,45 @@
|
|||||||
|
#include "StarTrackerDummy.h"
|
||||||
|
|
||||||
|
#include <linux/devices/devicedefinitions/StarTrackerDefinitions.h>
|
||||||
|
|
||||||
|
StarTrackerDummy::StarTrackerDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie)
|
||||||
|
: DeviceHandlerBase(objectId, comif, comCookie) {}
|
||||||
|
|
||||||
|
StarTrackerDummy::~StarTrackerDummy() {}
|
||||||
|
|
||||||
|
void StarTrackerDummy::doStartUp() {}
|
||||||
|
|
||||||
|
void StarTrackerDummy::doShutDown() {}
|
||||||
|
|
||||||
|
ReturnValue_t StarTrackerDummy::buildNormalDeviceCommand(DeviceCommandId_t *id) {
|
||||||
|
return NOTHING_TO_SEND;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t StarTrackerDummy::buildTransitionDeviceCommand(DeviceCommandId_t *id) {
|
||||||
|
return NOTHING_TO_SEND;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t StarTrackerDummy::buildCommandFromCommand(DeviceCommandId_t deviceCommand,
|
||||||
|
const uint8_t *commandData,
|
||||||
|
size_t commandDataLen) {
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t StarTrackerDummy::scanForReply(const uint8_t *start, size_t len,
|
||||||
|
DeviceCommandId_t *foundId, size_t *foundLen) {
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t StarTrackerDummy::interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) {
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
void StarTrackerDummy::fillCommandAndReplyMap() {}
|
||||||
|
|
||||||
|
uint32_t StarTrackerDummy::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { return 500; }
|
||||||
|
|
||||||
|
ReturnValue_t StarTrackerDummy::initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
|
||||||
|
LocalDataPoolManager &poolManager) {
|
||||||
|
localDataPoolMap.emplace(startracker::MCU_TEMPERATURE, new PoolEntry<float>({0}));
|
||||||
|
return HasReturnvaluesIF::RETURN_OK;
|
||||||
|
}
|
33
dummies/StarTrackerDummy.h
Normal file
33
dummies/StarTrackerDummy.h
Normal file
@ -0,0 +1,33 @@
|
|||||||
|
#ifndef DUMMIES_STARTRACKERDUMMY_H_
|
||||||
|
#define DUMMIES_STARTRACKERDUMMY_H_
|
||||||
|
|
||||||
|
#include <fsfw/devicehandlers/DeviceHandlerBase.h>
|
||||||
|
|
||||||
|
class StarTrackerDummy : public DeviceHandlerBase {
|
||||||
|
public:
|
||||||
|
static const DeviceCommandId_t SIMPLE_COMMAND = 1;
|
||||||
|
static const DeviceCommandId_t PERIODIC_REPLY = 2;
|
||||||
|
|
||||||
|
static const uint8_t SIMPLE_COMMAND_DATA = 1;
|
||||||
|
static const uint8_t PERIODIC_REPLY_DATA = 2;
|
||||||
|
|
||||||
|
StarTrackerDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie);
|
||||||
|
virtual ~StarTrackerDummy();
|
||||||
|
|
||||||
|
protected:
|
||||||
|
void doStartUp() override;
|
||||||
|
void doShutDown() override;
|
||||||
|
ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t *id) override;
|
||||||
|
ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t *id) override;
|
||||||
|
ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, const uint8_t *commandData,
|
||||||
|
size_t commandDataLen) override;
|
||||||
|
ReturnValue_t scanForReply(const uint8_t *start, size_t len, DeviceCommandId_t *foundId,
|
||||||
|
size_t *foundLen) override;
|
||||||
|
ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) override;
|
||||||
|
void fillCommandAndReplyMap() override;
|
||||||
|
uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override;
|
||||||
|
ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
|
||||||
|
LocalDataPoolManager &poolManager) override;
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif /* DUMMIES_STARTRACKERDUMMY_H_ */
|
78
dummies/SusDummy.cpp
Normal file
78
dummies/SusDummy.cpp
Normal file
@ -0,0 +1,78 @@
|
|||||||
|
#include "SusDummy.h"
|
||||||
|
|
||||||
|
#include <objects/systemObjectList.h>
|
||||||
|
|
||||||
|
#include <cmath>
|
||||||
|
#include <cstdlib>
|
||||||
|
|
||||||
|
SusDummy::SusDummy()
|
||||||
|
: ExtendedControllerBase(objects::SUS_0_N_LOC_XFYFZM_PT_XF, objects::NO_OBJECT), susSet(this) {
|
||||||
|
ObjectManager::instance()->insert(objects::SUS_6_R_LOC_XFYBZM_PT_XF, this);
|
||||||
|
ObjectManager::instance()->insert(objects::SUS_1_N_LOC_XBYFZM_PT_XB, this);
|
||||||
|
ObjectManager::instance()->insert(objects::SUS_7_R_LOC_XBYBZM_PT_XB, this);
|
||||||
|
ObjectManager::instance()->insert(objects::SUS_2_N_LOC_XFYBZB_PT_YB, this);
|
||||||
|
ObjectManager::instance()->insert(objects::SUS_8_R_LOC_XBYBZB_PT_YB, this);
|
||||||
|
ObjectManager::instance()->insert(objects::SUS_3_N_LOC_XFYBZF_PT_YF, this);
|
||||||
|
ObjectManager::instance()->insert(objects::SUS_9_R_LOC_XBYBZB_PT_YF, this);
|
||||||
|
ObjectManager::instance()->insert(objects::SUS_4_N_LOC_XMYFZF_PT_ZF, this);
|
||||||
|
ObjectManager::instance()->insert(objects::SUS_10_N_LOC_XMYBZF_PT_ZF, this);
|
||||||
|
ObjectManager::instance()->insert(objects::SUS_5_N_LOC_XFYMZB_PT_ZB, this);
|
||||||
|
ObjectManager::instance()->insert(objects::SUS_11_R_LOC_XBYMZB_PT_ZB, this);
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t SusDummy::initialize() {
|
||||||
|
static bool done = false;
|
||||||
|
if (not done) {
|
||||||
|
done = true;
|
||||||
|
ReturnValue_t result = ExtendedControllerBase::initialize();
|
||||||
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return HasReturnvaluesIF::RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t SusDummy::handleCommandMessage(CommandMessage* message) { return RETURN_FAILED; }
|
||||||
|
|
||||||
|
void SusDummy::performControlOperation() {
|
||||||
|
iteration++;
|
||||||
|
value = sin(iteration / 80. * M_PI + 10) * 10 - 10;
|
||||||
|
|
||||||
|
susSet.read();
|
||||||
|
susSet.temperatureCelcius = value;
|
||||||
|
if ((iteration % 100) < 20) {
|
||||||
|
susSet.setValidity(false, true);
|
||||||
|
} else {
|
||||||
|
susSet.setValidity(true, true);
|
||||||
|
}
|
||||||
|
susSet.commit();
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t SusDummy::initializeLocalDataPool(localpool::DataPool& localDataPoolMap,
|
||||||
|
LocalDataPoolManager& poolManager) {
|
||||||
|
localDataPoolMap.emplace(SUS::SusPoolIds::TEMPERATURE_C, new PoolEntry<float>({0}, 1, true));
|
||||||
|
localDataPoolMap.emplace(SUS::SusPoolIds::CHANNEL_VEC, new PoolEntry<uint16_t>({0}));
|
||||||
|
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
LocalPoolDataSetBase* SusDummy::getDataSetHandle(sid_t sid) {
|
||||||
|
switch (sid.ownerSetId) {
|
||||||
|
case SUS::SUS_DATA_SET_ID:
|
||||||
|
return &susSet;
|
||||||
|
default:
|
||||||
|
return nullptr;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t SusDummy::checkModeCommand(Mode_t mode, Submode_t submode,
|
||||||
|
uint32_t* msToReachTheMode) {
|
||||||
|
if (submode != SUBMODE_NONE) {
|
||||||
|
return INVALID_SUBMODE;
|
||||||
|
}
|
||||||
|
if ((mode != MODE_OFF) && (mode != MODE_ON) && (mode != MODE_NORMAL)) {
|
||||||
|
return INVALID_MODE;
|
||||||
|
}
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
27
dummies/SusDummy.h
Normal file
27
dummies/SusDummy.h
Normal file
@ -0,0 +1,27 @@
|
|||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include <fsfw/controller/ExtendedControllerBase.h>
|
||||||
|
#include <mission/devices/devicedefinitions/SusDefinitions.h>
|
||||||
|
|
||||||
|
class SusDummy : public ExtendedControllerBase {
|
||||||
|
public:
|
||||||
|
SusDummy();
|
||||||
|
|
||||||
|
ReturnValue_t initialize() override;
|
||||||
|
|
||||||
|
protected:
|
||||||
|
virtual ReturnValue_t handleCommandMessage(CommandMessage* message) override;
|
||||||
|
virtual void performControlOperation() override;
|
||||||
|
virtual ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap,
|
||||||
|
LocalDataPoolManager& poolManager) override;
|
||||||
|
virtual LocalPoolDataSetBase* getDataSetHandle(sid_t sid) override;
|
||||||
|
|
||||||
|
// Mode abstract functions
|
||||||
|
virtual ReturnValue_t checkModeCommand(Mode_t mode, Submode_t submode,
|
||||||
|
uint32_t* msToReachTheMode) override;
|
||||||
|
|
||||||
|
private:
|
||||||
|
int iteration = 0;
|
||||||
|
float value = 0;
|
||||||
|
SUS::SusDataset susSet;
|
||||||
|
};
|
46
dummies/SyrlinksDummy.cpp
Normal file
46
dummies/SyrlinksDummy.cpp
Normal file
@ -0,0 +1,46 @@
|
|||||||
|
#include "SyrlinksDummy.h"
|
||||||
|
|
||||||
|
#include <mission/devices/devicedefinitions/SyrlinksDefinitions.h>
|
||||||
|
|
||||||
|
SyrlinksDummy::SyrlinksDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie)
|
||||||
|
: DeviceHandlerBase(objectId, comif, comCookie) {}
|
||||||
|
|
||||||
|
SyrlinksDummy::~SyrlinksDummy() {}
|
||||||
|
|
||||||
|
void SyrlinksDummy::doStartUp() {}
|
||||||
|
|
||||||
|
void SyrlinksDummy::doShutDown() {}
|
||||||
|
|
||||||
|
ReturnValue_t SyrlinksDummy::buildNormalDeviceCommand(DeviceCommandId_t *id) {
|
||||||
|
return NOTHING_TO_SEND;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t SyrlinksDummy::buildTransitionDeviceCommand(DeviceCommandId_t *id) {
|
||||||
|
return NOTHING_TO_SEND;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t SyrlinksDummy::buildCommandFromCommand(DeviceCommandId_t deviceCommand,
|
||||||
|
const uint8_t *commandData,
|
||||||
|
size_t commandDataLen) {
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t SyrlinksDummy::scanForReply(const uint8_t *start, size_t len,
|
||||||
|
DeviceCommandId_t *foundId, size_t *foundLen) {
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t SyrlinksDummy::interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) {
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
void SyrlinksDummy::fillCommandAndReplyMap() {}
|
||||||
|
|
||||||
|
uint32_t SyrlinksDummy::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { return 500; }
|
||||||
|
|
||||||
|
ReturnValue_t SyrlinksDummy::initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
|
||||||
|
LocalDataPoolManager &poolManager) {
|
||||||
|
localDataPoolMap.emplace(syrlinks::TEMP_BASEBAND_BOARD, new PoolEntry<float>({0}));
|
||||||
|
localDataPoolMap.emplace(syrlinks::TEMP_POWER_AMPLIFIER, new PoolEntry<float>({0}));
|
||||||
|
return HasReturnvaluesIF::RETURN_OK;
|
||||||
|
}
|
33
dummies/SyrlinksDummy.h
Normal file
33
dummies/SyrlinksDummy.h
Normal file
@ -0,0 +1,33 @@
|
|||||||
|
#ifndef DUMMIES_SYRLINKSDUMMY_H_
|
||||||
|
#define DUMMIES_SYRLINKSDUMMY_H_
|
||||||
|
|
||||||
|
#include <fsfw/devicehandlers/DeviceHandlerBase.h>
|
||||||
|
|
||||||
|
class SyrlinksDummy : public DeviceHandlerBase {
|
||||||
|
public:
|
||||||
|
static const DeviceCommandId_t SIMPLE_COMMAND = 1;
|
||||||
|
static const DeviceCommandId_t PERIODIC_REPLY = 2;
|
||||||
|
|
||||||
|
static const uint8_t SIMPLE_COMMAND_DATA = 1;
|
||||||
|
static const uint8_t PERIODIC_REPLY_DATA = 2;
|
||||||
|
|
||||||
|
SyrlinksDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie);
|
||||||
|
virtual ~SyrlinksDummy();
|
||||||
|
|
||||||
|
protected:
|
||||||
|
void doStartUp() override;
|
||||||
|
void doShutDown() override;
|
||||||
|
ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t *id) override;
|
||||||
|
ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t *id) override;
|
||||||
|
ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, const uint8_t *commandData,
|
||||||
|
size_t commandDataLen) override;
|
||||||
|
ReturnValue_t scanForReply(const uint8_t *start, size_t len, DeviceCommandId_t *foundId,
|
||||||
|
size_t *foundLen) override;
|
||||||
|
ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) override;
|
||||||
|
void fillCommandAndReplyMap() override;
|
||||||
|
uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override;
|
||||||
|
ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
|
||||||
|
LocalDataPoolManager &poolManager) override;
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif /* DUMMIES_SYRLINKSDUMMY_H_ */
|
98
dummies/TemperatureSensorsDummy.cpp
Normal file
98
dummies/TemperatureSensorsDummy.cpp
Normal file
@ -0,0 +1,98 @@
|
|||||||
|
#include "TemperatureSensorsDummy.h"
|
||||||
|
|
||||||
|
#include <objects/systemObjectList.h>
|
||||||
|
|
||||||
|
#include <cmath>
|
||||||
|
#include <cstdlib>
|
||||||
|
|
||||||
|
TemperatureSensorsDummy::TemperatureSensorsDummy()
|
||||||
|
: ExtendedControllerBase(objects::RTD_0_IC3_PLOC_HEATSPREADER, objects::NO_OBJECT),
|
||||||
|
max31865Set(this, MAX31865::MAX31865_SET_ID) {
|
||||||
|
ObjectManager::instance()->insert(objects::RTD_1_IC4_PLOC_MISSIONBOARD, this);
|
||||||
|
ObjectManager::instance()->insert(objects::RTD_2_IC5_4K_CAMERA, this);
|
||||||
|
ObjectManager::instance()->insert(objects::RTD_3_IC6_DAC_HEATSPREADER, this);
|
||||||
|
ObjectManager::instance()->insert(objects::RTD_4_IC7_STARTRACKER, this);
|
||||||
|
ObjectManager::instance()->insert(objects::RTD_5_IC8_RW1_MX_MY, this);
|
||||||
|
ObjectManager::instance()->insert(objects::RTD_6_IC9_DRO, this);
|
||||||
|
ObjectManager::instance()->insert(objects::RTD_7_IC10_SCEX, this);
|
||||||
|
ObjectManager::instance()->insert(objects::RTD_8_IC11_X8, this);
|
||||||
|
ObjectManager::instance()->insert(objects::RTD_9_IC12_HPA, this);
|
||||||
|
ObjectManager::instance()->insert(objects::RTD_10_IC13_PL_TX, this);
|
||||||
|
ObjectManager::instance()->insert(objects::RTD_11_IC14_MPA, this);
|
||||||
|
ObjectManager::instance()->insert(objects::RTD_12_IC15_ACU, this);
|
||||||
|
ObjectManager::instance()->insert(objects::RTD_13_IC16_PLPCDU_HEATSPREADER, this);
|
||||||
|
ObjectManager::instance()->insert(objects::RTD_14_IC17_TCS_BOARD, this);
|
||||||
|
ObjectManager::instance()->insert(objects::RTD_15_IC18_IMTQ, this);
|
||||||
|
ObjectManager::instance()->insert(objects::TMP1075_HANDLER_1, this);
|
||||||
|
ObjectManager::instance()->insert(objects::TMP1075_HANDLER_2, this);
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t TemperatureSensorsDummy::initialize() {
|
||||||
|
static bool done = false;
|
||||||
|
if (not done) {
|
||||||
|
done = true;
|
||||||
|
ReturnValue_t result = ExtendedControllerBase::initialize();
|
||||||
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return HasReturnvaluesIF::RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t TemperatureSensorsDummy::handleCommandMessage(CommandMessage* message) {
|
||||||
|
return RETURN_FAILED;
|
||||||
|
}
|
||||||
|
|
||||||
|
void TemperatureSensorsDummy::performControlOperation() {
|
||||||
|
iteration++;
|
||||||
|
value = sin(iteration / 80. * M_PI) * 10;
|
||||||
|
|
||||||
|
ReturnValue_t result = max31865Set.read();
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
sif::warning << "Failed to read temperature from MAX31865 dataset" << std::endl;
|
||||||
|
}
|
||||||
|
max31865Set.rtdValue = value - 5;
|
||||||
|
max31865Set.temperatureCelcius = value;
|
||||||
|
if ((iteration % 100) < 20) {
|
||||||
|
max31865Set.setValidity(false, true);
|
||||||
|
} else {
|
||||||
|
max31865Set.setValidity(true, true);
|
||||||
|
}
|
||||||
|
max31865Set.commit();
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t TemperatureSensorsDummy::initializeLocalDataPool(
|
||||||
|
localpool::DataPool& localDataPoolMap, LocalDataPoolManager& poolManager) {
|
||||||
|
localDataPoolMap.emplace(static_cast<lp_id_t>(MAX31865::PoolIds::RTD_VALUE),
|
||||||
|
new PoolEntry<float>({0}));
|
||||||
|
localDataPoolMap.emplace(static_cast<lp_id_t>(MAX31865::PoolIds::TEMPERATURE_C),
|
||||||
|
new PoolEntry<float>({0}));
|
||||||
|
localDataPoolMap.emplace(static_cast<lp_id_t>(MAX31865::PoolIds::LAST_FAULT_BYTE),
|
||||||
|
new PoolEntry<uint8_t>({0}));
|
||||||
|
localDataPoolMap.emplace(static_cast<lp_id_t>(MAX31865::PoolIds::FAULT_BYTE),
|
||||||
|
new PoolEntry<uint8_t>({0}));
|
||||||
|
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
LocalPoolDataSetBase* TemperatureSensorsDummy::getDataSetHandle(sid_t sid) {
|
||||||
|
sif::debug << "getHandle" << std::endl;
|
||||||
|
switch (sid.ownerSetId) {
|
||||||
|
case MAX31865::MAX31865_SET_ID:
|
||||||
|
return &max31865Set;
|
||||||
|
default:
|
||||||
|
return nullptr;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t TemperatureSensorsDummy::checkModeCommand(Mode_t mode, Submode_t submode,
|
||||||
|
uint32_t* msToReachTheMode) {
|
||||||
|
if (submode != SUBMODE_NONE) {
|
||||||
|
return INVALID_SUBMODE;
|
||||||
|
}
|
||||||
|
if ((mode != MODE_OFF) && (mode != MODE_ON) && (mode != MODE_NORMAL)) {
|
||||||
|
return INVALID_MODE;
|
||||||
|
}
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
29
dummies/TemperatureSensorsDummy.h
Normal file
29
dummies/TemperatureSensorsDummy.h
Normal file
@ -0,0 +1,29 @@
|
|||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include <fsfw/controller/ExtendedControllerBase.h>
|
||||||
|
#include <mission/devices/devicedefinitions/Max31865Definitions.h>
|
||||||
|
|
||||||
|
class TemperatureSensorsDummy : public ExtendedControllerBase {
|
||||||
|
public:
|
||||||
|
TemperatureSensorsDummy();
|
||||||
|
|
||||||
|
ReturnValue_t initialize() override;
|
||||||
|
|
||||||
|
protected:
|
||||||
|
virtual ReturnValue_t handleCommandMessage(CommandMessage* message) override;
|
||||||
|
virtual void performControlOperation() override;
|
||||||
|
virtual ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap,
|
||||||
|
LocalDataPoolManager& poolManager) override;
|
||||||
|
virtual LocalPoolDataSetBase* getDataSetHandle(sid_t sid) override;
|
||||||
|
|
||||||
|
// Mode abstract functions
|
||||||
|
virtual ReturnValue_t checkModeCommand(Mode_t mode, Submode_t submode,
|
||||||
|
uint32_t* msToReachTheMode) override;
|
||||||
|
|
||||||
|
private:
|
||||||
|
int iteration = 0;
|
||||||
|
float value = 0;
|
||||||
|
MAX31865::Max31865Set max31865Set;
|
||||||
|
|
||||||
|
void noise();
|
||||||
|
};
|
2
fsfw
2
fsfw
@ -1 +1 @@
|
|||||||
Subproject commit 1910a7838c712f1cf34031d2a8b53e2f7cd24f66
|
Subproject commit 6a62cf7f1e47d627346916f3605829118ffd8357
|
@ -1,3 +1,4 @@
|
|||||||
|
Event ID (dec); Event ID (hex); Name; Severity; Description; File Path
|
||||||
2200;0x0898;STORE_SEND_WRITE_FAILED;LOW;;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
|
2200;0x0898;STORE_SEND_WRITE_FAILED;LOW;;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
|
||||||
2201;0x0899;STORE_WRITE_FAILED;LOW;;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
|
2201;0x0899;STORE_WRITE_FAILED;LOW;;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
|
||||||
2202;0x089a;STORE_SEND_READ_FAILED;LOW;;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
|
2202;0x089a;STORE_SEND_READ_FAILED;LOW;;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
|
||||||
@ -127,6 +128,8 @@
|
|||||||
12402;0x3072;INVALID_FAR;HIGH;Read invalid FAR from PDEC after startup;linux/obc/PdecHandler.h
|
12402;0x3072;INVALID_FAR;HIGH;Read invalid FAR from PDEC after startup;linux/obc/PdecHandler.h
|
||||||
12403;0x3073;CARRIER_LOCK;INFO;Carrier lock detected;linux/obc/PdecHandler.h
|
12403;0x3073;CARRIER_LOCK;INFO;Carrier lock detected;linux/obc/PdecHandler.h
|
||||||
12404;0x3074;BIT_LOCK_PDEC;INFO;Bit lock detected (data valid);linux/obc/PdecHandler.h
|
12404;0x3074;BIT_LOCK_PDEC;INFO;Bit lock detected (data valid);linux/obc/PdecHandler.h
|
||||||
|
12405;0x3075;LOST_CARRIER_LOCK_PDEC;INFO;Lost carrier lock;linux/obc/PdecHandler.h
|
||||||
|
12406;0x3076;LOST_BIT_LOCK_PDEC;INFO;Lost bit lock;linux/obc/PdecHandler.h
|
||||||
12500;0x30d4;IMAGE_UPLOAD_FAILED;LOW;Image upload failed;linux/devices/startracker/StrHelper.h
|
12500;0x30d4;IMAGE_UPLOAD_FAILED;LOW;Image upload failed;linux/devices/startracker/StrHelper.h
|
||||||
12501;0x30d5;IMAGE_DOWNLOAD_FAILED;LOW;Image download failed;linux/devices/startracker/StrHelper.h
|
12501;0x30d5;IMAGE_DOWNLOAD_FAILED;LOW;Image download failed;linux/devices/startracker/StrHelper.h
|
||||||
12502;0x30d6;IMAGE_UPLOAD_SUCCESSFUL;LOW;Uploading image to star tracker was successfulop;linux/devices/startracker/StrHelper.h
|
12502;0x30d6;IMAGE_UPLOAD_SUCCESSFUL;LOW;Uploading image to star tracker was successfulop;linux/devices/startracker/StrHelper.h
|
||||||
|
|
@ -110,6 +110,7 @@
|
|||||||
0x54000010;SPI_TEST
|
0x54000010;SPI_TEST
|
||||||
0x54000020;UART_TEST
|
0x54000020;UART_TEST
|
||||||
0x54000030;I2C_TEST
|
0x54000030;I2C_TEST
|
||||||
|
0x54000040;DUMMY_COM_IF
|
||||||
0x5400AFFE;DUMMY_HANDLER
|
0x5400AFFE;DUMMY_HANDLER
|
||||||
0x5400CAFE;DUMMY_INTERFACE
|
0x5400CAFE;DUMMY_INTERFACE
|
||||||
0x54123456;LIBGPIOD_TEST
|
0x54123456;LIBGPIOD_TEST
|
||||||
|
|
File diff suppressed because it is too large
Load Diff
1
generators/deps/fsfwgen
Submodule
1
generators/deps/fsfwgen
Submodule
@ -0,0 +1 @@
|
|||||||
|
Subproject commit a5dee6e41749508a85842a931e6f1d210aee2031
|
@ -4,17 +4,19 @@ Event exporter.
|
|||||||
import datetime
|
import datetime
|
||||||
import time
|
import time
|
||||||
import os
|
import os
|
||||||
|
from pathlib import Path
|
||||||
|
|
||||||
from fsfwgen.events.event_parser import (
|
from fsfwgen.events.event_parser import (
|
||||||
handle_csv_export,
|
handle_csv_export,
|
||||||
handle_cpp_export,
|
handle_cpp_export,
|
||||||
SubsystemDefinitionParser,
|
SubsystemDefinitionParser,
|
||||||
EventParser,
|
EventParser,
|
||||||
|
EventDictT,
|
||||||
)
|
)
|
||||||
from fsfwgen.parserbase.file_list_parser import FileListParser
|
from fsfwgen.parserbase.file_list_parser import FileListParser
|
||||||
from fsfwgen.utility.printer import PrettyPrinter
|
from fsfwgen.utility.printer import PrettyPrinter
|
||||||
from fsfwgen.utility.file_management import copy_file
|
from fsfwgen.utility.file_management import copy_file
|
||||||
from fsfwgen.core import get_console_logger
|
from fsfwgen.logging import get_console_logger
|
||||||
from definitions import BspType, ROOT_DIR, OBSW_ROOT_DIR
|
from definitions import BspType, ROOT_DIR, OBSW_ROOT_DIR
|
||||||
|
|
||||||
LOGGER = get_console_logger()
|
LOGGER = get_console_logger()
|
||||||
@ -31,24 +33,28 @@ MOVE_CSV_FILE = True
|
|||||||
PARSE_HOST_BSP = True
|
PARSE_HOST_BSP = True
|
||||||
|
|
||||||
# Store these files relative to the events folder
|
# Store these files relative to the events folder
|
||||||
CPP_FILENAME = f"{os.path.dirname(os.path.realpath(__file__))}/translateEvents.cpp"
|
CPP_FILENAME = Path(
|
||||||
CPP_H_FILENAME = f"{os.path.dirname(os.path.realpath(__file__))}/translateEvents.h"
|
f"{os.path.dirname(os.path.realpath(__file__))}/translateEvents.cpp"
|
||||||
|
)
|
||||||
|
CPP_H_FILENAME = Path(
|
||||||
|
f"{os.path.dirname(os.path.realpath(__file__))}/translateEvents.h"
|
||||||
|
)
|
||||||
|
|
||||||
BSP_SELECT = BspType.BSP_Q7S
|
BSP_SELECT = BspType.BSP_Q7S
|
||||||
|
|
||||||
BSP_DIR_NAME = BSP_SELECT.value
|
BSP_DIR_NAME = BSP_SELECT.value
|
||||||
|
|
||||||
# Store this file in the root of the generators folder
|
# Store this file in the root of the generators folder
|
||||||
CSV_FILENAME = f"{ROOT_DIR}/{BSP_SELECT.value}_events.csv"
|
CSV_FILENAME = Path(f"{ROOT_DIR}/{BSP_SELECT.value}_events.csv")
|
||||||
CSV_COPY_DEST = f"{OBSW_ROOT_DIR}/tmtc/config/events.csv"
|
CSV_COPY_DEST = Path(f"{OBSW_ROOT_DIR}/tmtc/config/events.csv")
|
||||||
|
|
||||||
if BSP_SELECT == BspType.BSP_Q7S or BSP_SELECT == BspType.BSP_LINUX_BOARD:
|
if BSP_SELECT == BspType.BSP_Q7S or BSP_SELECT == BspType.BSP_LINUX_BOARD:
|
||||||
FSFW_CONFIG_ROOT = f"{OBSW_ROOT_DIR}/linux/fsfwconfig"
|
FSFW_CONFIG_ROOT = Path(f"{OBSW_ROOT_DIR}/linux/fsfwconfig")
|
||||||
|
|
||||||
else:
|
else:
|
||||||
FSFW_CONFIG_ROOT = f"{OBSW_ROOT_DIR}/{BSP_DIR_NAME}/fsfwconfig"
|
FSFW_CONFIG_ROOT = Path(f"{OBSW_ROOT_DIR}/{BSP_DIR_NAME}/fsfwconfig")
|
||||||
|
|
||||||
CPP_COPY_DESTINATION = f"{FSFW_CONFIG_ROOT}/events/"
|
CPP_COPY_DESTINATION = Path(f"{FSFW_CONFIG_ROOT}/events/")
|
||||||
|
|
||||||
FILE_SEPARATOR = ";"
|
FILE_SEPARATOR = ";"
|
||||||
SUBSYSTEM_DEFINITION_DESTINATIONS = [
|
SUBSYSTEM_DEFINITION_DESTINATIONS = [
|
||||||
@ -56,14 +62,21 @@ SUBSYSTEM_DEFINITION_DESTINATIONS = [
|
|||||||
f"{OBSW_ROOT_DIR}/fsfw/src/fsfw/events/fwSubsystemIdRanges.h",
|
f"{OBSW_ROOT_DIR}/fsfw/src/fsfw/events/fwSubsystemIdRanges.h",
|
||||||
f"{OBSW_ROOT_DIR}/common/config/commonSubsystemIds.h",
|
f"{OBSW_ROOT_DIR}/common/config/commonSubsystemIds.h",
|
||||||
]
|
]
|
||||||
|
SUBSYSTEM_DEFS_DEST_AS_PATH = [Path(x) for x in SUBSYSTEM_DEFINITION_DESTINATIONS]
|
||||||
|
|
||||||
HEADER_DEFINITION_DESTINATIONS = [
|
HEADER_DEFINITION_DESTINATIONS = [
|
||||||
f"{OBSW_ROOT_DIR}/mission/",
|
f"{OBSW_ROOT_DIR}/mission/",
|
||||||
f"{OBSW_ROOT_DIR}/fsfw/",
|
f"{OBSW_ROOT_DIR}/fsfw/",
|
||||||
f"{FSFW_CONFIG_ROOT}",
|
f"{FSFW_CONFIG_ROOT}",
|
||||||
f"{OBSW_ROOT_DIR}/test/",
|
f"{OBSW_ROOT_DIR}/test/",
|
||||||
f"{OBSW_ROOT_DIR}/bsp_q7s",
|
f"{OBSW_ROOT_DIR}/bsp_q7s/",
|
||||||
f"{OBSW_ROOT_DIR}/linux/",
|
f"{OBSW_ROOT_DIR}/linux/",
|
||||||
]
|
]
|
||||||
|
HEADER_DEFINITION_DESTINATIONS_AS_PATH = [
|
||||||
|
Path(x) for x in HEADER_DEFINITION_DESTINATIONS
|
||||||
|
]
|
||||||
|
|
||||||
|
LOGGER = get_console_logger()
|
||||||
|
|
||||||
|
|
||||||
def parse_events(
|
def parse_events(
|
||||||
@ -77,7 +90,6 @@ def parse_events(
|
|||||||
PrettyPrinter.pprint(event_list)
|
PrettyPrinter.pprint(event_list)
|
||||||
# Delay for clean printout
|
# Delay for clean printout
|
||||||
time.sleep(0.1)
|
time.sleep(0.1)
|
||||||
# xml_test()
|
|
||||||
if generate_csv:
|
if generate_csv:
|
||||||
handle_csv_export(
|
handle_csv_export(
|
||||||
file_name=CSV_FILENAME, event_list=event_list, file_separator=FILE_SEPARATOR
|
file_name=CSV_FILENAME, event_list=event_list, file_separator=FILE_SEPARATOR
|
||||||
@ -96,17 +108,19 @@ def parse_events(
|
|||||||
header_file_name=CPP_H_FILENAME,
|
header_file_name=CPP_H_FILENAME,
|
||||||
)
|
)
|
||||||
if COPY_CPP_FILE:
|
if COPY_CPP_FILE:
|
||||||
LOGGER.info(f"EventParser: Copying CPP translation file to {CPP_COPY_DESTINATION}")
|
LOGGER.info(
|
||||||
|
f"EventParser: Copying CPP translation file to {CPP_COPY_DESTINATION}"
|
||||||
|
)
|
||||||
copy_file(CPP_FILENAME, CPP_COPY_DESTINATION)
|
copy_file(CPP_FILENAME, CPP_COPY_DESTINATION)
|
||||||
copy_file(CPP_H_FILENAME, CPP_COPY_DESTINATION)
|
copy_file(CPP_H_FILENAME, CPP_COPY_DESTINATION)
|
||||||
|
|
||||||
|
|
||||||
def generate_event_list() -> list:
|
def generate_event_list() -> EventDictT:
|
||||||
subsystem_parser = SubsystemDefinitionParser(SUBSYSTEM_DEFINITION_DESTINATIONS)
|
subsystem_parser = SubsystemDefinitionParser(SUBSYSTEM_DEFS_DEST_AS_PATH)
|
||||||
subsystem_table = subsystem_parser.parse_files()
|
subsystem_table = subsystem_parser.parse_files()
|
||||||
LOGGER.info(f"Found {len(subsystem_table)} subsystem definitions.")
|
LOGGER.info(f"Found {len(subsystem_table)} subsystem definitions.")
|
||||||
PrettyPrinter.pprint(subsystem_table)
|
PrettyPrinter.pprint(subsystem_table)
|
||||||
event_header_parser = FileListParser(HEADER_DEFINITION_DESTINATIONS)
|
event_header_parser = FileListParser(HEADER_DEFINITION_DESTINATIONS_AS_PATH)
|
||||||
event_headers = event_header_parser.parse_header_files(
|
event_headers = event_header_parser.parse_header_files(
|
||||||
True, "Parsing event header file list:\n", True
|
True, "Parsing event header file list:\n", True
|
||||||
)
|
)
|
||||||
@ -116,6 +130,6 @@ def generate_event_list() -> list:
|
|||||||
event_parser.obsw_root_path = OBSW_ROOT_DIR
|
event_parser.obsw_root_path = OBSW_ROOT_DIR
|
||||||
event_parser.set_moving_window_mode(moving_window_size=7)
|
event_parser.set_moving_window_mode(moving_window_size=7)
|
||||||
event_table = event_parser.parse_files()
|
event_table = event_parser.parse_files()
|
||||||
event_list = sorted(event_table.items())
|
events_sorted = dict(sorted(event_table.items()))
|
||||||
LOGGER.info(f"Found {len(event_list)} entries")
|
LOGGER.info(f"Found {len(events_sorted)} entries")
|
||||||
return event_list
|
return events_sorted
|
||||||
|
@ -1,7 +1,7 @@
|
|||||||
/**
|
/**
|
||||||
* @brief Auto-generated event translation file. Contains 207 translations.
|
* @brief Auto-generated event translation file. Contains 209 translations.
|
||||||
* @details
|
* @details
|
||||||
* Generated on: 2022-05-25 18:14:41
|
* Generated on: 2022-06-27 09:14:37
|
||||||
*/
|
*/
|
||||||
#include "translateEvents.h"
|
#include "translateEvents.h"
|
||||||
|
|
||||||
@ -134,6 +134,8 @@ const char *INVALID_TC_FRAME_STRING = "INVALID_TC_FRAME";
|
|||||||
const char *INVALID_FAR_STRING = "INVALID_FAR";
|
const char *INVALID_FAR_STRING = "INVALID_FAR";
|
||||||
const char *CARRIER_LOCK_STRING = "CARRIER_LOCK";
|
const char *CARRIER_LOCK_STRING = "CARRIER_LOCK";
|
||||||
const char *BIT_LOCK_PDEC_STRING = "BIT_LOCK_PDEC";
|
const char *BIT_LOCK_PDEC_STRING = "BIT_LOCK_PDEC";
|
||||||
|
const char *LOST_CARRIER_LOCK_PDEC_STRING = "LOST_CARRIER_LOCK_PDEC";
|
||||||
|
const char *LOST_BIT_LOCK_PDEC_STRING = "LOST_BIT_LOCK_PDEC";
|
||||||
const char *IMAGE_UPLOAD_FAILED_STRING = "IMAGE_UPLOAD_FAILED";
|
const char *IMAGE_UPLOAD_FAILED_STRING = "IMAGE_UPLOAD_FAILED";
|
||||||
const char *IMAGE_DOWNLOAD_FAILED_STRING = "IMAGE_DOWNLOAD_FAILED";
|
const char *IMAGE_DOWNLOAD_FAILED_STRING = "IMAGE_DOWNLOAD_FAILED";
|
||||||
const char *IMAGE_UPLOAD_SUCCESSFUL_STRING = "IMAGE_UPLOAD_SUCCESSFUL";
|
const char *IMAGE_UPLOAD_SUCCESSFUL_STRING = "IMAGE_UPLOAD_SUCCESSFUL";
|
||||||
@ -469,6 +471,10 @@ const char *translateEvents(Event event) {
|
|||||||
return CARRIER_LOCK_STRING;
|
return CARRIER_LOCK_STRING;
|
||||||
case (12404):
|
case (12404):
|
||||||
return BIT_LOCK_PDEC_STRING;
|
return BIT_LOCK_PDEC_STRING;
|
||||||
|
case (12405):
|
||||||
|
return LOST_CARRIER_LOCK_PDEC_STRING;
|
||||||
|
case (12406):
|
||||||
|
return LOST_BIT_LOCK_PDEC_STRING;
|
||||||
case (12500):
|
case (12500):
|
||||||
return IMAGE_UPLOAD_FAILED_STRING;
|
return IMAGE_UPLOAD_FAILED_STRING;
|
||||||
case (12501):
|
case (12501):
|
||||||
|
@ -1 +0,0 @@
|
|||||||
Subproject commit 169ad98cdeebe3ccfd1b78938934496a20b6a294
|
|
@ -7,10 +7,8 @@ from returnvalues.returnvalues_parser import parse_returnvalues
|
|||||||
from fsfwgen.core import (
|
from fsfwgen.core import (
|
||||||
return_generic_args_parser,
|
return_generic_args_parser,
|
||||||
init_printout,
|
init_printout,
|
||||||
get_console_logger,
|
|
||||||
ParserTypes,
|
|
||||||
)
|
)
|
||||||
|
from fsfwgen.logging import get_console_logger
|
||||||
|
|
||||||
LOGGER = get_console_logger()
|
LOGGER = get_console_logger()
|
||||||
|
|
||||||
@ -20,7 +18,7 @@ def main():
|
|||||||
parser = return_generic_args_parser()
|
parser = return_generic_args_parser()
|
||||||
args = parser.parse_args()
|
args = parser.parse_args()
|
||||||
if args.type == "objects":
|
if args.type == "objects":
|
||||||
LOGGER.info(f"Generating objects data..")
|
LOGGER.info(f"Generating objects data")
|
||||||
time.sleep(0.05)
|
time.sleep(0.05)
|
||||||
parse_objects()
|
parse_objects()
|
||||||
elif args.type == "events":
|
elif args.type == "events":
|
||||||
|
@ -3,8 +3,9 @@ Object exporter.
|
|||||||
"""
|
"""
|
||||||
import datetime
|
import datetime
|
||||||
import os
|
import os
|
||||||
|
from pathlib import Path
|
||||||
|
|
||||||
from fsfwgen.core import get_console_logger
|
from fsfwgen.logging import get_console_logger
|
||||||
from fsfwgen.objects.objects import (
|
from fsfwgen.objects.objects import (
|
||||||
sql_object_exporter,
|
sql_object_exporter,
|
||||||
ObjectDefinitionParser,
|
ObjectDefinitionParser,
|
||||||
@ -46,11 +47,11 @@ CSV_COPY_DEST = f"{OBSW_ROOT_DIR}/tmtc/config/objects.csv"
|
|||||||
FILE_SEPARATOR = ";"
|
FILE_SEPARATOR = ";"
|
||||||
|
|
||||||
|
|
||||||
OBJECTS_PATH = f"{FSFW_CONFIG_ROOT}/objects/systemObjectList.h"
|
OBJECTS_PATH = Path(f"{FSFW_CONFIG_ROOT}/objects/systemObjectList.h")
|
||||||
FRAMEWORK_OBJECT_PATH = (
|
FRAMEWORK_OBJECT_PATH = Path(
|
||||||
f"{OBSW_ROOT_DIR}/fsfw/src/fsfw/objectmanager/frameworkObjects.h"
|
f"{OBSW_ROOT_DIR}/fsfw/src/fsfw/objectmanager/frameworkObjects.h"
|
||||||
)
|
)
|
||||||
COMMON_OBJECTS_PATH = f"{OBSW_ROOT_DIR}/common/config/commonObjects.h"
|
COMMON_OBJECTS_PATH = Path(f"{OBSW_ROOT_DIR}/common/config/commonObjects.h")
|
||||||
OBJECTS_DEFINITIONS = [OBJECTS_PATH, FRAMEWORK_OBJECT_PATH, COMMON_OBJECTS_PATH]
|
OBJECTS_DEFINITIONS = [OBJECTS_PATH, FRAMEWORK_OBJECT_PATH, COMMON_OBJECTS_PATH]
|
||||||
|
|
||||||
SQL_DELETE_OBJECTS_CMD = """
|
SQL_DELETE_OBJECTS_CMD = """
|
||||||
|
@ -1,8 +1,8 @@
|
|||||||
/**
|
/**
|
||||||
* @brief Auto-generated object translation file.
|
* @brief Auto-generated object translation file.
|
||||||
* @details
|
* @details
|
||||||
* Contains 131 translations.
|
* Contains 132 translations.
|
||||||
* Generated on: 2022-05-25 18:14:41
|
* Generated on: 2022-06-27 09:14:34
|
||||||
*/
|
*/
|
||||||
#include "translateObjects.h"
|
#include "translateObjects.h"
|
||||||
|
|
||||||
@ -118,6 +118,7 @@ const char *FSFW_OBJECTS_END_STRING = "FSFW_OBJECTS_END";
|
|||||||
const char *SPI_TEST_STRING = "SPI_TEST";
|
const char *SPI_TEST_STRING = "SPI_TEST";
|
||||||
const char *UART_TEST_STRING = "UART_TEST";
|
const char *UART_TEST_STRING = "UART_TEST";
|
||||||
const char *I2C_TEST_STRING = "I2C_TEST";
|
const char *I2C_TEST_STRING = "I2C_TEST";
|
||||||
|
const char *DUMMY_COM_IF_STRING = "DUMMY_COM_IF";
|
||||||
const char *DUMMY_HANDLER_STRING = "DUMMY_HANDLER";
|
const char *DUMMY_HANDLER_STRING = "DUMMY_HANDLER";
|
||||||
const char *DUMMY_INTERFACE_STRING = "DUMMY_INTERFACE";
|
const char *DUMMY_INTERFACE_STRING = "DUMMY_INTERFACE";
|
||||||
const char *LIBGPIOD_TEST_STRING = "LIBGPIOD_TEST";
|
const char *LIBGPIOD_TEST_STRING = "LIBGPIOD_TEST";
|
||||||
@ -364,6 +365,8 @@ const char *translateObject(object_id_t object) {
|
|||||||
return UART_TEST_STRING;
|
return UART_TEST_STRING;
|
||||||
case 0x54000030:
|
case 0x54000030:
|
||||||
return I2C_TEST_STRING;
|
return I2C_TEST_STRING;
|
||||||
|
case 0x54000040:
|
||||||
|
return DUMMY_COM_IF_STRING;
|
||||||
case 0x5400AFFE:
|
case 0x5400AFFE:
|
||||||
return DUMMY_HANDLER_STRING;
|
return DUMMY_HANDLER_STRING;
|
||||||
case 0x5400CAFE:
|
case 0x5400CAFE:
|
||||||
|
@ -3,10 +3,16 @@
|
|||||||
"""Part of the MIB export tools for the EIVE project by.
|
"""Part of the MIB export tools for the EIVE project by.
|
||||||
Returnvalue exporter.
|
Returnvalue exporter.
|
||||||
"""
|
"""
|
||||||
from fsfwgen.core import get_console_logger
|
from pathlib import Path
|
||||||
|
|
||||||
|
from fsfwgen.logging import get_console_logger
|
||||||
from fsfwgen.utility.file_management import copy_file
|
from fsfwgen.utility.file_management import copy_file
|
||||||
from fsfwgen.parserbase.file_list_parser import FileListParser
|
from fsfwgen.parserbase.file_list_parser import FileListParser
|
||||||
from fsfwgen.returnvalues.returnvalues_parser import InterfaceParser, ReturnValueParser
|
from fsfwgen.returnvalues.returnvalues_parser import (
|
||||||
|
InterfaceParser,
|
||||||
|
ReturnValueParser,
|
||||||
|
RetvalDictT,
|
||||||
|
)
|
||||||
from fsfwgen.utility.sql_writer import SqlWriter
|
from fsfwgen.utility.sql_writer import SqlWriter
|
||||||
from fsfwgen.utility.printer import PrettyPrinter
|
from fsfwgen.utility.printer import PrettyPrinter
|
||||||
|
|
||||||
@ -24,8 +30,8 @@ MAX_STRING_LENGTH = 32
|
|||||||
|
|
||||||
BSP_SELECT = BspType.BSP_Q7S
|
BSP_SELECT = BspType.BSP_Q7S
|
||||||
BSP_DIR_NAME = BSP_SELECT.value
|
BSP_DIR_NAME = BSP_SELECT.value
|
||||||
CSV_RETVAL_FILENAME = f"{ROOT_DIR}/{BSP_SELECT.value}_returnvalues.csv"
|
CSV_RETVAL_FILENAME = Path(f"{ROOT_DIR}/{BSP_SELECT.value}_returnvalues.csv")
|
||||||
CSV_COPY_DEST = f"{OBSW_ROOT_DIR}/tmtc/config/returnvalues.csv"
|
CSV_COPY_DEST = Path(f"{OBSW_ROOT_DIR}/tmtc/config/returnvalues.csv")
|
||||||
ADD_LINUX_FOLDER = False
|
ADD_LINUX_FOLDER = False
|
||||||
|
|
||||||
if BSP_SELECT == BspType.BSP_Q7S or BSP_SELECT == BspType.BSP_LINUX_BOARD:
|
if BSP_SELECT == BspType.BSP_Q7S or BSP_SELECT == BspType.BSP_LINUX_BOARD:
|
||||||
@ -45,6 +51,7 @@ RETURNVALUE_SOURCES = [
|
|||||||
f"{OBSW_ROOT_DIR}/fsfw/",
|
f"{OBSW_ROOT_DIR}/fsfw/",
|
||||||
f"{BSP_PATH}",
|
f"{BSP_PATH}",
|
||||||
]
|
]
|
||||||
|
RETVAL_SRCS_AS_PATH = [Path(x) for x in RETURNVALUE_SOURCES]
|
||||||
|
|
||||||
if ADD_LINUX_FOLDER:
|
if ADD_LINUX_FOLDER:
|
||||||
RETURNVALUE_SOURCES.append(f"{OBSW_ROOT_DIR}/linux")
|
RETURNVALUE_SOURCES.append(f"{OBSW_ROOT_DIR}/linux")
|
||||||
@ -73,7 +80,7 @@ VALUES(?,?,?,?,?)
|
|||||||
def parse_returnvalues():
|
def parse_returnvalues():
|
||||||
returnvalue_table = generate_returnvalue_table()
|
returnvalue_table = generate_returnvalue_table()
|
||||||
if EXPORT_TO_FILE:
|
if EXPORT_TO_FILE:
|
||||||
ReturnValueParser.export_to_file(
|
ReturnValueParser.export_to_csv(
|
||||||
CSV_RETVAL_FILENAME, returnvalue_table, FILE_SEPARATOR
|
CSV_RETVAL_FILENAME, returnvalue_table, FILE_SEPARATOR
|
||||||
)
|
)
|
||||||
if COPY_CSV_FILE:
|
if COPY_CSV_FILE:
|
||||||
@ -95,7 +102,7 @@ def generate_returnvalue_table():
|
|||||||
file_list=INTERFACE_DEFINITION_FILES, print_table=PRINT_TABLES
|
file_list=INTERFACE_DEFINITION_FILES, print_table=PRINT_TABLES
|
||||||
)
|
)
|
||||||
interfaces = interface_parser.parse_files()
|
interfaces = interface_parser.parse_files()
|
||||||
header_parser = FileListParser(RETURNVALUE_SOURCES)
|
header_parser = FileListParser(RETVAL_SRCS_AS_PATH)
|
||||||
header_list = header_parser.parse_header_files(True, "Parsing header file list: ")
|
header_list = header_parser.parse_header_files(True, "Parsing header file list: ")
|
||||||
returnvalue_parser = ReturnValueParser(interfaces, header_list, PRINT_TABLES)
|
returnvalue_parser = ReturnValueParser(interfaces, header_list, PRINT_TABLES)
|
||||||
returnvalue_parser.obsw_root_path = OBSW_ROOT_DIR
|
returnvalue_parser.obsw_root_path = OBSW_ROOT_DIR
|
||||||
@ -105,13 +112,19 @@ def generate_returnvalue_table():
|
|||||||
return returnvalue_table
|
return returnvalue_table
|
||||||
|
|
||||||
|
|
||||||
def sql_retval_exporter(returnvalue_table, db_filename: str):
|
def sql_retval_exporter(returnvalue_table: RetvalDictT, db_filename: str):
|
||||||
sql_writer = SqlWriter(db_filename=db_filename)
|
sql_writer = SqlWriter(db_filename=db_filename)
|
||||||
sql_writer.open(SQL_CREATE_RETURNVALUES_CMD)
|
sql_writer.open(SQL_CREATE_RETURNVALUES_CMD)
|
||||||
for entry in returnvalue_table.items():
|
for entry in returnvalue_table.items():
|
||||||
sql_writer.write_entries(
|
sql_writer.write_entries(
|
||||||
SQL_INSERT_RETURNVALUES_CMD,
|
SQL_INSERT_RETURNVALUES_CMD,
|
||||||
(entry[0], entry[1][2], entry[1][4], entry[1][3], entry[1][1]),
|
(
|
||||||
|
entry[0],
|
||||||
|
entry[1].name,
|
||||||
|
entry[1].description,
|
||||||
|
entry[1].unique_id,
|
||||||
|
entry[1].subsystem_name,
|
||||||
|
),
|
||||||
)
|
)
|
||||||
sql_writer.commit()
|
sql_writer.commit()
|
||||||
sql_writer.close()
|
sql_writer.close()
|
||||||
|
@ -9,6 +9,7 @@
|
|||||||
#include <fsfw_hal/linux/uart/UartCookie.h>
|
#include <fsfw_hal/linux/uart/UartCookie.h>
|
||||||
#include <linux/callbacks/gpioCallbacks.h>
|
#include <linux/callbacks/gpioCallbacks.h>
|
||||||
#include <linux/devices/Max31865RtdLowlevelHandler.h>
|
#include <linux/devices/Max31865RtdLowlevelHandler.h>
|
||||||
|
#include <mission/controller/ThermalController.h>
|
||||||
#include <mission/devices/Max31865EiveHandler.h>
|
#include <mission/devices/Max31865EiveHandler.h>
|
||||||
#include <mission/devices/Max31865PT1000Handler.h>
|
#include <mission/devices/Max31865PT1000Handler.h>
|
||||||
#include <mission/devices/ScexDeviceHandler.h>
|
#include <mission/devices/ScexDeviceHandler.h>
|
||||||
@ -331,6 +332,10 @@ void ObjectFactory::createScexComponents(std::string uartDev, PowerSwitchIF* pwr
|
|||||||
scexHandler->setStartUpImmediately();
|
scexHandler->setStartUpImmediately();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void ObjectFactory::createThermalController() {
|
||||||
|
new ThermalController(objects::THERMAL_CONTROLLER, objects::NO_OBJECT);
|
||||||
|
}
|
||||||
|
|
||||||
void ObjectFactory::gpioChecker(ReturnValue_t result, std::string output) {
|
void ObjectFactory::gpioChecker(ReturnValue_t result, std::string output) {
|
||||||
if (result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
sif::error << "ObjectFactory: Adding GPIOs failed for " << output << std::endl;
|
sif::error << "ObjectFactory: Adding GPIOs failed for " << output << std::endl;
|
||||||
|
@ -1,5 +1,6 @@
|
|||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
|
#include <fsfw/hal/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h>
|
||||||
#include <fsfw/returnvalues/HasReturnvaluesIF.h>
|
#include <fsfw/returnvalues/HasReturnvaluesIF.h>
|
||||||
|
|
||||||
#include <string>
|
#include <string>
|
||||||
@ -19,4 +20,6 @@ void createScexComponents(std::string uartDev, PowerSwitchIF* pwrSwitcher);
|
|||||||
|
|
||||||
void gpioChecker(ReturnValue_t result, std::string output);
|
void gpioChecker(ReturnValue_t result, std::string output);
|
||||||
|
|
||||||
|
void createThermalController();
|
||||||
|
|
||||||
} // namespace ObjectFactory
|
} // namespace ObjectFactory
|
||||||
|
@ -100,6 +100,33 @@ static const uint16_t TC_WRITE_SEQ_EXECUTION_DELAY = 80;
|
|||||||
// Requires approx. 2 seconds for execution. 8 => 4 seconds
|
// Requires approx. 2 seconds for execution. 8 => 4 seconds
|
||||||
static const uint16_t TC_DOWNLINK_PWR_ON_EXECUTION_DELAY = 8;
|
static const uint16_t TC_DOWNLINK_PWR_ON_EXECUTION_DELAY = 8;
|
||||||
|
|
||||||
|
namespace status_code {
|
||||||
|
static const uint16_t UNKNOWN_APID = 0x5DD;
|
||||||
|
static const uint16_t INCORRECT_LENGTH = 0x5DE;
|
||||||
|
static const uint16_t INCORRECT_CRC = 0x5DF;
|
||||||
|
static const uint16_t INCORRECT_PKT_SEQ_CNT = 0x5E0;
|
||||||
|
static const uint16_t TC_NOT_ALLOWED_IN_MODE = 0x5E1;
|
||||||
|
static const uint16_t TC_EXEUTION_DISABLED = 0x5E2;
|
||||||
|
static const uint16_t FLASH_MOUNT_FAILED = 0x5E3;
|
||||||
|
static const uint16_t FLASH_FILE_ALREADY_CLOSED = 0x5E4;
|
||||||
|
static const uint16_t FLASH_FILE_OPEN_FAILED = 0x5E5;
|
||||||
|
static const uint16_t FLASH_FILE_ALREDY_OPEN = 0x5E6;
|
||||||
|
static const uint16_t FLASH_FILE_NOT_OPEN = 0x5E7;
|
||||||
|
static const uint16_t FLASH_UNMOUNT_FAILED = 0x5E8;
|
||||||
|
static const uint16_t HEAP_ALLOCATION_FAILED = 0x5E9;
|
||||||
|
static const uint16_t INVALID_PARAMETER = 0x5EA;
|
||||||
|
static const uint16_t NOT_INITIALIZED = 0x5EB;
|
||||||
|
static const uint16_t REBOOT_IMMINENT = 0x5EC;
|
||||||
|
static const uint16_t CORRUPT_DATA = 0x5ED;
|
||||||
|
static const uint16_t FLASH_CORRECTABLE_MISMATCH = 0x5EE;
|
||||||
|
static const uint16_t FLASH_UNCORRECTABLE_MISMATCH = 0x5EF;
|
||||||
|
static const uint16_t RESERVED_0 = 0x5F0;
|
||||||
|
static const uint16_t RESERVED_1 = 0x5F1;
|
||||||
|
static const uint16_t RESERVED_2 = 0x5F2;
|
||||||
|
static const uint16_t RESERVED_3 = 0x5F3;
|
||||||
|
static const uint16_t RESERVED_4 = 0x5F4;
|
||||||
|
} // namespace status_code
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Abstract base class for TC space packet of MPSoC.
|
* @brief Abstract base class for TC space packet of MPSoC.
|
||||||
*/
|
*/
|
||||||
@ -656,9 +683,13 @@ class TcCamcmdSend : public TcBase {
|
|||||||
if (commandDataLen > MAX_DATA_LENGTH) {
|
if (commandDataLen > MAX_DATA_LENGTH) {
|
||||||
return INVALID_LENGTH;
|
return INVALID_LENGTH;
|
||||||
}
|
}
|
||||||
std::memcpy(this->getPacketData(), commandData, commandDataLen);
|
uint16_t dataLen = static_cast<uint16_t>(commandDataLen + sizeof(CARRIAGE_RETURN));
|
||||||
*(this->getPacketData() + commandDataLen) = CARRIAGE_RETURN;
|
size_t size = sizeof(dataLen);
|
||||||
uint16_t trueLength = commandDataLen + sizeof(CARRIAGE_RETURN) + CRC_SIZE;
|
SerializeAdapter::serialize(&dataLen, this->getPacketData(), &size, sizeof(dataLen),
|
||||||
|
SerializeIF::Endianness::BIG);
|
||||||
|
std::memcpy(this->getPacketData() + sizeof(dataLen), commandData, commandDataLen);
|
||||||
|
*(this->getPacketData() + sizeof(dataLen) + commandDataLen) = CARRIAGE_RETURN;
|
||||||
|
uint16_t trueLength = sizeof(dataLen) + commandDataLen + sizeof(CARRIAGE_RETURN) + CRC_SIZE;
|
||||||
this->setPacketDataLength(trueLength - 1);
|
this->setPacketDataLength(trueLength - 1);
|
||||||
return HasReturnvaluesIF::RETURN_OK;
|
return HasReturnvaluesIF::RETURN_OK;
|
||||||
}
|
}
|
||||||
|
@ -589,14 +589,14 @@ ReturnValue_t PlocMPSoCHandler::handleAckReport(const uint8_t* data) {
|
|||||||
|
|
||||||
switch (apid) {
|
switch (apid) {
|
||||||
case mpsoc::apid::ACK_FAILURE: {
|
case mpsoc::apid::ACK_FAILURE: {
|
||||||
// TODO: Interpretation of status field in acknowledgment report
|
|
||||||
sif::debug << "PlocMPSoCHandler::handleAckReport: Received Ack failure report" << std::endl;
|
sif::debug << "PlocMPSoCHandler::handleAckReport: Received Ack failure report" << std::endl;
|
||||||
DeviceCommandId_t commandId = getPendingCommand();
|
DeviceCommandId_t commandId = getPendingCommand();
|
||||||
uint16_t status = getStatus(data);
|
uint16_t status = getStatus(data);
|
||||||
|
printStatus(data);
|
||||||
if (commandId != DeviceHandlerIF::NO_COMMAND_ID) {
|
if (commandId != DeviceHandlerIF::NO_COMMAND_ID) {
|
||||||
triggerEvent(ACK_FAILURE, commandId, status);
|
triggerEvent(ACK_FAILURE, commandId, status);
|
||||||
}
|
}
|
||||||
sendFailureReport(mpsoc::ACK_REPORT, MPSoCReturnValuesIF::RECEIVED_ACK_FAILURE);
|
sendFailureReport(mpsoc::ACK_REPORT, status);
|
||||||
disableAllReplies();
|
disableAllReplies();
|
||||||
nextReplyId = mpsoc::NONE;
|
nextReplyId = mpsoc::NONE;
|
||||||
result = IGNORE_REPLY_DATA;
|
result = IGNORE_REPLY_DATA;
|
||||||
@ -683,17 +683,18 @@ ReturnValue_t PlocMPSoCHandler::handleCamCmdRpt(const uint8_t* data) {
|
|||||||
if (result == MPSoCReturnValuesIF::CRC_FAILURE) {
|
if (result == MPSoCReturnValuesIF::CRC_FAILURE) {
|
||||||
sif::warning << "PlocMPSoCHandler::handleCamCmdRpt: CRC failure" << std::endl;
|
sif::warning << "PlocMPSoCHandler::handleCamCmdRpt: CRC failure" << std::endl;
|
||||||
}
|
}
|
||||||
const uint8_t* dataFieldPtr = data + mpsoc::SPACE_PACKET_HEADER_SIZE;
|
const uint8_t* dataFieldPtr = data + mpsoc::SPACE_PACKET_HEADER_SIZE + sizeof(uint16_t);
|
||||||
std::string camCmdRptMsg(
|
std::string camCmdRptMsg(
|
||||||
reinterpret_cast<const char*>(dataFieldPtr),
|
reinterpret_cast<const char*>(dataFieldPtr),
|
||||||
tmCamCmdRpt.rememberSpacePacketSize - mpsoc::SPACE_PACKET_HEADER_SIZE - 3);
|
tmCamCmdRpt.rememberSpacePacketSize - mpsoc::SPACE_PACKET_HEADER_SIZE - sizeof(uint16_t) - 3);
|
||||||
#if OBSW_DEBUG_PLOC_MPSOC == 1
|
#if OBSW_DEBUG_PLOC_MPSOC == 1
|
||||||
uint8_t ackValue = *(packet.getPacketData() + packet.getPacketDataLength() - 2);
|
uint8_t ackValue = *(packet.getPacketData() + packet.getPacketDataLength() - 2);
|
||||||
sif::info << "PlocMPSoCHandler: CamCmdRpt message: " << camCmdRptMsg << std::endl;
|
sif::info << "PlocMPSoCHandler: CamCmdRpt message: " << camCmdRptMsg << std::endl;
|
||||||
sif::info << "PlocMPSoCHandler: CamCmdRpt Ack value: 0x" << std::hex
|
sif::info << "PlocMPSoCHandler: CamCmdRpt Ack value: 0x" << std::hex
|
||||||
<< static_cast<unsigned int>(ackValue) << std::endl;
|
<< static_cast<unsigned int>(ackValue) << std::endl;
|
||||||
#endif /* OBSW_DEBUG_PLOC_MPSOC == 1 */
|
#endif /* OBSW_DEBUG_PLOC_MPSOC == 1 */
|
||||||
handleDeviceTM(packet.getPacketData(), packet.getPacketDataLength() - 1, mpsoc::TM_CAM_CMD_RPT);
|
handleDeviceTM(packet.getPacketData() + sizeof(uint16_t), packet.getPacketDataLength() - 1,
|
||||||
|
mpsoc::TM_CAM_CMD_RPT);
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -994,7 +995,7 @@ void PlocMPSoCHandler::disableExeReportReply() {
|
|||||||
|
|
||||||
void PlocMPSoCHandler::printStatus(const uint8_t* data) {
|
void PlocMPSoCHandler::printStatus(const uint8_t* data) {
|
||||||
uint16_t status = *(data + STATUS_OFFSET) << 8 | *(data + STATUS_OFFSET + 1);
|
uint16_t status = *(data + STATUS_OFFSET) << 8 | *(data + STATUS_OFFSET + 1);
|
||||||
sif::info << "Verification report status: 0x" << std::hex << status << std::endl;
|
sif::info << "Verification report status: " << getStatusString(status) << std::endl;
|
||||||
}
|
}
|
||||||
|
|
||||||
uint16_t PlocMPSoCHandler::getStatus(const uint8_t* data) {
|
uint16_t PlocMPSoCHandler::getStatus(const uint8_t* data) {
|
||||||
@ -1033,3 +1034,79 @@ void PlocMPSoCHandler::handleActionCommandFailure(ActionId_t actionId) {
|
|||||||
}
|
}
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
std::string PlocMPSoCHandler::getStatusString(uint16_t status) {
|
||||||
|
switch (status) {
|
||||||
|
case (mpsoc::status_code::UNKNOWN_APID): {
|
||||||
|
return "Unknown APID";
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case (mpsoc::status_code::INCORRECT_LENGTH): {
|
||||||
|
return "Incorrect length";
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case (mpsoc::status_code::INCORRECT_CRC): {
|
||||||
|
return "Incorrect crc";
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case (mpsoc::status_code::INCORRECT_PKT_SEQ_CNT): {
|
||||||
|
return "Incorrect packet sequence count";
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case (mpsoc::status_code::TC_NOT_ALLOWED_IN_MODE): {
|
||||||
|
return "TC not allowed in this mode";
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case (mpsoc::status_code::TC_EXEUTION_DISABLED): {
|
||||||
|
return "TC execution disabled";
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case (mpsoc::status_code::FLASH_MOUNT_FAILED): {
|
||||||
|
return "Flash mount failed";
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case (mpsoc::status_code::FLASH_FILE_ALREADY_CLOSED): {
|
||||||
|
return "Flash file already closed";
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case (mpsoc::status_code::FLASH_FILE_NOT_OPEN): {
|
||||||
|
return "Flash file not open";
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case (mpsoc::status_code::FLASH_UNMOUNT_FAILED): {
|
||||||
|
return "Flash unmount failed";
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case (mpsoc::status_code::HEAP_ALLOCATION_FAILED): {
|
||||||
|
return "Heap allocation failed";
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case (mpsoc::status_code::INVALID_PARAMETER): {
|
||||||
|
return "Invalid parameter";
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case (mpsoc::status_code::NOT_INITIALIZED): {
|
||||||
|
return "Not initialized";
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case (mpsoc::status_code::REBOOT_IMMINENT): {
|
||||||
|
return "Reboot imminent";
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case (mpsoc::status_code::CORRUPT_DATA): {
|
||||||
|
return "Corrupt data";
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case (mpsoc::status_code::FLASH_CORRECTABLE_MISMATCH): {
|
||||||
|
return "Flash correctable mismatch";
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case (mpsoc::status_code::FLASH_UNCORRECTABLE_MISMATCH): {
|
||||||
|
return "Flash uncorrectable mismatch";
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
return "";
|
||||||
|
}
|
||||||
|
@ -263,6 +263,8 @@ class PlocMPSoCHandler : public DeviceHandlerBase, public CommandsActionsIF {
|
|||||||
uint16_t getStatus(const uint8_t* data);
|
uint16_t getStatus(const uint8_t* data);
|
||||||
|
|
||||||
void handleActionCommandFailure(ActionId_t actionId);
|
void handleActionCommandFailure(ActionId_t actionId);
|
||||||
|
|
||||||
|
std::string getStatusString(uint16_t status);
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* BSP_Q7S_DEVICES_PLOC_PLOCMPSOCHANDLER_H_ */
|
#endif /* BSP_Q7S_DEVICES_PLOC_PLOCMPSOCHANDLER_H_ */
|
||||||
|
@ -78,7 +78,7 @@ MessageQueueIF* PlocMemoryDumper::getCommandQueuePtr() { return commandQueue; }
|
|||||||
|
|
||||||
void PlocMemoryDumper::readCommandQueue() {
|
void PlocMemoryDumper::readCommandQueue() {
|
||||||
CommandMessage message;
|
CommandMessage message;
|
||||||
ReturnValue_t result;
|
ReturnValue_t result = RETURN_OK;
|
||||||
|
|
||||||
for (result = commandQueue->receiveMessage(&message); result == HasReturnvaluesIF::RETURN_OK;
|
for (result = commandQueue->receiveMessage(&message); result == HasReturnvaluesIF::RETURN_OK;
|
||||||
result = commandQueue->receiveMessage(&message)) {
|
result = commandQueue->receiveMessage(&message)) {
|
||||||
|
@ -142,6 +142,7 @@ ReturnValue_t PlocSupervisorHandler::executeAction(ActionId_t actionId,
|
|||||||
}
|
}
|
||||||
|
|
||||||
void PlocSupervisorHandler::doStartUp() {
|
void PlocSupervisorHandler::doStartUp() {
|
||||||
|
if (setTimeDuringStartup) {
|
||||||
switch (startupState) {
|
switch (startupState) {
|
||||||
case StartupState::OFF: {
|
case StartupState::OFF: {
|
||||||
bootTimeout.resetTimer();
|
bootTimeout.resetTimer();
|
||||||
@ -163,6 +164,10 @@ void PlocSupervisorHandler::doStartUp() {
|
|||||||
default:
|
default:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
} else {
|
||||||
|
uartIsolatorSwitch.pullHigh();
|
||||||
|
setMode(_MODE_TO_ON);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void PlocSupervisorHandler::doShutDown() {
|
void PlocSupervisorHandler::doShutDown() {
|
||||||
@ -887,14 +892,11 @@ ReturnValue_t PlocSupervisorHandler::handleAckReport(const uint8_t* data) {
|
|||||||
|
|
||||||
switch (result) {
|
switch (result) {
|
||||||
case SupvReturnValuesIF::RECEIVED_ACK_FAILURE: {
|
case SupvReturnValuesIF::RECEIVED_ACK_FAILURE: {
|
||||||
#if OBSW_DEBUG_PLOC_SUPERVISOR == 1
|
|
||||||
sif::debug << "PlocSupervisorHandler: Received Ack failure report with status code: 0x"
|
|
||||||
<< std::hex << ack.getStatusCode() << std::endl;
|
|
||||||
#endif /* OBSW_DEBUG_PLOC_SUPERVISOR == 1 */
|
|
||||||
DeviceCommandId_t commandId = getPendingCommand();
|
DeviceCommandId_t commandId = getPendingCommand();
|
||||||
if (commandId != DeviceHandlerIF::NO_COMMAND_ID) {
|
if (commandId != DeviceHandlerIF::NO_COMMAND_ID) {
|
||||||
triggerEvent(SUPV_ACK_FAILURE, commandId, static_cast<uint32_t>(ack.getStatusCode()));
|
triggerEvent(SUPV_ACK_FAILURE, commandId, static_cast<uint32_t>(ack.getStatusCode()));
|
||||||
}
|
}
|
||||||
|
printAckFailureInfo(ack.getStatusCode(), commandId);
|
||||||
sendFailureReport(supv::ACK_REPORT, SupvReturnValuesIF::RECEIVED_ACK_FAILURE);
|
sendFailureReport(supv::ACK_REPORT, SupvReturnValuesIF::RECEIVED_ACK_FAILURE);
|
||||||
disableAllReplies();
|
disableAllReplies();
|
||||||
nextReplyId = supv::NONE;
|
nextReplyId = supv::NONE;
|
||||||
@ -1944,3 +1946,17 @@ void PlocSupervisorHandler::handleExecutionFailureReport(uint16_t statusCode) {
|
|||||||
sendFailureReport(EXE_REPORT, SupvReturnValuesIF::RECEIVED_EXE_FAILURE);
|
sendFailureReport(EXE_REPORT, SupvReturnValuesIF::RECEIVED_EXE_FAILURE);
|
||||||
disableExeReportReply();
|
disableExeReportReply();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void PlocSupervisorHandler::printAckFailureInfo(uint16_t statusCode, DeviceCommandId_t commandId) {
|
||||||
|
sif::warning << "PlocSupervisorHandler: Received Ack failure report with status code: 0x"
|
||||||
|
<< std::hex << statusCode << std::endl;
|
||||||
|
switch (commandId) {
|
||||||
|
case (supv::SET_TIME_REF): {
|
||||||
|
sif::info << "PlocSupervisoHandler: Setting time failed. Make sure the OBC has a valid time"
|
||||||
|
<< std::endl;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
@ -95,6 +95,8 @@ class PlocSupervisorHandler : public DeviceHandlerBase {
|
|||||||
static const uint32_t BOOT_TIMEOUT = 2000;
|
static const uint32_t BOOT_TIMEOUT = 2000;
|
||||||
enum class StartupState : uint8_t { OFF, BOOTING, SET_TIME, SET_TIME_EXECUTING, ON };
|
enum class StartupState : uint8_t { OFF, BOOTING, SET_TIME, SET_TIME_EXECUTING, ON };
|
||||||
|
|
||||||
|
bool setTimeDuringStartup = true;
|
||||||
|
|
||||||
StartupState startupState = StartupState::OFF;
|
StartupState startupState = StartupState::OFF;
|
||||||
|
|
||||||
uint8_t commandBuffer[supv::MAX_COMMAND_SIZE];
|
uint8_t commandBuffer[supv::MAX_COMMAND_SIZE];
|
||||||
@ -369,6 +371,8 @@ class PlocSupervisorHandler : public DeviceHandlerBase {
|
|||||||
|
|
||||||
void handleExecutionSuccessReport(const uint8_t* data);
|
void handleExecutionSuccessReport(const uint8_t* data);
|
||||||
void handleExecutionFailureReport(uint16_t statusCode);
|
void handleExecutionFailureReport(uint16_t statusCode);
|
||||||
|
|
||||||
|
void printAckFailureInfo(uint16_t statusCode, DeviceCommandId_t commandId);
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* MISSION_DEVICES_PLOCSUPERVISORHANDLER_H_ */
|
#endif /* MISSION_DEVICES_PLOCSUPERVISORHANDLER_H_ */
|
||||||
|
@ -1,7 +1,7 @@
|
|||||||
/**
|
/**
|
||||||
* @brief Auto-generated event translation file. Contains 207 translations.
|
* @brief Auto-generated event translation file. Contains 209 translations.
|
||||||
* @details
|
* @details
|
||||||
* Generated on: 2022-05-25 18:14:41
|
* Generated on: 2022-06-27 09:14:37
|
||||||
*/
|
*/
|
||||||
#include "translateEvents.h"
|
#include "translateEvents.h"
|
||||||
|
|
||||||
@ -134,6 +134,8 @@ const char *INVALID_TC_FRAME_STRING = "INVALID_TC_FRAME";
|
|||||||
const char *INVALID_FAR_STRING = "INVALID_FAR";
|
const char *INVALID_FAR_STRING = "INVALID_FAR";
|
||||||
const char *CARRIER_LOCK_STRING = "CARRIER_LOCK";
|
const char *CARRIER_LOCK_STRING = "CARRIER_LOCK";
|
||||||
const char *BIT_LOCK_PDEC_STRING = "BIT_LOCK_PDEC";
|
const char *BIT_LOCK_PDEC_STRING = "BIT_LOCK_PDEC";
|
||||||
|
const char *LOST_CARRIER_LOCK_PDEC_STRING = "LOST_CARRIER_LOCK_PDEC";
|
||||||
|
const char *LOST_BIT_LOCK_PDEC_STRING = "LOST_BIT_LOCK_PDEC";
|
||||||
const char *IMAGE_UPLOAD_FAILED_STRING = "IMAGE_UPLOAD_FAILED";
|
const char *IMAGE_UPLOAD_FAILED_STRING = "IMAGE_UPLOAD_FAILED";
|
||||||
const char *IMAGE_DOWNLOAD_FAILED_STRING = "IMAGE_DOWNLOAD_FAILED";
|
const char *IMAGE_DOWNLOAD_FAILED_STRING = "IMAGE_DOWNLOAD_FAILED";
|
||||||
const char *IMAGE_UPLOAD_SUCCESSFUL_STRING = "IMAGE_UPLOAD_SUCCESSFUL";
|
const char *IMAGE_UPLOAD_SUCCESSFUL_STRING = "IMAGE_UPLOAD_SUCCESSFUL";
|
||||||
@ -469,6 +471,10 @@ const char *translateEvents(Event event) {
|
|||||||
return CARRIER_LOCK_STRING;
|
return CARRIER_LOCK_STRING;
|
||||||
case (12404):
|
case (12404):
|
||||||
return BIT_LOCK_PDEC_STRING;
|
return BIT_LOCK_PDEC_STRING;
|
||||||
|
case (12405):
|
||||||
|
return LOST_CARRIER_LOCK_PDEC_STRING;
|
||||||
|
case (12406):
|
||||||
|
return LOST_BIT_LOCK_PDEC_STRING;
|
||||||
case (12500):
|
case (12500):
|
||||||
return IMAGE_UPLOAD_FAILED_STRING;
|
return IMAGE_UPLOAD_FAILED_STRING;
|
||||||
case (12501):
|
case (12501):
|
||||||
|
@ -1,5 +1,5 @@
|
|||||||
#ifndef HOSTED_CONFIG_OBJECTS_SYSTEMOBJECTLIST_H_
|
#ifndef LINUX_FSFWCONFIG_OBJECTS_SYSTEMOBJECTLIST_H_
|
||||||
#define HOSTED_CONFIG_OBJECTS_SYSTEMOBJECTLIST_H_
|
#define LINUX_FSFWCONFIG_OBJECTS_SYSTEMOBJECTLIST_H_
|
||||||
|
|
||||||
#include <fsfw/objectmanager/frameworkObjects.h>
|
#include <fsfw/objectmanager/frameworkObjects.h>
|
||||||
|
|
||||||
@ -64,7 +64,8 @@ enum sourceObjects : uint32_t {
|
|||||||
DUMMY_INTERFACE = 0x5400CAFE,
|
DUMMY_INTERFACE = 0x5400CAFE,
|
||||||
DUMMY_HANDLER = 0x5400AFFE,
|
DUMMY_HANDLER = 0x5400AFFE,
|
||||||
P60DOCK_TEST_TASK = 0x00005060,
|
P60DOCK_TEST_TASK = 0x00005060,
|
||||||
|
DUMMY_COM_IF = 0x54000040
|
||||||
};
|
};
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif /* BSP_CONFIG_OBJECTS_SYSTEMOBJECTLIST_H_ */
|
#endif /* LINUX_FSFWCONFIG_OBJECTS_SYSTEMOBJECTLIST_H_ */
|
||||||
|
@ -1,8 +1,8 @@
|
|||||||
/**
|
/**
|
||||||
* @brief Auto-generated object translation file.
|
* @brief Auto-generated object translation file.
|
||||||
* @details
|
* @details
|
||||||
* Contains 131 translations.
|
* Contains 132 translations.
|
||||||
* Generated on: 2022-05-25 18:14:41
|
* Generated on: 2022-06-27 09:14:34
|
||||||
*/
|
*/
|
||||||
#include "translateObjects.h"
|
#include "translateObjects.h"
|
||||||
|
|
||||||
@ -118,6 +118,7 @@ const char *FSFW_OBJECTS_END_STRING = "FSFW_OBJECTS_END";
|
|||||||
const char *SPI_TEST_STRING = "SPI_TEST";
|
const char *SPI_TEST_STRING = "SPI_TEST";
|
||||||
const char *UART_TEST_STRING = "UART_TEST";
|
const char *UART_TEST_STRING = "UART_TEST";
|
||||||
const char *I2C_TEST_STRING = "I2C_TEST";
|
const char *I2C_TEST_STRING = "I2C_TEST";
|
||||||
|
const char *DUMMY_COM_IF_STRING = "DUMMY_COM_IF";
|
||||||
const char *DUMMY_HANDLER_STRING = "DUMMY_HANDLER";
|
const char *DUMMY_HANDLER_STRING = "DUMMY_HANDLER";
|
||||||
const char *DUMMY_INTERFACE_STRING = "DUMMY_INTERFACE";
|
const char *DUMMY_INTERFACE_STRING = "DUMMY_INTERFACE";
|
||||||
const char *LIBGPIOD_TEST_STRING = "LIBGPIOD_TEST";
|
const char *LIBGPIOD_TEST_STRING = "LIBGPIOD_TEST";
|
||||||
@ -364,6 +365,8 @@ const char *translateObject(object_id_t object) {
|
|||||||
return UART_TEST_STRING;
|
return UART_TEST_STRING;
|
||||||
case 0x54000030:
|
case 0x54000030:
|
||||||
return I2C_TEST_STRING;
|
return I2C_TEST_STRING;
|
||||||
|
case 0x54000040:
|
||||||
|
return DUMMY_COM_IF_STRING;
|
||||||
case 0x5400AFFE:
|
case 0x5400AFFE:
|
||||||
return DUMMY_HANDLER_STRING;
|
return DUMMY_HANDLER_STRING;
|
||||||
case 0x5400CAFE:
|
case 0x5400CAFE:
|
||||||
|
@ -191,15 +191,20 @@ bool PdecHandler::newTcReceived() {
|
|||||||
|
|
||||||
void PdecHandler::checkLocks() {
|
void PdecHandler::checkLocks() {
|
||||||
uint32_t clcw = getClcw();
|
uint32_t clcw = getClcw();
|
||||||
if (!(clcw & NO_RF_MASK) && (lastClcw & NO_RF_MASK)) {
|
if (not(clcw & NO_RF_MASK) && not carrierLock) {
|
||||||
// Rf available changed from 0 to 1
|
|
||||||
triggerEvent(CARRIER_LOCK);
|
triggerEvent(CARRIER_LOCK);
|
||||||
|
carrierLock = true;
|
||||||
|
} else if ((clcw & NO_RF_MASK) && carrierLock) {
|
||||||
|
carrierLock = false;
|
||||||
|
triggerEvent(LOST_CARRIER_LOCK_PDEC);
|
||||||
}
|
}
|
||||||
if (!(clcw & NO_BITLOCK_MASK) && (lastClcw & NO_BITLOCK_MASK)) {
|
if (not(clcw & NO_BITLOCK_MASK) && not bitLock) {
|
||||||
// Bit lock changed from 0 to 1
|
|
||||||
triggerEvent(BIT_LOCK_PDEC);
|
triggerEvent(BIT_LOCK_PDEC);
|
||||||
|
bitLock = true;
|
||||||
|
} else if ((clcw & NO_BITLOCK_MASK) && bitLock) {
|
||||||
|
bitLock = false;
|
||||||
|
triggerEvent(LOST_BIT_LOCK_PDEC);
|
||||||
}
|
}
|
||||||
lastClcw = clcw;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
bool PdecHandler::checkFrameAna(uint32_t pdecFar) {
|
bool PdecHandler::checkFrameAna(uint32_t pdecFar) {
|
||||||
|
@ -73,6 +73,10 @@ class PdecHandler : public SystemObject,
|
|||||||
static const Event CARRIER_LOCK = MAKE_EVENT(3, severity::INFO);
|
static const Event CARRIER_LOCK = MAKE_EVENT(3, severity::INFO);
|
||||||
//! [EXPORT] : [COMMENT] Bit lock detected (data valid)
|
//! [EXPORT] : [COMMENT] Bit lock detected (data valid)
|
||||||
static const Event BIT_LOCK_PDEC = MAKE_EVENT(4, severity::INFO);
|
static const Event BIT_LOCK_PDEC = MAKE_EVENT(4, severity::INFO);
|
||||||
|
//! [EXPORT] : [COMMENT] Lost carrier lock
|
||||||
|
static const Event LOST_CARRIER_LOCK_PDEC = MAKE_EVENT(5, severity::INFO);
|
||||||
|
//! [EXPORT] : [COMMENT] Lost bit lock
|
||||||
|
static const Event LOST_BIT_LOCK_PDEC = MAKE_EVENT(6, severity::INFO);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
static const uint8_t INTERFACE_ID = CLASS_ID::PDEC_HANDLER;
|
static const uint8_t INTERFACE_ID = CLASS_ID::PDEC_HANDLER;
|
||||||
@ -391,6 +395,9 @@ class PdecHandler : public SystemObject,
|
|||||||
|
|
||||||
// Used to check carrier and bit lock changes (default set to no rf and no bitlock)
|
// Used to check carrier and bit lock changes (default set to no rf and no bitlock)
|
||||||
uint32_t lastClcw = 0xC000;
|
uint32_t lastClcw = 0xC000;
|
||||||
|
|
||||||
|
bool carrierLock = false;
|
||||||
|
bool bitLock = false;
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* LINUX_OBC_PDECHANDLER_H_ */
|
#endif /* LINUX_OBC_PDECHANDLER_H_ */
|
||||||
|
@ -21,7 +21,7 @@
|
|||||||
<stringAttribute key="org.eclipse.cdt.launch.PROGRAM_NAME" value="cmake-build-debug/eive-obsw"/>
|
<stringAttribute key="org.eclipse.cdt.launch.PROGRAM_NAME" value="cmake-build-debug/eive-obsw"/>
|
||||||
<stringAttribute key="org.eclipse.cdt.launch.PROJECT_ATTR" value="eive-obsw"/>
|
<stringAttribute key="org.eclipse.cdt.launch.PROJECT_ATTR" value="eive-obsw"/>
|
||||||
<booleanAttribute key="org.eclipse.cdt.launch.PROJECT_BUILD_CONFIG_AUTO_ATTR" value="false"/>
|
<booleanAttribute key="org.eclipse.cdt.launch.PROJECT_BUILD_CONFIG_AUTO_ATTR" value="false"/>
|
||||||
<stringAttribute key="org.eclipse.cdt.launch.PROJECT_BUILD_CONFIG_ID_ATTR" value="cdt.managedbuild.toolchain.gnu.mingw.base.1455833186.1840876443.2117915473"/>
|
<stringAttribute key="org.eclipse.cdt.launch.PROJECT_BUILD_CONFIG_ID_ATTR" value=""/>
|
||||||
<listAttribute key="org.eclipse.debug.core.MAPPED_RESOURCE_PATHS">
|
<listAttribute key="org.eclipse.debug.core.MAPPED_RESOURCE_PATHS">
|
||||||
<listEntry value="/eive-obsw"/>
|
<listEntry value="/eive-obsw"/>
|
||||||
</listAttribute>
|
</listAttribute>
|
||||||
|
@ -20,12 +20,13 @@
|
|||||||
<stringAttribute key="org.eclipse.cdt.launch.PROGRAM_NAME" value="cmake-build-debug/eive-unittest"/>
|
<stringAttribute key="org.eclipse.cdt.launch.PROGRAM_NAME" value="cmake-build-debug/eive-unittest"/>
|
||||||
<stringAttribute key="org.eclipse.cdt.launch.PROJECT_ATTR" value="eive-obsw"/>
|
<stringAttribute key="org.eclipse.cdt.launch.PROJECT_ATTR" value="eive-obsw"/>
|
||||||
<booleanAttribute key="org.eclipse.cdt.launch.PROJECT_BUILD_CONFIG_AUTO_ATTR" value="false"/>
|
<booleanAttribute key="org.eclipse.cdt.launch.PROJECT_BUILD_CONFIG_AUTO_ATTR" value="false"/>
|
||||||
<stringAttribute key="org.eclipse.cdt.launch.PROJECT_BUILD_CONFIG_ID_ATTR" value="cdt.managedbuild.toolchain.gnu.mingw.base.1455833186.1840876443.2117915473.758550634"/>
|
<stringAttribute key="org.eclipse.cdt.launch.PROJECT_BUILD_CONFIG_ID_ATTR" value=""/>
|
||||||
<listAttribute key="org.eclipse.debug.core.MAPPED_RESOURCE_PATHS">
|
<listAttribute key="org.eclipse.debug.core.MAPPED_RESOURCE_PATHS">
|
||||||
<listEntry value="/eive-obsw"/>
|
<listEntry value="/eive-obsw"/>
|
||||||
</listAttribute>
|
</listAttribute>
|
||||||
<listAttribute key="org.eclipse.debug.core.MAPPED_RESOURCE_TYPES">
|
<listAttribute key="org.eclipse.debug.core.MAPPED_RESOURCE_TYPES">
|
||||||
<listEntry value="4"/>
|
<listEntry value="4"/>
|
||||||
</listAttribute>
|
</listAttribute>
|
||||||
|
<stringAttribute key="org.eclipse.dsf.launch.MEMORY_BLOCKS" value="<?xml version="1.0" encoding="UTF-8" standalone="no"?><memoryBlockExpressionList context="reserved-for-future-use"/>"/>
|
||||||
<stringAttribute key="process_factory_id" value="org.eclipse.cdt.dsf.gdb.GdbProcessFactory"/>
|
<stringAttribute key="process_factory_id" value="org.eclipse.cdt.dsf.gdb.GdbProcessFactory"/>
|
||||||
</launchConfiguration>
|
</launchConfiguration>
|
||||||
|
@ -1 +1,3 @@
|
|||||||
|
if(TGT_BSP MATCHES "arm/q7s" OR TGT_BSP MATCHES "")
|
||||||
target_sources(${LIB_EIVE_MISSION} PRIVATE ThermalController.cpp)
|
target_sources(${LIB_EIVE_MISSION} PRIVATE ThermalController.cpp)
|
||||||
|
endif()
|
||||||
|
@ -1,40 +1,224 @@
|
|||||||
#include "ThermalController.h"
|
#include "ThermalController.h"
|
||||||
|
|
||||||
|
#include <bsp_q7s/core/CoreDefinitions.h>
|
||||||
|
#include <fsfw/datapool/PoolReadGuard.h>
|
||||||
|
#include <fsfw_hal/devicehandlers/devicedefinitions/MgmLIS3HandlerDefs.h>
|
||||||
|
#include <linux/devices/devicedefinitions/StarTrackerDefinitions.h>
|
||||||
|
#include <mission/devices/devicedefinitions/BpxBatteryDefinitions.h>
|
||||||
|
#include <mission/devices/devicedefinitions/GomspaceDefinitions.h>
|
||||||
|
#include <mission/devices/devicedefinitions/GyroADIS1650XDefinitions.h>
|
||||||
|
#include <mission/devices/devicedefinitions/GyroL3GD20Definitions.h>
|
||||||
|
#include <mission/devices/devicedefinitions/IMTQHandlerDefinitions.h>
|
||||||
|
#include <mission/devices/devicedefinitions/RwDefinitions.h>
|
||||||
|
#include <mission/devices/devicedefinitions/SyrlinksDefinitions.h>
|
||||||
|
#include <mission/devices/devicedefinitions/payloadPcduDefinitions.h>
|
||||||
|
#include <objects/systemObjectList.h>
|
||||||
|
|
||||||
ThermalController::ThermalController(object_id_t objectId, object_id_t parentId)
|
ThermalController::ThermalController(object_id_t objectId, object_id_t parentId)
|
||||||
: ExtendedControllerBase(objectId, parentId),
|
: ExtendedControllerBase(objectId, parentId),
|
||||||
sensorTemperatures(this),
|
sensorTemperatures(this),
|
||||||
componentTemperatures(this) {}
|
susTemperatures(this),
|
||||||
|
deviceTemperatures(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) {
|
ReturnValue_t ThermalController::handleCommandMessage(CommandMessage* message) {
|
||||||
return RETURN_FAILED;
|
return RETURN_FAILED;
|
||||||
}
|
}
|
||||||
|
|
||||||
void ThermalController::performControlOperation() {
|
void ThermalController::performControlOperation() {
|
||||||
|
switch (internalState) {
|
||||||
|
case InternalState::STARTUP: {
|
||||||
|
initialCountdown.resetTimer();
|
||||||
|
internalState = InternalState::INITIAL_DELAY;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
case InternalState::INITIAL_DELAY: {
|
||||||
|
if (initialCountdown.hasTimedOut()) {
|
||||||
|
internalState = InternalState::READY;
|
||||||
|
}
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
case InternalState::READY: {
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
ReturnValue_t result = sensorTemperatures.read();
|
ReturnValue_t result = sensorTemperatures.read();
|
||||||
if (result != RETURN_OK) {
|
if (result == RETURN_OK) {
|
||||||
return;
|
copySensors();
|
||||||
}
|
|
||||||
result = componentTemperatures.read();
|
|
||||||
if (result != RETURN_OK) {
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
componentTemperatures.rw = (sensorTemperatures.rw.value + sensorTemperatures.gps.value) / 2;
|
|
||||||
|
|
||||||
sensorTemperatures.commit();
|
sensorTemperatures.commit();
|
||||||
componentTemperatures.commit();
|
}
|
||||||
|
|
||||||
|
result = susTemperatures.read();
|
||||||
|
if (result == RETURN_OK) {
|
||||||
|
copySus();
|
||||||
|
susTemperatures.commit();
|
||||||
|
}
|
||||||
|
|
||||||
|
result = deviceTemperatures.read();
|
||||||
|
if (result == RETURN_OK) {
|
||||||
|
copyDevices();
|
||||||
|
deviceTemperatures.commit();
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
ReturnValue_t ThermalController::initializeLocalDataPool(localpool::DataPool& localDataPoolMap,
|
ReturnValue_t ThermalController::initializeLocalDataPool(localpool::DataPool& localDataPoolMap,
|
||||||
LocalDataPoolManager& poolManager) {
|
LocalDataPoolManager& poolManager) {
|
||||||
localDataPoolMap.emplace(thermalControllerDefinitions::SENSOR_RW, new PoolEntry<float>({0.0}));
|
localDataPoolMap.emplace(thermalControllerDefinitions::SENSOR_PLOC_HEATSPREADER,
|
||||||
localDataPoolMap.emplace(thermalControllerDefinitions::SENSOR_GPS, new PoolEntry<float>({0.0}));
|
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::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<float>({0}));
|
||||||
|
localDataPoolMap.emplace(thermalControllerDefinitions::TEMP_SYRLINKS_BASEBAND_BOARD,
|
||||||
|
new PoolEntry<float>({0}));
|
||||||
|
localDataPoolMap.emplace(thermalControllerDefinitions::TEMP_MGT, new PoolEntry<int16_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(), false, 1.0, false);
|
||||||
|
poolManager.subscribeForPeriodicPacket(susTemperatures.getSid(), false, 1.0, false);
|
||||||
|
poolManager.subscribeForPeriodicPacket(deviceTemperatures.getSid(), false, 1.0, false);
|
||||||
|
|
||||||
return RETURN_OK;
|
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,
|
ReturnValue_t ThermalController::checkModeCommand(Mode_t mode, Submode_t submode,
|
||||||
uint32_t* msToReachTheMode) {
|
uint32_t* msToReachTheMode) {
|
||||||
@ -46,3 +230,647 @@ ReturnValue_t ThermalController::checkModeCommand(Mode_t mode, Submode_t submode
|
|||||||
}
|
}
|
||||||
return RETURN_OK;
|
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<float> tempSyrlinksPowerAmplifier =
|
||||||
|
lp_var_t<float>(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<float> tempSyrlinksBasebandBoard =
|
||||||
|
lp_var_t<float>(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<int16_t> tempMgt = lp_var_t<int16_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<int16_t>(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);
|
||||||
|
deviceTemperatures.acu[0] = static_cast<float>(INVALID_TEMPERATURE);
|
||||||
|
deviceTemperatures.acu[1] = static_cast<float>(INVALID_TEMPERATURE);
|
||||||
|
deviceTemperatures.acu[2] = static_cast<float>(INVALID_TEMPERATURE);
|
||||||
|
} 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;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
@ -2,10 +2,16 @@
|
|||||||
#define MISSION_CONTROLLER_THERMALCONTROLLER_H_
|
#define MISSION_CONTROLLER_THERMALCONTROLLER_H_
|
||||||
|
|
||||||
#include <fsfw/controller/ExtendedControllerBase.h>
|
#include <fsfw/controller/ExtendedControllerBase.h>
|
||||||
|
#include <fsfw/timemanager/Countdown.h>
|
||||||
#include <mission/controller/controllerdefinitions/ThermalControllerDefinitions.h>
|
#include <mission/controller/controllerdefinitions/ThermalControllerDefinitions.h>
|
||||||
|
#include <mission/devices/devicedefinitions/Max31865Definitions.h>
|
||||||
|
#include <mission/devices/devicedefinitions/SusDefinitions.h>
|
||||||
|
#include <mission/devices/devicedefinitions/Tmp1075Definitions.h>
|
||||||
|
|
||||||
class ThermalController : public ExtendedControllerBase {
|
class ThermalController : public ExtendedControllerBase {
|
||||||
public:
|
public:
|
||||||
|
static const uint16_t INVALID_TEMPERATURE = 999;
|
||||||
|
|
||||||
ThermalController(object_id_t objectId, object_id_t parentId);
|
ThermalController(object_id_t objectId, object_id_t parentId);
|
||||||
|
|
||||||
ReturnValue_t initialize() override;
|
ReturnValue_t initialize() override;
|
||||||
@ -22,8 +28,56 @@ class ThermalController : public ExtendedControllerBase {
|
|||||||
uint32_t* msToReachTheMode) override;
|
uint32_t* msToReachTheMode) override;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
static const uint32_t DELAY = 500;
|
||||||
|
|
||||||
|
enum class InternalState { STARTUP, INITIAL_DELAY, READY };
|
||||||
|
|
||||||
|
InternalState internalState = InternalState::STARTUP;
|
||||||
|
|
||||||
thermalControllerDefinitions::SensorTemperatures sensorTemperatures;
|
thermalControllerDefinitions::SensorTemperatures sensorTemperatures;
|
||||||
thermalControllerDefinitions::ComponentTemperatures componentTemperatures;
|
thermalControllerDefinitions::SusTemperatures susTemperatures;
|
||||||
|
thermalControllerDefinitions::DeviceTemperatures deviceTemperatures;
|
||||||
|
|
||||||
|
// 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;
|
||||||
|
|
||||||
|
// Initial delay to make sure all pool variables have been initialized their owners
|
||||||
|
Countdown initialCountdown = Countdown(DELAY);
|
||||||
|
|
||||||
|
void copySensors();
|
||||||
|
void copySus();
|
||||||
|
void copyDevices();
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* MISSION_CONTROLLER_THERMALCONTROLLER_H_ */
|
#endif /* MISSION_CONTROLLER_THERMALCONTROLLER_H_ */
|
||||||
|
@ -6,36 +6,190 @@
|
|||||||
|
|
||||||
namespace thermalControllerDefinitions {
|
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
|
* @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:
|
public:
|
||||||
SensorTemperatures(HasLocalDataPoolIF* owner) : StaticLocalDataSet(owner, SENSOR_TEMPERATURES) {}
|
SensorTemperatures(HasLocalDataPoolIF* owner) : StaticLocalDataSet(owner, SENSOR_TEMPERATURES) {}
|
||||||
|
|
||||||
SensorTemperatures(object_id_t objectId)
|
SensorTemperatures(object_id_t objectId)
|
||||||
: StaticLocalDataSet(sid_t(objectId, SENSOR_TEMPERATURES)) {}
|
: 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> sensor_ploc_heatspreader =
|
||||||
lp_var_t<float> gps = lp_var_t<float>(sid.objectId, PoolIds::SENSOR_GPS, this);
|
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 components
|
* @brief This dataset can be used to store the collected temperatures of all device temperature
|
||||||
|
* sensors
|
||||||
*/
|
*/
|
||||||
class ComponentTemperatures : public StaticLocalDataSet<2> {
|
class DeviceTemperatures : public StaticLocalDataSet<ENTRIES_DEVICE_TEMPERATURE_SET> {
|
||||||
public:
|
public:
|
||||||
ComponentTemperatures(HasLocalDataPoolIF* owner)
|
DeviceTemperatures(HasLocalDataPoolIF* owner) : StaticLocalDataSet(owner, DEVICE_TEMPERATURES) {}
|
||||||
: StaticLocalDataSet(owner, SENSOR_TEMPERATURES) {}
|
|
||||||
|
|
||||||
ComponentTemperatures(object_id_t objectId)
|
DeviceTemperatures(object_id_t objectId)
|
||||||
: StaticLocalDataSet(sid_t(objectId, SENSOR_TEMPERATURES)) {}
|
: StaticLocalDataSet(sid_t(objectId, DEVICE_TEMPERATURES)) {}
|
||||||
|
|
||||||
lp_var_t<float> rw = lp_var_t<float>(sid.objectId, PoolIds::COMPONENT_RW, this);
|
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<float> syrlinksPowerAmplifier =
|
||||||
|
lp_var_t<float>(sid.objectId, PoolIds::TEMP_SYRLINKS_POWER_AMPLIFIER, this);
|
||||||
|
lp_var_t<float> syrlinksBasebandBoard =
|
||||||
|
lp_var_t<float>(sid.objectId, PoolIds::TEMP_SYRLINKS_BASEBAND_BOARD, this);
|
||||||
|
lp_var_t<int16_t> mgt = lp_var_t<int16_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);
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace thermalControllerDefinitions
|
} // namespace thermalControllerDefinitions
|
||||||
|
@ -17,7 +17,7 @@
|
|||||||
#include <fsfw/tcdistribution/CCSDSDistributor.h>
|
#include <fsfw/tcdistribution/CCSDSDistributor.h>
|
||||||
#include <fsfw/tcdistribution/PUSDistributor.h>
|
#include <fsfw/tcdistribution/PUSDistributor.h>
|
||||||
#include <fsfw/timemanager/TimeStamper.h>
|
#include <fsfw/timemanager/TimeStamper.h>
|
||||||
#include <mission/utility/TmFunnel.h>
|
#include <mission/tmtc/TmFunnel.h>
|
||||||
|
|
||||||
#include "OBSWConfig.h"
|
#include "OBSWConfig.h"
|
||||||
#include "eive/definitions.h"
|
#include "eive/definitions.h"
|
||||||
|
@ -75,7 +75,8 @@ ReturnValue_t ACUHandler::parseHkTableReply(const uint8_t *packet) {
|
|||||||
dataOffset += 4;
|
dataOffset += 4;
|
||||||
|
|
||||||
for (size_t idx = 0; idx < 3; idx++) {
|
for (size_t idx = 0; idx < 3; idx++) {
|
||||||
coreHk.temperatures[idx] = (packet[dataOffset] << 8) | packet[dataOffset + 1];
|
coreHk.temperatures[idx] =
|
||||||
|
static_cast<int16_t>((packet[dataOffset] << 8) | packet[dataOffset + 1]) * 0.1;
|
||||||
dataOffset += 4;
|
dataOffset += 4;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -146,7 +147,7 @@ ReturnValue_t ACUHandler::initializeLocalDataPool(localpool::DataPool &localData
|
|||||||
localDataPoolMap.emplace(pool::ACU_VCC, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(pool::ACU_VCC, new PoolEntry<uint16_t>({0}));
|
||||||
localDataPoolMap.emplace(pool::ACU_VBAT, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(pool::ACU_VBAT, new PoolEntry<uint16_t>({0}));
|
||||||
|
|
||||||
localDataPoolMap.emplace(pool::ACU_TEMPERATURES, new PoolEntry<int16_t>(3));
|
localDataPoolMap.emplace(pool::ACU_TEMPERATURES, new PoolEntry<float>(3));
|
||||||
|
|
||||||
localDataPoolMap.emplace(pool::ACU_MPPT_MODE, new PoolEntry<uint8_t>({0}));
|
localDataPoolMap.emplace(pool::ACU_MPPT_MODE, new PoolEntry<uint8_t>({0}));
|
||||||
|
|
||||||
|
@ -366,7 +366,7 @@ ReturnValue_t GomspaceDeviceHandler::initializePduPool(
|
|||||||
|
|
||||||
localDataPoolMap.emplace(P60System::pool::PDU_VCC, new PoolEntry<int16_t>({0}));
|
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_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_CONV_EN, new PoolEntry<uint8_t>(3));
|
||||||
|
|
||||||
localDataPoolMap.emplace(P60System::pool::PDU_OUT_ENABLE,
|
localDataPoolMap.emplace(P60System::pool::PDU_OUT_ENABLE,
|
||||||
@ -472,7 +472,8 @@ ReturnValue_t GomspaceDeviceHandler::parsePduHkTable(PDU::PduCoreHk& coreHk, PDU
|
|||||||
dataOffset += 4;
|
dataOffset += 4;
|
||||||
auxHk.vbat = *(packet + dataOffset) << 8 | *(packet + dataOffset + 1);
|
auxHk.vbat = *(packet + dataOffset) << 8 | *(packet + dataOffset + 1);
|
||||||
dataOffset += 4;
|
dataOffset += 4;
|
||||||
coreHk.temperature = *(packet + dataOffset) << 8 | *(packet + dataOffset + 1);
|
coreHk.temperature =
|
||||||
|
static_cast<int16_t>(*(packet + dataOffset) << 8 | *(packet + dataOffset + 1)) * 0.1;
|
||||||
dataOffset += 4;
|
dataOffset += 4;
|
||||||
|
|
||||||
for (uint8_t idx = 0; idx < 3; idx++) {
|
for (uint8_t idx = 0; idx < 3; idx++) {
|
||||||
|
@ -14,6 +14,7 @@
|
|||||||
#include <fsfw/timemanager/Countdown.h>
|
#include <fsfw/timemanager/Countdown.h>
|
||||||
#include <fsfw_hal/common/gpio/GpioIF.h>
|
#include <fsfw_hal/common/gpio/GpioIF.h>
|
||||||
|
|
||||||
|
#include <array>
|
||||||
#include <vector>
|
#include <vector>
|
||||||
|
|
||||||
#include "devices/heaterSwitcherList.h"
|
#include "devices/heaterSwitcherList.h"
|
||||||
|
@ -325,10 +325,10 @@ ReturnValue_t IMTQHandler::initializeLocalDataPool(localpool::DataPool& localDat
|
|||||||
localDataPoolMap.emplace(IMTQ::COIL_X_CURRENT, new PoolEntry<float>({0}));
|
localDataPoolMap.emplace(IMTQ::COIL_X_CURRENT, new PoolEntry<float>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::COIL_Y_CURRENT, new PoolEntry<float>({0}));
|
localDataPoolMap.emplace(IMTQ::COIL_Y_CURRENT, new PoolEntry<float>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::COIL_Z_CURRENT, new PoolEntry<float>({0}));
|
localDataPoolMap.emplace(IMTQ::COIL_Z_CURRENT, new PoolEntry<float>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::COIL_X_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::COIL_X_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::COIL_Y_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::COIL_Y_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::COIL_Z_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::COIL_Z_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::MCU_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::MCU_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
|
|
||||||
/** Entries of calibrated MTM measurement dataset */
|
/** Entries of calibrated MTM measurement dataset */
|
||||||
localDataPoolMap.emplace(IMTQ::MTM_CAL_X, new PoolEntry<int32_t>({0}));
|
localDataPoolMap.emplace(IMTQ::MTM_CAL_X, new PoolEntry<int32_t>({0}));
|
||||||
@ -353,9 +353,9 @@ ReturnValue_t IMTQHandler::initializeLocalDataPool(localpool::DataPool& localDat
|
|||||||
localDataPoolMap.emplace(IMTQ::INIT_POS_X_COIL_X_CURRENT, new PoolEntry<float>({0}));
|
localDataPoolMap.emplace(IMTQ::INIT_POS_X_COIL_X_CURRENT, new PoolEntry<float>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::INIT_POS_X_COIL_Y_CURRENT, new PoolEntry<float>({0}));
|
localDataPoolMap.emplace(IMTQ::INIT_POS_X_COIL_Y_CURRENT, new PoolEntry<float>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::INIT_POS_X_COIL_Z_CURRENT, new PoolEntry<float>({0}));
|
localDataPoolMap.emplace(IMTQ::INIT_POS_X_COIL_Z_CURRENT, new PoolEntry<float>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::INIT_POS_X_COIL_X_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::INIT_POS_X_COIL_X_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::INIT_POS_X_COIL_Y_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::INIT_POS_X_COIL_Y_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::INIT_POS_X_COIL_Z_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::INIT_POS_X_COIL_Z_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
|
|
||||||
/** INIT measurements for negative X axis test */
|
/** INIT measurements for negative X axis test */
|
||||||
localDataPoolMap.emplace(IMTQ::INIT_NEG_X_ERR, new PoolEntry<uint8_t>({0}));
|
localDataPoolMap.emplace(IMTQ::INIT_NEG_X_ERR, new PoolEntry<uint8_t>({0}));
|
||||||
@ -368,9 +368,9 @@ ReturnValue_t IMTQHandler::initializeLocalDataPool(localpool::DataPool& localDat
|
|||||||
localDataPoolMap.emplace(IMTQ::INIT_NEG_X_COIL_X_CURRENT, new PoolEntry<float>({0}));
|
localDataPoolMap.emplace(IMTQ::INIT_NEG_X_COIL_X_CURRENT, new PoolEntry<float>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::INIT_NEG_X_COIL_Y_CURRENT, new PoolEntry<float>({0}));
|
localDataPoolMap.emplace(IMTQ::INIT_NEG_X_COIL_Y_CURRENT, new PoolEntry<float>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::INIT_NEG_X_COIL_Z_CURRENT, new PoolEntry<float>({0}));
|
localDataPoolMap.emplace(IMTQ::INIT_NEG_X_COIL_Z_CURRENT, new PoolEntry<float>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::INIT_NEG_X_COIL_X_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::INIT_NEG_X_COIL_X_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::INIT_NEG_X_COIL_Y_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::INIT_NEG_X_COIL_Y_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::INIT_NEG_X_COIL_Z_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::INIT_NEG_X_COIL_Z_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
|
|
||||||
/** INIT measurements for positive Y axis test */
|
/** INIT measurements for positive Y axis test */
|
||||||
localDataPoolMap.emplace(IMTQ::INIT_POS_Y_ERR, new PoolEntry<uint8_t>({0}));
|
localDataPoolMap.emplace(IMTQ::INIT_POS_Y_ERR, new PoolEntry<uint8_t>({0}));
|
||||||
@ -383,9 +383,9 @@ ReturnValue_t IMTQHandler::initializeLocalDataPool(localpool::DataPool& localDat
|
|||||||
localDataPoolMap.emplace(IMTQ::INIT_POS_Y_COIL_X_CURRENT, new PoolEntry<float>({0}));
|
localDataPoolMap.emplace(IMTQ::INIT_POS_Y_COIL_X_CURRENT, new PoolEntry<float>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::INIT_POS_Y_COIL_Y_CURRENT, new PoolEntry<float>({0}));
|
localDataPoolMap.emplace(IMTQ::INIT_POS_Y_COIL_Y_CURRENT, new PoolEntry<float>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::INIT_POS_Y_COIL_Z_CURRENT, new PoolEntry<float>({0}));
|
localDataPoolMap.emplace(IMTQ::INIT_POS_Y_COIL_Z_CURRENT, new PoolEntry<float>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::INIT_POS_Y_COIL_X_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::INIT_POS_Y_COIL_X_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::INIT_POS_Y_COIL_Y_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::INIT_POS_Y_COIL_Y_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::INIT_POS_Y_COIL_Z_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::INIT_POS_Y_COIL_Z_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
|
|
||||||
/** INIT measurements for negative Y axis test */
|
/** INIT measurements for negative Y axis test */
|
||||||
localDataPoolMap.emplace(IMTQ::INIT_NEG_Y_ERR, new PoolEntry<uint8_t>({0}));
|
localDataPoolMap.emplace(IMTQ::INIT_NEG_Y_ERR, new PoolEntry<uint8_t>({0}));
|
||||||
@ -398,9 +398,9 @@ ReturnValue_t IMTQHandler::initializeLocalDataPool(localpool::DataPool& localDat
|
|||||||
localDataPoolMap.emplace(IMTQ::INIT_NEG_Y_COIL_X_CURRENT, new PoolEntry<float>({0}));
|
localDataPoolMap.emplace(IMTQ::INIT_NEG_Y_COIL_X_CURRENT, new PoolEntry<float>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::INIT_NEG_Y_COIL_Y_CURRENT, new PoolEntry<float>({0}));
|
localDataPoolMap.emplace(IMTQ::INIT_NEG_Y_COIL_Y_CURRENT, new PoolEntry<float>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::INIT_NEG_Y_COIL_Z_CURRENT, new PoolEntry<float>({0}));
|
localDataPoolMap.emplace(IMTQ::INIT_NEG_Y_COIL_Z_CURRENT, new PoolEntry<float>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::INIT_NEG_Y_COIL_X_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::INIT_NEG_Y_COIL_X_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::INIT_NEG_Y_COIL_Y_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::INIT_NEG_Y_COIL_Y_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::INIT_NEG_Y_COIL_Z_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::INIT_NEG_Y_COIL_Z_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
|
|
||||||
/** INIT measurements for positive Z axis test */
|
/** INIT measurements for positive Z axis test */
|
||||||
localDataPoolMap.emplace(IMTQ::INIT_POS_Z_ERR, new PoolEntry<uint8_t>({0}));
|
localDataPoolMap.emplace(IMTQ::INIT_POS_Z_ERR, new PoolEntry<uint8_t>({0}));
|
||||||
@ -413,9 +413,9 @@ ReturnValue_t IMTQHandler::initializeLocalDataPool(localpool::DataPool& localDat
|
|||||||
localDataPoolMap.emplace(IMTQ::INIT_POS_Z_COIL_X_CURRENT, new PoolEntry<float>({0}));
|
localDataPoolMap.emplace(IMTQ::INIT_POS_Z_COIL_X_CURRENT, new PoolEntry<float>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::INIT_POS_Z_COIL_Y_CURRENT, new PoolEntry<float>({0}));
|
localDataPoolMap.emplace(IMTQ::INIT_POS_Z_COIL_Y_CURRENT, new PoolEntry<float>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::INIT_POS_Z_COIL_Z_CURRENT, new PoolEntry<float>({0}));
|
localDataPoolMap.emplace(IMTQ::INIT_POS_Z_COIL_Z_CURRENT, new PoolEntry<float>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::INIT_POS_Z_COIL_X_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::INIT_POS_Z_COIL_X_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::INIT_POS_Z_COIL_Y_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::INIT_POS_Z_COIL_Y_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::INIT_POS_Z_COIL_Z_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::INIT_POS_Z_COIL_Z_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
|
|
||||||
/** INIT measurements for negative Z axis test */
|
/** INIT measurements for negative Z axis test */
|
||||||
localDataPoolMap.emplace(IMTQ::INIT_NEG_Z_ERR, new PoolEntry<uint8_t>({0}));
|
localDataPoolMap.emplace(IMTQ::INIT_NEG_Z_ERR, new PoolEntry<uint8_t>({0}));
|
||||||
@ -428,9 +428,9 @@ ReturnValue_t IMTQHandler::initializeLocalDataPool(localpool::DataPool& localDat
|
|||||||
localDataPoolMap.emplace(IMTQ::INIT_NEG_Z_COIL_X_CURRENT, new PoolEntry<float>({0}));
|
localDataPoolMap.emplace(IMTQ::INIT_NEG_Z_COIL_X_CURRENT, new PoolEntry<float>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::INIT_NEG_Z_COIL_Y_CURRENT, new PoolEntry<float>({0}));
|
localDataPoolMap.emplace(IMTQ::INIT_NEG_Z_COIL_Y_CURRENT, new PoolEntry<float>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::INIT_NEG_Z_COIL_Z_CURRENT, new PoolEntry<float>({0}));
|
localDataPoolMap.emplace(IMTQ::INIT_NEG_Z_COIL_Z_CURRENT, new PoolEntry<float>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::INIT_NEG_Z_COIL_X_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::INIT_NEG_Z_COIL_X_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::INIT_NEG_Z_COIL_Y_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::INIT_NEG_Z_COIL_Y_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::INIT_NEG_Z_COIL_Z_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::INIT_NEG_Z_COIL_Z_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
|
|
||||||
localDataPoolMap.emplace(IMTQ::POS_X_ERR, new PoolEntry<uint8_t>({0}));
|
localDataPoolMap.emplace(IMTQ::POS_X_ERR, new PoolEntry<uint8_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::POS_X_RAW_MAG_X, new PoolEntry<float>({0}));
|
localDataPoolMap.emplace(IMTQ::POS_X_RAW_MAG_X, new PoolEntry<float>({0}));
|
||||||
@ -442,9 +442,9 @@ ReturnValue_t IMTQHandler::initializeLocalDataPool(localpool::DataPool& localDat
|
|||||||
localDataPoolMap.emplace(IMTQ::POS_X_COIL_X_CURRENT, new PoolEntry<float>({0}));
|
localDataPoolMap.emplace(IMTQ::POS_X_COIL_X_CURRENT, new PoolEntry<float>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::POS_X_COIL_Y_CURRENT, new PoolEntry<float>({0}));
|
localDataPoolMap.emplace(IMTQ::POS_X_COIL_Y_CURRENT, new PoolEntry<float>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::POS_X_COIL_Z_CURRENT, new PoolEntry<float>({0}));
|
localDataPoolMap.emplace(IMTQ::POS_X_COIL_Z_CURRENT, new PoolEntry<float>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::POS_X_COIL_X_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::POS_X_COIL_X_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::POS_X_COIL_Y_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::POS_X_COIL_Y_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::POS_X_COIL_Z_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::POS_X_COIL_Z_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
|
|
||||||
localDataPoolMap.emplace(IMTQ::NEG_X_ERR, new PoolEntry<uint8_t>({0}));
|
localDataPoolMap.emplace(IMTQ::NEG_X_ERR, new PoolEntry<uint8_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::NEG_X_RAW_MAG_X, new PoolEntry<uint32_t>({0}));
|
localDataPoolMap.emplace(IMTQ::NEG_X_RAW_MAG_X, new PoolEntry<uint32_t>({0}));
|
||||||
@ -456,9 +456,9 @@ ReturnValue_t IMTQHandler::initializeLocalDataPool(localpool::DataPool& localDat
|
|||||||
localDataPoolMap.emplace(IMTQ::NEG_X_COIL_X_CURRENT, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::NEG_X_COIL_X_CURRENT, new PoolEntry<uint16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::NEG_X_COIL_Y_CURRENT, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::NEG_X_COIL_Y_CURRENT, new PoolEntry<uint16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::NEG_X_COIL_Z_CURRENT, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::NEG_X_COIL_Z_CURRENT, new PoolEntry<uint16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::NEG_X_COIL_X_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::NEG_X_COIL_X_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::NEG_X_COIL_Y_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::NEG_X_COIL_Y_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::NEG_X_COIL_Z_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::NEG_X_COIL_Z_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
|
|
||||||
localDataPoolMap.emplace(IMTQ::POS_Y_ERR, new PoolEntry<uint8_t>({0}));
|
localDataPoolMap.emplace(IMTQ::POS_Y_ERR, new PoolEntry<uint8_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::POS_Y_RAW_MAG_X, new PoolEntry<uint32_t>({0}));
|
localDataPoolMap.emplace(IMTQ::POS_Y_RAW_MAG_X, new PoolEntry<uint32_t>({0}));
|
||||||
@ -470,9 +470,9 @@ ReturnValue_t IMTQHandler::initializeLocalDataPool(localpool::DataPool& localDat
|
|||||||
localDataPoolMap.emplace(IMTQ::POS_Y_COIL_X_CURRENT, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::POS_Y_COIL_X_CURRENT, new PoolEntry<uint16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::POS_Y_COIL_Y_CURRENT, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::POS_Y_COIL_Y_CURRENT, new PoolEntry<uint16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::POS_Y_COIL_Z_CURRENT, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::POS_Y_COIL_Z_CURRENT, new PoolEntry<uint16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::POS_Y_COIL_X_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::POS_Y_COIL_X_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::POS_Y_COIL_Y_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::POS_Y_COIL_Y_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::POS_Y_COIL_Z_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::POS_Y_COIL_Z_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
|
|
||||||
localDataPoolMap.emplace(IMTQ::NEG_Y_ERR, new PoolEntry<uint8_t>({0}));
|
localDataPoolMap.emplace(IMTQ::NEG_Y_ERR, new PoolEntry<uint8_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::NEG_Y_RAW_MAG_X, new PoolEntry<uint32_t>({0}));
|
localDataPoolMap.emplace(IMTQ::NEG_Y_RAW_MAG_X, new PoolEntry<uint32_t>({0}));
|
||||||
@ -484,9 +484,9 @@ ReturnValue_t IMTQHandler::initializeLocalDataPool(localpool::DataPool& localDat
|
|||||||
localDataPoolMap.emplace(IMTQ::NEG_Y_COIL_X_CURRENT, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::NEG_Y_COIL_X_CURRENT, new PoolEntry<uint16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::NEG_Y_COIL_Y_CURRENT, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::NEG_Y_COIL_Y_CURRENT, new PoolEntry<uint16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::NEG_Y_COIL_Z_CURRENT, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::NEG_Y_COIL_Z_CURRENT, new PoolEntry<uint16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::NEG_Y_COIL_X_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::NEG_Y_COIL_X_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::NEG_Y_COIL_Y_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::NEG_Y_COIL_Y_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::NEG_Y_COIL_Z_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::NEG_Y_COIL_Z_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
|
|
||||||
localDataPoolMap.emplace(IMTQ::POS_Z_ERR, new PoolEntry<uint8_t>({0}));
|
localDataPoolMap.emplace(IMTQ::POS_Z_ERR, new PoolEntry<uint8_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::POS_Z_RAW_MAG_X, new PoolEntry<uint32_t>({0}));
|
localDataPoolMap.emplace(IMTQ::POS_Z_RAW_MAG_X, new PoolEntry<uint32_t>({0}));
|
||||||
@ -498,9 +498,9 @@ ReturnValue_t IMTQHandler::initializeLocalDataPool(localpool::DataPool& localDat
|
|||||||
localDataPoolMap.emplace(IMTQ::POS_Z_COIL_X_CURRENT, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::POS_Z_COIL_X_CURRENT, new PoolEntry<uint16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::POS_Z_COIL_Y_CURRENT, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::POS_Z_COIL_Y_CURRENT, new PoolEntry<uint16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::POS_Z_COIL_Z_CURRENT, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::POS_Z_COIL_Z_CURRENT, new PoolEntry<uint16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::POS_Z_COIL_X_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::POS_Z_COIL_X_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::POS_Z_COIL_Y_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::POS_Z_COIL_Y_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::POS_Z_COIL_Z_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::POS_Z_COIL_Z_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
|
|
||||||
localDataPoolMap.emplace(IMTQ::NEG_Z_ERR, new PoolEntry<uint8_t>({0}));
|
localDataPoolMap.emplace(IMTQ::NEG_Z_ERR, new PoolEntry<uint8_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::NEG_Z_RAW_MAG_X, new PoolEntry<uint32_t>({0}));
|
localDataPoolMap.emplace(IMTQ::NEG_Z_RAW_MAG_X, new PoolEntry<uint32_t>({0}));
|
||||||
@ -512,9 +512,9 @@ ReturnValue_t IMTQHandler::initializeLocalDataPool(localpool::DataPool& localDat
|
|||||||
localDataPoolMap.emplace(IMTQ::NEG_Z_COIL_X_CURRENT, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::NEG_Z_COIL_X_CURRENT, new PoolEntry<uint16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::NEG_Z_COIL_Y_CURRENT, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::NEG_Z_COIL_Y_CURRENT, new PoolEntry<uint16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::NEG_Z_COIL_Z_CURRENT, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::NEG_Z_COIL_Z_CURRENT, new PoolEntry<uint16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::NEG_Z_COIL_X_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::NEG_Z_COIL_X_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::NEG_Z_COIL_Y_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::NEG_Z_COIL_Y_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::NEG_Z_COIL_Z_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::NEG_Z_COIL_Z_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
|
|
||||||
/** FINA measurements for positive X axis test */
|
/** FINA measurements for positive X axis test */
|
||||||
localDataPoolMap.emplace(IMTQ::FINA_POS_X_ERR, new PoolEntry<uint8_t>({0}));
|
localDataPoolMap.emplace(IMTQ::FINA_POS_X_ERR, new PoolEntry<uint8_t>({0}));
|
||||||
@ -527,9 +527,9 @@ ReturnValue_t IMTQHandler::initializeLocalDataPool(localpool::DataPool& localDat
|
|||||||
localDataPoolMap.emplace(IMTQ::FINA_POS_X_COIL_X_CURRENT, new PoolEntry<float>({0}));
|
localDataPoolMap.emplace(IMTQ::FINA_POS_X_COIL_X_CURRENT, new PoolEntry<float>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::FINA_POS_X_COIL_Y_CURRENT, new PoolEntry<float>({0}));
|
localDataPoolMap.emplace(IMTQ::FINA_POS_X_COIL_Y_CURRENT, new PoolEntry<float>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::FINA_POS_X_COIL_Z_CURRENT, new PoolEntry<float>({0}));
|
localDataPoolMap.emplace(IMTQ::FINA_POS_X_COIL_Z_CURRENT, new PoolEntry<float>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::FINA_POS_X_COIL_X_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::FINA_POS_X_COIL_X_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::FINA_POS_X_COIL_Y_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::FINA_POS_X_COIL_Y_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::FINA_POS_X_COIL_Z_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::FINA_POS_X_COIL_Z_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
|
|
||||||
/** FINA measurements for negative X axis test */
|
/** FINA measurements for negative X axis test */
|
||||||
localDataPoolMap.emplace(IMTQ::FINA_NEG_X_ERR, new PoolEntry<uint8_t>({0}));
|
localDataPoolMap.emplace(IMTQ::FINA_NEG_X_ERR, new PoolEntry<uint8_t>({0}));
|
||||||
@ -542,9 +542,9 @@ ReturnValue_t IMTQHandler::initializeLocalDataPool(localpool::DataPool& localDat
|
|||||||
localDataPoolMap.emplace(IMTQ::FINA_NEG_X_COIL_X_CURRENT, new PoolEntry<float>({0}));
|
localDataPoolMap.emplace(IMTQ::FINA_NEG_X_COIL_X_CURRENT, new PoolEntry<float>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::FINA_NEG_X_COIL_Y_CURRENT, new PoolEntry<float>({0}));
|
localDataPoolMap.emplace(IMTQ::FINA_NEG_X_COIL_Y_CURRENT, new PoolEntry<float>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::FINA_NEG_X_COIL_Z_CURRENT, new PoolEntry<float>({0}));
|
localDataPoolMap.emplace(IMTQ::FINA_NEG_X_COIL_Z_CURRENT, new PoolEntry<float>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::FINA_NEG_X_COIL_X_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::FINA_NEG_X_COIL_X_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::FINA_NEG_X_COIL_Y_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::FINA_NEG_X_COIL_Y_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::FINA_NEG_X_COIL_Z_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::FINA_NEG_X_COIL_Z_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
|
|
||||||
/** FINA measurements for positive Y axis test */
|
/** FINA measurements for positive Y axis test */
|
||||||
localDataPoolMap.emplace(IMTQ::FINA_POS_Y_ERR, new PoolEntry<uint8_t>({0}));
|
localDataPoolMap.emplace(IMTQ::FINA_POS_Y_ERR, new PoolEntry<uint8_t>({0}));
|
||||||
@ -557,9 +557,9 @@ ReturnValue_t IMTQHandler::initializeLocalDataPool(localpool::DataPool& localDat
|
|||||||
localDataPoolMap.emplace(IMTQ::FINA_POS_Y_COIL_X_CURRENT, new PoolEntry<float>({0}));
|
localDataPoolMap.emplace(IMTQ::FINA_POS_Y_COIL_X_CURRENT, new PoolEntry<float>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::FINA_POS_Y_COIL_Y_CURRENT, new PoolEntry<float>({0}));
|
localDataPoolMap.emplace(IMTQ::FINA_POS_Y_COIL_Y_CURRENT, new PoolEntry<float>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::FINA_POS_Y_COIL_Z_CURRENT, new PoolEntry<float>({0}));
|
localDataPoolMap.emplace(IMTQ::FINA_POS_Y_COIL_Z_CURRENT, new PoolEntry<float>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::FINA_POS_Y_COIL_X_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::FINA_POS_Y_COIL_X_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::FINA_POS_Y_COIL_Y_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::FINA_POS_Y_COIL_Y_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::FINA_POS_Y_COIL_Z_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::FINA_POS_Y_COIL_Z_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
|
|
||||||
/** FINA measurements for negative Y axis test */
|
/** FINA measurements for negative Y axis test */
|
||||||
localDataPoolMap.emplace(IMTQ::FINA_NEG_Y_ERR, new PoolEntry<uint8_t>({0}));
|
localDataPoolMap.emplace(IMTQ::FINA_NEG_Y_ERR, new PoolEntry<uint8_t>({0}));
|
||||||
@ -572,9 +572,9 @@ ReturnValue_t IMTQHandler::initializeLocalDataPool(localpool::DataPool& localDat
|
|||||||
localDataPoolMap.emplace(IMTQ::FINA_NEG_Y_COIL_X_CURRENT, new PoolEntry<float>({0}));
|
localDataPoolMap.emplace(IMTQ::FINA_NEG_Y_COIL_X_CURRENT, new PoolEntry<float>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::FINA_NEG_Y_COIL_Y_CURRENT, new PoolEntry<float>({0}));
|
localDataPoolMap.emplace(IMTQ::FINA_NEG_Y_COIL_Y_CURRENT, new PoolEntry<float>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::FINA_NEG_Y_COIL_Z_CURRENT, new PoolEntry<float>({0}));
|
localDataPoolMap.emplace(IMTQ::FINA_NEG_Y_COIL_Z_CURRENT, new PoolEntry<float>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::FINA_NEG_Y_COIL_X_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::FINA_NEG_Y_COIL_X_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::FINA_NEG_Y_COIL_Y_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::FINA_NEG_Y_COIL_Y_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::FINA_NEG_Y_COIL_Z_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::FINA_NEG_Y_COIL_Z_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
|
|
||||||
/** FINA measurements for positive Z axis test */
|
/** FINA measurements for positive Z axis test */
|
||||||
localDataPoolMap.emplace(IMTQ::FINA_POS_Z_ERR, new PoolEntry<uint8_t>({0}));
|
localDataPoolMap.emplace(IMTQ::FINA_POS_Z_ERR, new PoolEntry<uint8_t>({0}));
|
||||||
@ -587,9 +587,9 @@ ReturnValue_t IMTQHandler::initializeLocalDataPool(localpool::DataPool& localDat
|
|||||||
localDataPoolMap.emplace(IMTQ::FINA_POS_Z_COIL_X_CURRENT, new PoolEntry<float>({0}));
|
localDataPoolMap.emplace(IMTQ::FINA_POS_Z_COIL_X_CURRENT, new PoolEntry<float>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::FINA_POS_Z_COIL_Y_CURRENT, new PoolEntry<float>({0}));
|
localDataPoolMap.emplace(IMTQ::FINA_POS_Z_COIL_Y_CURRENT, new PoolEntry<float>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::FINA_POS_Z_COIL_Z_CURRENT, new PoolEntry<float>({0}));
|
localDataPoolMap.emplace(IMTQ::FINA_POS_Z_COIL_Z_CURRENT, new PoolEntry<float>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::FINA_POS_Z_COIL_X_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::FINA_POS_Z_COIL_X_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::FINA_POS_Z_COIL_Y_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::FINA_POS_Z_COIL_Y_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::FINA_POS_Z_COIL_Z_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::FINA_POS_Z_COIL_Z_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
|
|
||||||
/** FINA measurements for negative Z axis test */
|
/** FINA measurements for negative Z axis test */
|
||||||
localDataPoolMap.emplace(IMTQ::FINA_NEG_Z_ERR, new PoolEntry<uint8_t>({0}));
|
localDataPoolMap.emplace(IMTQ::FINA_NEG_Z_ERR, new PoolEntry<uint8_t>({0}));
|
||||||
@ -602,9 +602,9 @@ ReturnValue_t IMTQHandler::initializeLocalDataPool(localpool::DataPool& localDat
|
|||||||
localDataPoolMap.emplace(IMTQ::FINA_NEG_Z_COIL_X_CURRENT, new PoolEntry<float>({0}));
|
localDataPoolMap.emplace(IMTQ::FINA_NEG_Z_COIL_X_CURRENT, new PoolEntry<float>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::FINA_NEG_Z_COIL_Y_CURRENT, new PoolEntry<float>({0}));
|
localDataPoolMap.emplace(IMTQ::FINA_NEG_Z_COIL_Y_CURRENT, new PoolEntry<float>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::FINA_NEG_Z_COIL_Z_CURRENT, new PoolEntry<float>({0}));
|
localDataPoolMap.emplace(IMTQ::FINA_NEG_Z_COIL_Z_CURRENT, new PoolEntry<float>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::FINA_NEG_Z_COIL_X_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::FINA_NEG_Z_COIL_X_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::FINA_NEG_Z_COIL_Y_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::FINA_NEG_Z_COIL_Y_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
localDataPoolMap.emplace(IMTQ::FINA_NEG_Z_COIL_Z_TEMPERATURE, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(IMTQ::FINA_NEG_Z_COIL_Z_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
|
|
||||||
poolManager.subscribeForPeriodicPacket(engHkDataset.getSid(), false, 10.0, true);
|
poolManager.subscribeForPeriodicPacket(engHkDataset.getSid(), false, 10.0, true);
|
||||||
poolManager.subscribeForPeriodicPacket(calMtmMeasurementSet.getSid(), false, 10.0, true);
|
poolManager.subscribeForPeriodicPacket(calMtmMeasurementSet.getSid(), false, 10.0, true);
|
||||||
@ -690,6 +690,8 @@ void IMTQHandler::fillEngHkDataset(const uint8_t* packet) {
|
|||||||
offset += 2;
|
offset += 2;
|
||||||
engHkDataset.mcuTemperature = (*(packet + offset + 1) << 8 | *(packet + offset));
|
engHkDataset.mcuTemperature = (*(packet + offset + 1) << 8 | *(packet + offset));
|
||||||
|
|
||||||
|
engHkDataset.setValidity(true, true);
|
||||||
|
|
||||||
if (debugMode) {
|
if (debugMode) {
|
||||||
#if OBSW_VERBOSE_LEVEL >= 1
|
#if OBSW_VERBOSE_LEVEL >= 1
|
||||||
sif::info << "IMTQ digital voltage: " << engHkDataset.digitalVoltageMv << " mV" << std::endl;
|
sif::info << "IMTQ digital voltage: " << engHkDataset.digitalVoltageMv << " mV" << std::endl;
|
||||||
|
@ -1,5 +1,7 @@
|
|||||||
#include "Max31865EiveHandler.h"
|
#include "Max31865EiveHandler.h"
|
||||||
|
|
||||||
|
#include <fsfw/datapool/PoolReadGuard.h>
|
||||||
|
|
||||||
Max31865EiveHandler::Max31865EiveHandler(object_id_t objectId, object_id_t comIF,
|
Max31865EiveHandler::Max31865EiveHandler(object_id_t objectId, object_id_t comIF,
|
||||||
CookieIF* comCookie)
|
CookieIF* comCookie)
|
||||||
: DeviceHandlerBase(objectId, comIF, comCookie, nullptr),
|
: DeviceHandlerBase(objectId, comIF, comCookie, nullptr),
|
||||||
@ -154,6 +156,15 @@ ReturnValue_t Max31865EiveHandler::interpretDeviceReply(DeviceCommandId_t id,
|
|||||||
// calculate approximation
|
// calculate approximation
|
||||||
float approxTemp = exchangeStruct.adcCode / 32.0 - 256.0;
|
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 (debugMode) {
|
||||||
if (debugDivider.checkAndIncrement()) {
|
if (debugDivider.checkAndIncrement()) {
|
||||||
sif::info << "Max31865: " << std::setw(20) << std::left << locString << std::right
|
sif::info << "Max31865: " << std::setw(20) << std::left << locString << std::right
|
||||||
@ -170,6 +181,8 @@ ReturnValue_t Max31865EiveHandler::initializeLocalDataPool(localpool::DataPool&
|
|||||||
using namespace MAX31865;
|
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::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::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}));
|
localDataPoolMap.emplace(static_cast<lp_id_t>(PoolIds::FAULT_BYTE), new PoolEntry<uint8_t>({0}));
|
||||||
poolManager.subscribeForPeriodicPacket(sensorDataset.getSid(), false, 30.0, false);
|
poolManager.subscribeForPeriodicPacket(sensorDataset.getSid(), false, 30.0, false);
|
||||||
return RETURN_OK;
|
return RETURN_OK;
|
||||||
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue
Block a user