chonky #670
70
CHANGELOG.md
70
CHANGELOG.md
@ -16,9 +16,11 @@ will consitute of a breaking change warranting a new major release:
|
|||||||
|
|
||||||
# [unreleased]
|
# [unreleased]
|
||||||
|
|
||||||
# [v2.2.0] to be released
|
# [v4.0.0] to be released
|
||||||
|
|
||||||
# [v2.1.0] to be released
|
# [v3.0.0] to be released
|
||||||
|
|
||||||
|
- `eive-tmtc` version v4.0.0
|
||||||
|
|
||||||
## Changed
|
## Changed
|
||||||
|
|
||||||
@ -33,19 +35,83 @@ will consitute of a breaking change warranting a new major release:
|
|||||||
CMake from selecting wrong cross-compilers if multiple cross-compilers with the same name are used
|
CMake from selecting wrong cross-compilers if multiple cross-compilers with the same name are used
|
||||||
on the same system.
|
on the same system.
|
||||||
- Add ACS board for EM by default now.
|
- Add ACS board for EM by default now.
|
||||||
|
- Add support for MPSoC HK packet.
|
||||||
|
- Add support for MPSoC Flash Directory Content Report.
|
||||||
|
- Dynamically enable and disable HK packets for MPSoC on `ON` and `OFF` commands.
|
||||||
|
- Add support for MPSoC Flash Directory Content Report.
|
||||||
|
- Larger allowed path and file sizes for STR and PLOC MPSoC modules.
|
||||||
|
- More robust MPSoC flash read and write command data handling.
|
||||||
|
- Increase frequency of payload handlers from 0.8 seconds to 0.5 seconds.
|
||||||
|
- Disable missed deadlines per default. Not useful in orbit, and triggers all the time on the EM
|
||||||
|
build after a number of subsequent runs, without any apparent reason (deadlines are not actually
|
||||||
|
missed, thread usage displayed is nominal)
|
||||||
|
- TM store dumpes will not be cancelled anymore if the transmitter is off. The dump can be cancelled
|
||||||
|
with an OFF command, and the PTME is perfectly capable of dumping without the transmitter being
|
||||||
|
on.
|
||||||
|
- Transmitter state is not taken into account anymore for writing into the PTME. The PTME should
|
||||||
|
be perfectly capable of generating a valid CADU, even when the transmitter is not ON for any
|
||||||
|
reason.
|
||||||
|
- OFF mode is ignores in TM store for determining whether a store will be written. The modes will
|
||||||
|
only be used to cancel a transfer.
|
||||||
|
- Handling of multiple RWs in the ACS Controller is improved and can be changed by parameter
|
||||||
|
commands.
|
||||||
|
- The Directory Listing direct dumper now has a state machine to stagger the directory listing dump.
|
||||||
|
This is required because very large dumps will overload the queue capacities in the framework.
|
||||||
|
- The PUS Service 8 now has larger queue sizes to handle more action replies. The PUS Service 1
|
||||||
|
also has a larger queue size to handle a lot of step replies now.
|
||||||
|
- Moved PDU `vcc` and `vbat` variable from auxiliary dataset to core dataset.
|
||||||
|
- Tweak TCP/IP configuration: Only the TCP server will be included on the EM. For the FM, no
|
||||||
|
TCP/IP servers will be included by default.
|
||||||
|
|
||||||
## Added
|
## Added
|
||||||
|
|
||||||
- Add the remaining system modes.
|
- Add the remaining system modes.
|
||||||
|
- PLOC MPSoC flash read command working.
|
||||||
|
- BPX battery handler is added for EM by default.
|
||||||
|
- ACU dummy HK sets
|
||||||
|
- IMTQ HK sets
|
||||||
|
- IMTQ dummy now handles power switch
|
||||||
|
- Added some new ACS parameters
|
||||||
|
- Enabled decimation filter for the ADIS GYRs
|
||||||
|
- Enabled second low-pass filter for L3GD20H GYRs
|
||||||
|
|
||||||
## Fixed
|
## Fixed
|
||||||
|
|
||||||
|
- CFDP low level protocol bugfix. Requires `fsfw` update and `tmtc` update.
|
||||||
- Compile fix if SCEX is compiled for the EM.
|
- Compile fix if SCEX is compiled for the EM.
|
||||||
- Set up Rad Sensor chip select even for EM to avoid SPI bus issues.
|
- Set up Rad Sensor chip select even for EM to avoid SPI bus issues.
|
||||||
- Correct ADIS Gyroscope type configuration for the EM, where the 16507 type is used instead of the
|
- Correct ADIS Gyroscope type configuration for the EM, where the 16507 type is used instead of the
|
||||||
16505 type.
|
16505 type.
|
||||||
- Host build is working again. Added reduced live TM helper which schedules the PUS and CFDP
|
- Host build is working again. Added reduced live TM helper which schedules the PUS and CFDP
|
||||||
funnel.
|
funnel.
|
||||||
|
- PLOC Supervisor handler now has a power switcher assigned to make PLOC power switching work
|
||||||
|
without an additional PCDU power switch command.
|
||||||
|
- The PLOC Supervisor handler now waits for the replies to the `SET_TIME` command to verify working
|
||||||
|
communication.
|
||||||
|
- The PLOC MPSoC now waits 10 cycles before going to on. These wait cycles are necessary because
|
||||||
|
the MPSoC is not ready to process commands without this additional boot time.
|
||||||
|
- Fixed correction for `GPS Altitude` in case the sensor data is out of the expected bonds.
|
||||||
|
- PLOC MPSoC special communication is now scheduled, which allows flash read and flash write
|
||||||
|
commands to work.
|
||||||
|
- Fixed the MPSoC flash write command.
|
||||||
|
- Added missing ACS parameter.
|
||||||
|
- HK TM store: The HK store dump success event was triggered for cancelled HK dumps.
|
||||||
|
- When a PUS parsing error occured while parsing a TM store file, the dump completion procedure
|
||||||
|
was always executed.
|
||||||
|
- Some smaller logic fixes in the TM store base class
|
||||||
|
- Fixed usage of C `abs` instead of C++ `std::abs`, which results in MTQ commands not being
|
||||||
|
scaled correctly between 1Am² and 0.2Am².
|
||||||
|
- TCS Heater Handler: Always trigger mode event if a heater goes `OFF` or `ON`. This event might
|
||||||
|
soon replace the `HEATER_WENT_ON` and `HEATER_WENT_OFF` events.
|
||||||
|
- Prevent spam of TCS controller heater unavailability event if all heaters are in external control.
|
||||||
|
- TCS heater switch info set contained invalid values because of a faulty `memcpy` in the TCS
|
||||||
|
controller. There is not crash risk but the heater states were invalid.
|
||||||
|
- STR datasets were not set to invalid on shutdown.
|
||||||
|
- Fixed usage of quaternion valid flag, which does not actually represent the validity of the
|
||||||
|
quaternion.
|
||||||
|
- Various fixes for the pointing modes of the `ACS Controller`. All modes should work now as
|
||||||
|
intended.
|
||||||
|
- The variance for the ADIS GYRs now represents the used `-3` version and not the `-1` version
|
||||||
- CFDP funnel did not route packets to live channel VC0
|
- CFDP funnel did not route packets to live channel VC0
|
||||||
|
|
||||||
# [v2.0.5] 2023-05-11
|
# [v2.0.5] 2023-05-11
|
||||||
|
@ -9,9 +9,9 @@
|
|||||||
# ##############################################################################
|
# ##############################################################################
|
||||||
cmake_minimum_required(VERSION 3.13)
|
cmake_minimum_required(VERSION 3.13)
|
||||||
|
|
||||||
set(OBSW_VERSION_MAJOR 2)
|
set(OBSW_VERSION_MAJOR 3)
|
||||||
set(OBSW_VERSION_MINOR 0)
|
set(OBSW_VERSION_MINOR 0)
|
||||||
set(OBSW_VERSION_REVISION 5)
|
set(OBSW_VERSION_REVISION 0)
|
||||||
|
|
||||||
# set(CMAKE_VERBOSE TRUE)
|
# set(CMAKE_VERBOSE TRUE)
|
||||||
|
|
||||||
@ -79,12 +79,19 @@ else()
|
|||||||
set(INIT_VAL 1)
|
set(INIT_VAL 1)
|
||||||
set(OBSW_STAR_TRACKER_GROUND_CONFIG 0)
|
set(OBSW_STAR_TRACKER_GROUND_CONFIG 0)
|
||||||
endif()
|
endif()
|
||||||
|
|
||||||
|
set(OBSW_ADD_TMTC_TCP_SERVER
|
||||||
|
${OBSW_Q7S_EM}
|
||||||
|
CACHE STRING "Add TCP TMTC Server")
|
||||||
|
set(OBSW_ADD_TMTC_UDP_SERVER
|
||||||
|
0
|
||||||
|
CACHE STRING "Add UDP TMTC Server")
|
||||||
set(OBSW_ADD_MGT
|
set(OBSW_ADD_MGT
|
||||||
${INIT_VAL}
|
${INIT_VAL}
|
||||||
CACHE STRING "Add MGT module")
|
CACHE STRING "Add MGT module")
|
||||||
set(OBSW_ADD_BPX_BATTERY_HANDLER
|
set(OBSW_ADD_BPX_BATTERY_HANDLER
|
||||||
${INIT_VAL}
|
1
|
||||||
CACHE STRING "Add MGT module")
|
CACHE STRING "Add BPX battery module")
|
||||||
set(OBSW_ADD_STAR_TRACKER
|
set(OBSW_ADD_STAR_TRACKER
|
||||||
${INIT_VAL}
|
${INIT_VAL}
|
||||||
CACHE STRING "Add Startracker module")
|
CACHE STRING "Add Startracker module")
|
||||||
@ -98,7 +105,7 @@ set(OBSW_ADD_THERMAL_TEMP_INSERTER
|
|||||||
${OBSW_Q7S_EM}
|
${OBSW_Q7S_EM}
|
||||||
CACHE STRING "Add thermal sensor temperature inserter")
|
CACHE STRING "Add thermal sensor temperature inserter")
|
||||||
set(OBSW_ADD_ACS_BOARD
|
set(OBSW_ADD_ACS_BOARD
|
||||||
1
|
${INIT_VAL}
|
||||||
CACHE STRING "Add ACS board module")
|
CACHE STRING "Add ACS board module")
|
||||||
set(OBSW_ADD_GPS_CTRL
|
set(OBSW_ADD_GPS_CTRL
|
||||||
${INIT_VAL}
|
${INIT_VAL}
|
||||||
|
@ -39,7 +39,7 @@
|
|||||||
#include "devices/gpioIds.h"
|
#include "devices/gpioIds.h"
|
||||||
#include "fsfw_hal/linux/gpio/Gpio.h"
|
#include "fsfw_hal/linux/gpio/Gpio.h"
|
||||||
#include "linux/payload/PlocMpsocHandler.h"
|
#include "linux/payload/PlocMpsocHandler.h"
|
||||||
#include "linux/payload/PlocMpsocHelper.h"
|
#include "linux/payload/PlocMpsocSpecialComHelper.h"
|
||||||
#include "linux/payload/PlocSupervisorHandler.h"
|
#include "linux/payload/PlocSupervisorHandler.h"
|
||||||
#include "linux/payload/PlocSupvUartMan.h"
|
#include "linux/payload/PlocSupvUartMan.h"
|
||||||
#include "test/gpio/DummyGpioIF.h"
|
#include "test/gpio/DummyGpioIF.h"
|
||||||
@ -62,6 +62,10 @@ void ObjectFactory::produce(void* args) {
|
|||||||
StorageManagerIF* tmStore;
|
StorageManagerIF* tmStore;
|
||||||
StorageManagerIF* ipcStore;
|
StorageManagerIF* ipcStore;
|
||||||
PersistentTmStores persistentStores;
|
PersistentTmStores persistentStores;
|
||||||
|
bool enableHkSets = false;
|
||||||
|
#if OBSW_ENABLE_PERIODIC_HK == 1
|
||||||
|
enableHkSets = true;
|
||||||
|
#endif
|
||||||
auto sdcMan = new DummySdCardManager("/tmp");
|
auto sdcMan = new DummySdCardManager("/tmp");
|
||||||
ObjectFactory::produceGenericObjects(nullptr, &pusFunnel, &cfdpFunnel, *sdcMan, &ipcStore,
|
ObjectFactory::produceGenericObjects(nullptr, &pusFunnel, &cfdpFunnel, *sdcMan, &ipcStore,
|
||||||
&tmStore, persistentStores, 120);
|
&tmStore, persistentStores, 120);
|
||||||
@ -82,8 +86,8 @@ void ObjectFactory::produce(void* args) {
|
|||||||
auto mpsocCookie = new UartCookie(objects::PLOC_MPSOC_HANDLER, mpscoDev, uart::PLOC_MPSOC_BAUD,
|
auto mpsocCookie = new UartCookie(objects::PLOC_MPSOC_HANDLER, mpscoDev, uart::PLOC_MPSOC_BAUD,
|
||||||
mpsoc::MAX_REPLY_SIZE, UartModes::NON_CANONICAL);
|
mpsoc::MAX_REPLY_SIZE, UartModes::NON_CANONICAL);
|
||||||
mpsocCookie->setNoFixedSizeReply();
|
mpsocCookie->setNoFixedSizeReply();
|
||||||
auto plocMpsocHelper = new PlocMPSoCHelper(objects::PLOC_MPSOC_HELPER);
|
auto plocMpsocHelper = new PlocMpsocSpecialComHelper(objects::PLOC_MPSOC_HELPER);
|
||||||
new PlocMPSoCHandler(objects::PLOC_MPSOC_HANDLER, objects::UART_COM_IF, mpsocCookie,
|
new PlocMpsocHandler(objects::PLOC_MPSOC_HANDLER, objects::UART_COM_IF, mpsocCookie,
|
||||||
plocMpsocHelper, Gpio(gpioIds::ENABLE_MPSOC_UART, dummyGpioIF),
|
plocMpsocHelper, Gpio(gpioIds::ENABLE_MPSOC_UART, dummyGpioIF),
|
||||||
objects::PLOC_SUPERVISOR_HANDLER);
|
objects::PLOC_SUPERVISOR_HANDLER);
|
||||||
#endif /* OBSW_ADD_PLOC_MPSOC == 1 */
|
#endif /* OBSW_ADD_PLOC_MPSOC == 1 */
|
||||||
@ -101,7 +105,7 @@ void ObjectFactory::produce(void* args) {
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
dummy::DummyCfg cfg;
|
dummy::DummyCfg cfg;
|
||||||
dummy::createDummies(cfg, *dummySwitcher, dummyGpioIF);
|
dummy::createDummies(cfg, *dummySwitcher, dummyGpioIF, enableHkSets);
|
||||||
|
|
||||||
HeaterHandler* heaterHandler = nullptr;
|
HeaterHandler* heaterHandler = nullptr;
|
||||||
// new ThermalController(objects::THERMAL_CONTROLLER);
|
// new ThermalController(objects::THERMAL_CONTROLLER);
|
||||||
|
@ -1,7 +1,7 @@
|
|||||||
/**
|
/**
|
||||||
* @brief Auto-generated event translation file. Contains 291 translations.
|
* @brief Auto-generated event translation file. Contains 295 translations.
|
||||||
* @details
|
* @details
|
||||||
* Generated on: 2023-04-17 11:34:19
|
* Generated on: 2023-05-17 17:15:34
|
||||||
*/
|
*/
|
||||||
#include "translateEvents.h"
|
#include "translateEvents.h"
|
||||||
|
|
||||||
@ -197,6 +197,10 @@ const char *MPSOC_EXE_INVALID_APID_STRING = "MPSOC_EXE_INVALID_APID";
|
|||||||
const char *MPSOC_HELPER_SEQ_CNT_MISMATCH_STRING = "MPSOC_HELPER_SEQ_CNT_MISMATCH";
|
const char *MPSOC_HELPER_SEQ_CNT_MISMATCH_STRING = "MPSOC_HELPER_SEQ_CNT_MISMATCH";
|
||||||
const char *MPSOC_TM_SIZE_ERROR_STRING = "MPSOC_TM_SIZE_ERROR";
|
const char *MPSOC_TM_SIZE_ERROR_STRING = "MPSOC_TM_SIZE_ERROR";
|
||||||
const char *MPSOC_TM_CRC_MISSMATCH_STRING = "MPSOC_TM_CRC_MISSMATCH";
|
const char *MPSOC_TM_CRC_MISSMATCH_STRING = "MPSOC_TM_CRC_MISSMATCH";
|
||||||
|
const char *MPSOC_FLASH_READ_PACKET_ERROR_STRING = "MPSOC_FLASH_READ_PACKET_ERROR";
|
||||||
|
const char *MPSOC_FLASH_READ_FAILED_STRING = "MPSOC_FLASH_READ_FAILED";
|
||||||
|
const char *MPSOC_FLASH_READ_SUCCESSFUL_STRING = "MPSOC_FLASH_READ_SUCCESSFUL";
|
||||||
|
const char *MPSOC_READ_TIMEOUT_STRING = "MPSOC_READ_TIMEOUT";
|
||||||
const char *TRANSITION_BACK_TO_OFF_STRING = "TRANSITION_BACK_TO_OFF";
|
const char *TRANSITION_BACK_TO_OFF_STRING = "TRANSITION_BACK_TO_OFF";
|
||||||
const char *NEG_V_OUT_OF_BOUNDS_STRING = "NEG_V_OUT_OF_BOUNDS";
|
const char *NEG_V_OUT_OF_BOUNDS_STRING = "NEG_V_OUT_OF_BOUNDS";
|
||||||
const char *U_DRO_OUT_OF_BOUNDS_STRING = "U_DRO_OUT_OF_BOUNDS";
|
const char *U_DRO_OUT_OF_BOUNDS_STRING = "U_DRO_OUT_OF_BOUNDS";
|
||||||
@ -683,6 +687,14 @@ const char *translateEvents(Event event) {
|
|||||||
return MPSOC_TM_SIZE_ERROR_STRING;
|
return MPSOC_TM_SIZE_ERROR_STRING;
|
||||||
case (12613):
|
case (12613):
|
||||||
return MPSOC_TM_CRC_MISSMATCH_STRING;
|
return MPSOC_TM_CRC_MISSMATCH_STRING;
|
||||||
|
case (12614):
|
||||||
|
return MPSOC_FLASH_READ_PACKET_ERROR_STRING;
|
||||||
|
case (12615):
|
||||||
|
return MPSOC_FLASH_READ_FAILED_STRING;
|
||||||
|
case (12616):
|
||||||
|
return MPSOC_FLASH_READ_SUCCESSFUL_STRING;
|
||||||
|
case (12617):
|
||||||
|
return MPSOC_READ_TIMEOUT_STRING;
|
||||||
case (12700):
|
case (12700):
|
||||||
return TRANSITION_BACK_TO_OFF_STRING;
|
return TRANSITION_BACK_TO_OFF_STRING;
|
||||||
case (12701):
|
case (12701):
|
||||||
|
@ -2,7 +2,7 @@
|
|||||||
* @brief Auto-generated object translation file.
|
* @brief Auto-generated object translation file.
|
||||||
* @details
|
* @details
|
||||||
* Contains 171 translations.
|
* Contains 171 translations.
|
||||||
* Generated on: 2023-04-17 11:34:19
|
* Generated on: 2023-05-17 17:15:34
|
||||||
*/
|
*/
|
||||||
#include "translateObjects.h"
|
#include "translateObjects.h"
|
||||||
|
|
||||||
|
@ -67,12 +67,12 @@
|
|||||||
// because UDP packets are not allowed in the VPN
|
// because UDP packets are not allowed in the VPN
|
||||||
// This will cause the OBSW to initialize the TMTC bridge responsible for exchanging data with the
|
// This will cause the OBSW to initialize the TMTC bridge responsible for exchanging data with the
|
||||||
// CCSDS IP Cores.
|
// CCSDS IP Cores.
|
||||||
#define OBSW_ADD_TMTC_TCP_SERVER 1
|
#define OBSW_ADD_TMTC_TCP_SERVER @OBSW_ADD_TMTC_TCP_SERVER@
|
||||||
#define OBSW_ADD_TMTC_UDP_SERVER 1
|
#define OBSW_ADD_TMTC_UDP_SERVER @OBSW_ADD_TMTC_UDP_SERVER@
|
||||||
|
|
||||||
// Can be used to switch device to NORMAL mode immediately
|
// Can be used to switch device to NORMAL mode immediately
|
||||||
#define OBSW_SWITCH_TO_NORMAL_MODE_AFTER_STARTUP 0
|
#define OBSW_SWITCH_TO_NORMAL_MODE_AFTER_STARTUP 0
|
||||||
#define OBSW_PRINT_MISSED_DEADLINES 1
|
#define OBSW_PRINT_MISSED_DEADLINES 0
|
||||||
|
|
||||||
#define OBSW_MPSOC_JTAG_BOOT 0
|
#define OBSW_MPSOC_JTAG_BOOT 0
|
||||||
#define OBSW_STAR_TRACKER_GROUND_CONFIG @OBSW_STAR_TRACKER_GROUND_CONFIG@
|
#define OBSW_STAR_TRACKER_GROUND_CONFIG @OBSW_STAR_TRACKER_GROUND_CONFIG@
|
||||||
|
@ -112,6 +112,9 @@ void CoreController::performControlOperation() {
|
|||||||
sdStateMachine();
|
sdStateMachine();
|
||||||
performMountedSdCardOperations();
|
performMountedSdCardOperations();
|
||||||
readHkData();
|
readHkData();
|
||||||
|
if (dumpContext.active) {
|
||||||
|
dirListingDumpHandler();
|
||||||
|
}
|
||||||
|
|
||||||
if (shellCmdIsExecuting) {
|
if (shellCmdIsExecuting) {
|
||||||
bool replyReceived = false;
|
bool replyReceived = false;
|
||||||
@ -1038,7 +1041,6 @@ ReturnValue_t CoreController::actionListDirectoryDumpDirectly(ActionId_t actionI
|
|||||||
return returnvalue::FAILED;
|
return returnvalue::FAILED;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
std::array<uint8_t, 1024> dirListingBuf{};
|
|
||||||
dirListingBuf[8] = parser.compressionOptionSet();
|
dirListingBuf[8] = parser.compressionOptionSet();
|
||||||
// First four bytes reserved for segment index. One byte for compression option information
|
// First four bytes reserved for segment index. One byte for compression option information
|
||||||
std::strcpy(reinterpret_cast<char *>(dirListingBuf.data() + 2 * sizeof(uint32_t) + 1), repoName);
|
std::strcpy(reinterpret_cast<char *>(dirListingBuf.data() + 2 * sizeof(uint32_t) + 1), repoName);
|
||||||
@ -1047,38 +1049,47 @@ ReturnValue_t CoreController::actionListDirectoryDumpDirectly(ActionId_t actionI
|
|||||||
return returnvalue::FAILED;
|
return returnvalue::FAILED;
|
||||||
}
|
}
|
||||||
std::error_code e;
|
std::error_code e;
|
||||||
size_t totalFileSize = std::filesystem::file_size(LIST_DIR_DUMP_WORK_FILE, e);
|
dumpContext.totalFileSize = std::filesystem::file_size(LIST_DIR_DUMP_WORK_FILE, e);
|
||||||
uint32_t segmentIdx = 0;
|
dumpContext.segmentIdx = 0;
|
||||||
size_t dumpedBytes = 0;
|
dumpContext.dumpedBytes = 0;
|
||||||
size_t nextDumpLen = 0;
|
size_t nextDumpLen = 0;
|
||||||
size_t dummy = 0;
|
size_t dummy = 0;
|
||||||
size_t maxDumpLen = dirListingBuf.size() - 2 * sizeof(uint32_t) - 1 - repoNameLen - 1;
|
dumpContext.maxDumpLen = dirListingBuf.size() - 2 * sizeof(uint32_t) - 1 - repoNameLen - 1;
|
||||||
size_t listingDataOffset = 2 * sizeof(uint32_t) + 1 + repoNameLen + 1;
|
dumpContext.listingDataOffset = 2 * sizeof(uint32_t) + 1 + repoNameLen + 1;
|
||||||
uint32_t chunks = totalFileSize / maxDumpLen;
|
uint32_t chunks = dumpContext.totalFileSize / dumpContext.maxDumpLen;
|
||||||
if (totalFileSize % maxDumpLen != 0) {
|
if (dumpContext.totalFileSize % dumpContext.maxDumpLen != 0) {
|
||||||
chunks++;
|
chunks++;
|
||||||
}
|
}
|
||||||
SerializeAdapter::serialize(&chunks, dirListingBuf.data() + sizeof(uint32_t), &dummy,
|
SerializeAdapter::serialize(&chunks, dirListingBuf.data() + sizeof(uint32_t), &dummy,
|
||||||
dirListingBuf.size() - sizeof(uint32_t),
|
dirListingBuf.size() - sizeof(uint32_t),
|
||||||
SerializeIF::Endianness::NETWORK);
|
SerializeIF::Endianness::NETWORK);
|
||||||
while (dumpedBytes < totalFileSize) {
|
while (dumpContext.dumpedBytes < dumpContext.totalFileSize) {
|
||||||
ifile.seekg(dumpedBytes, std::ios::beg);
|
ifile.seekg(dumpContext.dumpedBytes, std::ios::beg);
|
||||||
nextDumpLen = maxDumpLen;
|
nextDumpLen = dumpContext.maxDumpLen;
|
||||||
if (totalFileSize - dumpedBytes < maxDumpLen) {
|
if (dumpContext.totalFileSize - dumpContext.dumpedBytes < dumpContext.maxDumpLen) {
|
||||||
nextDumpLen = totalFileSize - dumpedBytes;
|
nextDumpLen = dumpContext.totalFileSize - dumpContext.dumpedBytes;
|
||||||
}
|
}
|
||||||
SerializeAdapter::serialize(&segmentIdx, dirListingBuf.data(), &dummy, dirListingBuf.size(),
|
SerializeAdapter::serialize(&dumpContext.segmentIdx, dirListingBuf.data(), &dummy,
|
||||||
SerializeIF::Endianness::NETWORK);
|
dirListingBuf.size(), SerializeIF::Endianness::NETWORK);
|
||||||
ifile.read(reinterpret_cast<char *>(dirListingBuf.data() + listingDataOffset), nextDumpLen);
|
ifile.read(reinterpret_cast<char *>(dirListingBuf.data() + dumpContext.listingDataOffset),
|
||||||
|
nextDumpLen);
|
||||||
result = actionHelper.reportData(commandedBy, actionId, dirListingBuf.data(),
|
result = actionHelper.reportData(commandedBy, actionId, dirListingBuf.data(),
|
||||||
listingDataOffset + nextDumpLen);
|
dumpContext.listingDataOffset + nextDumpLen);
|
||||||
if (result != returnvalue::OK) {
|
if (result != returnvalue::OK) {
|
||||||
// Remove work file when we are done
|
// Remove work file when we are done
|
||||||
std::filesystem::remove(LIST_DIR_DUMP_WORK_FILE, e);
|
std::filesystem::remove(LIST_DIR_DUMP_WORK_FILE, e);
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
segmentIdx++;
|
dumpContext.segmentIdx++;
|
||||||
dumpedBytes += nextDumpLen;
|
dumpContext.dumpedBytes += nextDumpLen;
|
||||||
|
// Dump takes multiple task cycles, so cache the dump state and continue dump the next cycles.
|
||||||
|
if (dumpContext.segmentIdx == 10) {
|
||||||
|
dumpContext.active = true;
|
||||||
|
dumpContext.firstDump = true;
|
||||||
|
dumpContext.commander = commandedBy;
|
||||||
|
dumpContext.actionId = actionId;
|
||||||
|
return returnvalue::OK;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
// Remove work file when we are done
|
// Remove work file when we are done
|
||||||
std::filesystem::remove(LIST_DIR_DUMP_WORK_FILE, e);
|
std::filesystem::remove(LIST_DIR_DUMP_WORK_FILE, e);
|
||||||
@ -2346,6 +2357,54 @@ MessageQueueId_t CoreController::getCommandQueue() const {
|
|||||||
return ExtendedControllerBase::getCommandQueue();
|
return ExtendedControllerBase::getCommandQueue();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void CoreController::dirListingDumpHandler() {
|
||||||
|
if (dumpContext.firstDump) {
|
||||||
|
dumpContext.firstDump = false;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
size_t nextDumpLen = 0;
|
||||||
|
size_t dummy = 0;
|
||||||
|
ReturnValue_t result;
|
||||||
|
std::error_code e;
|
||||||
|
std::ifstream ifile(LIST_DIR_DUMP_WORK_FILE, std::ios::binary);
|
||||||
|
if (ifile.bad()) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
while (dumpContext.dumpedBytes < dumpContext.totalFileSize) {
|
||||||
|
ifile.seekg(dumpContext.dumpedBytes, std::ios::beg);
|
||||||
|
nextDumpLen = dumpContext.maxDumpLen;
|
||||||
|
if (dumpContext.totalFileSize - dumpContext.dumpedBytes < dumpContext.maxDumpLen) {
|
||||||
|
nextDumpLen = dumpContext.totalFileSize - dumpContext.dumpedBytes;
|
||||||
|
}
|
||||||
|
SerializeAdapter::serialize(&dumpContext.segmentIdx, dirListingBuf.data(), &dummy,
|
||||||
|
dirListingBuf.size(), SerializeIF::Endianness::NETWORK);
|
||||||
|
ifile.read(reinterpret_cast<char *>(dirListingBuf.data() + dumpContext.listingDataOffset),
|
||||||
|
nextDumpLen);
|
||||||
|
result =
|
||||||
|
actionHelper.reportData(dumpContext.commander, dumpContext.actionId, dirListingBuf.data(),
|
||||||
|
dumpContext.listingDataOffset + nextDumpLen);
|
||||||
|
if (result != returnvalue::OK) {
|
||||||
|
// Remove work file when we are done
|
||||||
|
std::filesystem::remove(LIST_DIR_DUMP_WORK_FILE, e);
|
||||||
|
dumpContext.active = false;
|
||||||
|
actionHelper.finish(false, dumpContext.commander, dumpContext.actionId, result);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
dumpContext.segmentIdx++;
|
||||||
|
dumpContext.dumpedBytes += nextDumpLen;
|
||||||
|
// Dump takes multiple task cycles, so cache the dump state and continue dump the next cycles.
|
||||||
|
if (dumpContext.segmentIdx == 10) {
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if (dumpContext.dumpedBytes >= dumpContext.totalFileSize) {
|
||||||
|
actionHelper.finish(true, dumpContext.commander, dumpContext.actionId, result);
|
||||||
|
dumpContext.active = false;
|
||||||
|
// Remove work file when we are done
|
||||||
|
std::filesystem::remove(LIST_DIR_DUMP_WORK_FILE, e);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
bool CoreController::isNumber(const std::string &s) {
|
bool CoreController::isNumber(const std::string &s) {
|
||||||
return !s.empty() && std::find_if(s.begin(), s.end(),
|
return !s.empty() && std::find_if(s.begin(), s.end(),
|
||||||
[](unsigned char c) { return !std::isdigit(c); }) == s.end();
|
[](unsigned char c) { return !std::isdigit(c); }) == s.end();
|
||||||
|
@ -177,6 +177,20 @@ class CoreController : public ExtendedControllerBase, public ReceivesParameterMe
|
|||||||
DeviceCommandId_t actionId;
|
DeviceCommandId_t actionId;
|
||||||
} sdCommandingInfo;
|
} sdCommandingInfo;
|
||||||
|
|
||||||
|
struct DirListingDumpContext {
|
||||||
|
bool active;
|
||||||
|
bool firstDump;
|
||||||
|
size_t dumpedBytes;
|
||||||
|
size_t totalFileSize;
|
||||||
|
size_t listingDataOffset;
|
||||||
|
size_t maxDumpLen;
|
||||||
|
uint32_t segmentIdx;
|
||||||
|
MessageQueueId_t commander = MessageQueueIF::NO_QUEUE;
|
||||||
|
DeviceCommandId_t actionId;
|
||||||
|
};
|
||||||
|
std::array<uint8_t, 1024> dirListingBuf{};
|
||||||
|
DirListingDumpContext dumpContext{};
|
||||||
|
|
||||||
RebootFile rebootFile = {};
|
RebootFile rebootFile = {};
|
||||||
|
|
||||||
CommandExecutor cmdExecutor;
|
CommandExecutor cmdExecutor;
|
||||||
@ -274,6 +288,7 @@ class CoreController : public ExtendedControllerBase, public ReceivesParameterMe
|
|||||||
void rewriteRebootFile(RebootFile file);
|
void rewriteRebootFile(RebootFile file);
|
||||||
void announceBootCounts();
|
void announceBootCounts();
|
||||||
void readHkData();
|
void readHkData();
|
||||||
|
void dirListingDumpHandler();
|
||||||
bool isNumber(const std::string& s);
|
bool isNumber(const std::string& s);
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -10,10 +10,10 @@
|
|||||||
#include <linux/com/SyrlinksComHandler.h>
|
#include <linux/com/SyrlinksComHandler.h>
|
||||||
#include <linux/payload/PlocMemoryDumper.h>
|
#include <linux/payload/PlocMemoryDumper.h>
|
||||||
#include <linux/payload/PlocMpsocHandler.h>
|
#include <linux/payload/PlocMpsocHandler.h>
|
||||||
#include <linux/payload/PlocMpsocHelper.h>
|
#include <linux/payload/PlocMpsocSpecialComHelper.h>
|
||||||
#include <linux/payload/PlocSupervisorHandler.h>
|
#include <linux/payload/PlocSupervisorHandler.h>
|
||||||
#include <linux/payload/ScexUartReader.h>
|
#include <linux/payload/ScexUartReader.h>
|
||||||
#include <linux/payload/plocMpscoDefs.h>
|
#include <linux/payload/plocMpsocHelpers.h>
|
||||||
#include <linux/power/CspComIF.h>
|
#include <linux/power/CspComIF.h>
|
||||||
#include <mission/acs/GyrL3gCustomHandler.h>
|
#include <mission/acs/GyrL3gCustomHandler.h>
|
||||||
#include <mission/acs/MgmLis3CustomHandler.h>
|
#include <mission/acs/MgmLis3CustomHandler.h>
|
||||||
@ -623,8 +623,8 @@ void ObjectFactory::createPayloadComponents(LinuxLibgpioIF* gpioComIF, PowerSwit
|
|||||||
new SerialCookie(objects::PLOC_MPSOC_HANDLER, q7s::UART_PLOC_MPSOC_DEV,
|
new SerialCookie(objects::PLOC_MPSOC_HANDLER, q7s::UART_PLOC_MPSOC_DEV,
|
||||||
serial::PLOC_MPSOC_BAUD, mpsoc::MAX_REPLY_SIZE, UartModes::NON_CANONICAL);
|
serial::PLOC_MPSOC_BAUD, mpsoc::MAX_REPLY_SIZE, UartModes::NON_CANONICAL);
|
||||||
mpsocCookie->setNoFixedSizeReply();
|
mpsocCookie->setNoFixedSizeReply();
|
||||||
auto plocMpsocHelper = new PlocMPSoCHelper(objects::PLOC_MPSOC_HELPER);
|
auto plocMpsocHelper = new PlocMpsocSpecialComHelper(objects::PLOC_MPSOC_HELPER);
|
||||||
auto* mpsocHandler = new PlocMPSoCHandler(
|
auto* mpsocHandler = new PlocMpsocHandler(
|
||||||
objects::PLOC_MPSOC_HANDLER, objects::UART_COM_IF, mpsocCookie, plocMpsocHelper,
|
objects::PLOC_MPSOC_HANDLER, objects::UART_COM_IF, mpsocCookie, plocMpsocHelper,
|
||||||
Gpio(gpioIds::ENABLE_MPSOC_UART, gpioComIF), objects::PLOC_SUPERVISOR_HANDLER);
|
Gpio(gpioIds::ENABLE_MPSOC_UART, gpioComIF), objects::PLOC_SUPERVISOR_HANDLER);
|
||||||
mpsocHandler->connectModeTreeParent(satsystem::payload::SUBSYSTEM);
|
mpsocHandler->connectModeTreeParent(satsystem::payload::SUBSYSTEM);
|
||||||
@ -644,6 +644,7 @@ void ObjectFactory::createPayloadComponents(LinuxLibgpioIF* gpioComIF, PowerSwit
|
|||||||
auto* supvHandler = new PlocSupervisorHandler(objects::PLOC_SUPERVISOR_HANDLER, supervisorCookie,
|
auto* supvHandler = new PlocSupervisorHandler(objects::PLOC_SUPERVISOR_HANDLER, supervisorCookie,
|
||||||
Gpio(gpioIds::ENABLE_SUPV_UART, gpioComIF),
|
Gpio(gpioIds::ENABLE_SUPV_UART, gpioComIF),
|
||||||
power::PDU1_CH6_PLOC_12V, *supvHelper);
|
power::PDU1_CH6_PLOC_12V, *supvHelper);
|
||||||
|
supvHandler->setPowerSwitcher(&pwrSwitch);
|
||||||
supvHandler->connectModeTreeParent(satsystem::payload::SUBSYSTEM);
|
supvHandler->connectModeTreeParent(satsystem::payload::SUBSYSTEM);
|
||||||
#endif /* OBSW_ADD_PLOC_SUPERVISOR == 1 */
|
#endif /* OBSW_ADD_PLOC_SUPERVISOR == 1 */
|
||||||
static_cast<void>(consumer);
|
static_cast<void>(consumer);
|
||||||
@ -804,7 +805,7 @@ ReturnValue_t ObjectFactory::createCcsdsComponents(CcsdsComponentArgs& args) {
|
|||||||
// Core task which handles the HK store and takes care of dumping it as TM using a VC directly
|
// Core task which handles the HK store and takes care of dumping it as TM using a VC directly
|
||||||
auto* hkStore = new PersistentSingleTmStoreTask(
|
auto* hkStore = new PersistentSingleTmStoreTask(
|
||||||
objects::HK_STORE_AND_TM_TASK, args.ipcStore, *args.stores.hkStore, *vc,
|
objects::HK_STORE_AND_TM_TASK, args.ipcStore, *args.stores.hkStore, *vc,
|
||||||
persTmStore::DUMP_HK_STORE_DONE, persTmStore::DUMP_HK_STORE_DONE, *SdCardManager::instance(),
|
persTmStore::DUMP_HK_STORE_DONE, persTmStore::DUMP_HK_CANCELLED, *SdCardManager::instance(),
|
||||||
PTME_LOCKED);
|
PTME_LOCKED);
|
||||||
hkStore->connectModeTreeParent(satsystem::com::SUBSYSTEM);
|
hkStore->connectModeTreeParent(satsystem::com::SUBSYSTEM);
|
||||||
|
|
||||||
|
@ -345,7 +345,6 @@ void scheduling::initTasks() {
|
|||||||
}
|
}
|
||||||
#endif /* OBSW_ADD_STAR_TRACKER == 1 */
|
#endif /* OBSW_ADD_STAR_TRACKER == 1 */
|
||||||
|
|
||||||
// TODO: Use regular scheduler for this task
|
|
||||||
#if OBSW_ADD_PLOC_MPSOC == 1
|
#if OBSW_ADD_PLOC_MPSOC == 1
|
||||||
PeriodicTaskIF* mpsocHelperTask = factory->createPeriodicTask(
|
PeriodicTaskIF* mpsocHelperTask = factory->createPeriodicTask(
|
||||||
"PLOC_MPSOC_HELPER", 0, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc);
|
"PLOC_MPSOC_HELPER", 0, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc);
|
||||||
@ -366,7 +365,7 @@ void scheduling::initTasks() {
|
|||||||
#endif /* OBSW_ADD_PLOC_SUPERVISOR */
|
#endif /* OBSW_ADD_PLOC_SUPERVISOR */
|
||||||
|
|
||||||
PeriodicTaskIF* plTask = factory->createPeriodicTask(
|
PeriodicTaskIF* plTask = factory->createPeriodicTask(
|
||||||
"PL_TASK", 25, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.8, missedDeadlineFunc, &RR_SCHEDULING);
|
"PL_TASK", 25, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.5, missedDeadlineFunc, &RR_SCHEDULING);
|
||||||
plTask->addComponent(objects::CAM_SWITCHER);
|
plTask->addComponent(objects::CAM_SWITCHER);
|
||||||
scheduling::addMpsocSupvHandlers(plTask);
|
scheduling::addMpsocSupvHandlers(plTask);
|
||||||
scheduling::scheduleScexDev(plTask);
|
scheduling::scheduleScexDev(plTask);
|
||||||
@ -472,6 +471,9 @@ void scheduling::initTasks() {
|
|||||||
#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 */
|
||||||
|
#if OBSW_ADD_PLOC_MPSOC == 1
|
||||||
|
mpsocHelperTask->startTask();
|
||||||
|
#endif
|
||||||
plTask->startTask();
|
plTask->startTask();
|
||||||
|
|
||||||
#if OBSW_ADD_TEST_CODE == 1
|
#if OBSW_ADD_TEST_CODE == 1
|
||||||
|
@ -52,12 +52,12 @@ void ObjectFactory::produce(void* args) {
|
|||||||
// level components.
|
// level components.
|
||||||
dummy::DummyCfg dummyCfg;
|
dummy::DummyCfg dummyCfg;
|
||||||
dummyCfg.addCoreCtrlCfg = false;
|
dummyCfg.addCoreCtrlCfg = false;
|
||||||
|
dummyCfg.addCamSwitcherDummy = false;
|
||||||
#if OBSW_ADD_SYRLINKS == 1
|
#if OBSW_ADD_SYRLINKS == 1
|
||||||
dummyCfg.addSyrlinksDummies = false;
|
dummyCfg.addSyrlinksDummies = false;
|
||||||
#endif
|
#endif
|
||||||
#if OBSW_ADD_PLOC_SUPERVISOR == 1 || OBSW_ADD_PLOC_MPSOC == 1
|
#if OBSW_ADD_PLOC_SUPERVISOR == 1 || OBSW_ADD_PLOC_MPSOC == 1
|
||||||
dummyCfg.addPlocDummies = false;
|
dummyCfg.addPlocDummies = false;
|
||||||
dummyCfg.addCamSwitcherDummy = false;
|
|
||||||
#endif
|
#endif
|
||||||
#if OBSW_ADD_GOMSPACE_PCDU == 1
|
#if OBSW_ADD_GOMSPACE_PCDU == 1
|
||||||
dummyCfg.addPowerDummies = false;
|
dummyCfg.addPowerDummies = false;
|
||||||
@ -79,7 +79,7 @@ void ObjectFactory::produce(void* args) {
|
|||||||
#endif
|
#endif
|
||||||
satsystem::EIVE_SYSTEM.setI2cRecoveryParams(pwrSwitcher);
|
satsystem::EIVE_SYSTEM.setI2cRecoveryParams(pwrSwitcher);
|
||||||
|
|
||||||
dummy::createDummies(dummyCfg, *pwrSwitcher, gpioComIF);
|
dummy::createDummies(dummyCfg, *pwrSwitcher, gpioComIF, enableHkSets);
|
||||||
|
|
||||||
new CoreController(objects::CORE_CONTROLLER, enableHkSets);
|
new CoreController(objects::CORE_CONTROLLER, enableHkSets);
|
||||||
|
|
||||||
@ -97,10 +97,10 @@ void ObjectFactory::produce(void* args) {
|
|||||||
// TODO: Careful! Switching this on somehow messes with the communication with the ProASIC
|
// TODO: Careful! Switching this on somehow messes with the communication with the ProASIC
|
||||||
// and will cause xsc_boot_copy commands to always boot to 0 0
|
// and will cause xsc_boot_copy commands to always boot to 0 0
|
||||||
// createRadSensorComponent(gpioComIF);
|
// createRadSensorComponent(gpioComIF);
|
||||||
// Still initialize chip select to avoid SPI bus issues.
|
|
||||||
createRadSensorChipSelect(gpioComIF);
|
|
||||||
|
|
||||||
#if OBSW_ADD_ACS_BOARD == 1
|
#if OBSW_ADD_ACS_BOARD == 1
|
||||||
|
// Still initialize chip select to avoid SPI bus issues.
|
||||||
|
createRadSensorChipSelect(gpioComIF);
|
||||||
createAcsBoardComponents(*spiMainComIF, gpioComIF, uartComIF, *pwrSwitcher, true,
|
createAcsBoardComponents(*spiMainComIF, gpioComIF, uartComIF, *pwrSwitcher, true,
|
||||||
adis1650x::Type::ADIS16507);
|
adis1650x::Type::ADIS16507);
|
||||||
#else
|
#else
|
||||||
|
@ -34,8 +34,8 @@ static constexpr uint32_t STR_IMG_HELPER_QUEUE_SIZE = 50;
|
|||||||
static constexpr uint8_t LIVE_TM = 0;
|
static constexpr uint8_t LIVE_TM = 0;
|
||||||
|
|
||||||
/* Limits for filename and path checks */
|
/* Limits for filename and path checks */
|
||||||
static constexpr uint32_t MAX_PATH_SIZE = 100;
|
static constexpr uint32_t MAX_PATH_SIZE = 200;
|
||||||
static constexpr uint32_t MAX_FILENAME_SIZE = 50;
|
static constexpr uint32_t MAX_FILENAME_SIZE = 100;
|
||||||
|
|
||||||
static constexpr uint32_t SA_DEPL_INIT_BUFFER_SECS = 120;
|
static constexpr uint32_t SA_DEPL_INIT_BUFFER_SECS = 120;
|
||||||
// Burn time for autonomous deployment
|
// Burn time for autonomous deployment
|
||||||
@ -58,7 +58,9 @@ static constexpr uint32_t CFDP_STORE_QUEUE_SIZE = 300;
|
|||||||
|
|
||||||
static constexpr uint32_t MAX_PUS_FUNNEL_QUEUE_DEPTH = 100;
|
static constexpr uint32_t MAX_PUS_FUNNEL_QUEUE_DEPTH = 100;
|
||||||
static constexpr uint32_t MAX_CFDP_FUNNEL_QUEUE_DEPTH = 80;
|
static constexpr uint32_t MAX_CFDP_FUNNEL_QUEUE_DEPTH = 80;
|
||||||
|
static constexpr uint32_t VERIFICATION_SERVICE_QUEUE_DEPTH = 120;
|
||||||
static constexpr uint32_t HK_SERVICE_QUEUE_DEPTH = 60;
|
static constexpr uint32_t HK_SERVICE_QUEUE_DEPTH = 60;
|
||||||
|
static constexpr uint32_t ACTION_SERVICE_QUEUE_DEPTH = 60;
|
||||||
|
|
||||||
static constexpr uint32_t MAX_STORED_CMDS_UDP = 150;
|
static constexpr uint32_t MAX_STORED_CMDS_UDP = 150;
|
||||||
static constexpr uint32_t MAX_STORED_CMDS_TCP = 180;
|
static constexpr uint32_t MAX_STORED_CMDS_TCP = 180;
|
||||||
|
@ -2,8 +2,11 @@
|
|||||||
|
|
||||||
#include <mission/power/gsDefs.h>
|
#include <mission/power/gsDefs.h>
|
||||||
|
|
||||||
AcuDummy::AcuDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie)
|
AcuDummy::AcuDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie, bool enableHkSets)
|
||||||
: DeviceHandlerBase(objectId, comif, comCookie) {}
|
: DeviceHandlerBase(objectId, comif, comCookie),
|
||||||
|
coreHk(this),
|
||||||
|
auxHk(this),
|
||||||
|
enableHkSets(enableHkSets) {}
|
||||||
|
|
||||||
AcuDummy::~AcuDummy() {}
|
AcuDummy::~AcuDummy() {}
|
||||||
|
|
||||||
@ -37,7 +40,49 @@ uint32_t AcuDummy::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { return
|
|||||||
|
|
||||||
ReturnValue_t AcuDummy::initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
|
ReturnValue_t AcuDummy::initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
|
||||||
LocalDataPoolManager &poolManager) {
|
LocalDataPoolManager &poolManager) {
|
||||||
|
using namespace ACU;
|
||||||
|
localDataPoolMap.emplace(pool::ACU_CURRENT_IN_CHANNELS, new PoolEntry<int16_t>(6));
|
||||||
|
localDataPoolMap.emplace(pool::ACU_VOLTAGE_IN_CHANNELS, new PoolEntry<uint16_t>(6));
|
||||||
|
|
||||||
|
localDataPoolMap.emplace(pool::ACU_VCC, new PoolEntry<uint16_t>({0}));
|
||||||
|
localDataPoolMap.emplace(pool::ACU_VBAT, new PoolEntry<uint16_t>({0}));
|
||||||
|
|
||||||
localDataPoolMap.emplace(ACU::pool::ACU_TEMPERATURES,
|
localDataPoolMap.emplace(ACU::pool::ACU_TEMPERATURES,
|
||||||
new PoolEntry<float>({10.0, 10.0, 10.0}, true));
|
new PoolEntry<float>({10.0, 10.0, 10.0}, true));
|
||||||
|
|
||||||
|
localDataPoolMap.emplace(pool::ACU_MPPT_MODE, new PoolEntry<uint8_t>({0}));
|
||||||
|
|
||||||
|
localDataPoolMap.emplace(pool::ACU_VBOOST_IN_CHANNELS, new PoolEntry<uint16_t>(6));
|
||||||
|
localDataPoolMap.emplace(pool::ACU_POWER_IN_CHANNELS, new PoolEntry<uint16_t>(6));
|
||||||
|
|
||||||
|
localDataPoolMap.emplace(pool::ACU_DAC_ENABLES, new PoolEntry<uint8_t>(3));
|
||||||
|
localDataPoolMap.emplace(pool::ACU_DAC_RAW_CHANNELS, new PoolEntry<uint16_t>(6));
|
||||||
|
|
||||||
|
localDataPoolMap.emplace(pool::ACU_BOOTCAUSE, new PoolEntry<uint32_t>({0}));
|
||||||
|
localDataPoolMap.emplace(pool::ACU_BOOTCNT, new PoolEntry<uint32_t>({0}));
|
||||||
|
localDataPoolMap.emplace(pool::ACU_UPTIME, new PoolEntry<uint32_t>({0}));
|
||||||
|
localDataPoolMap.emplace(pool::ACU_RESET_CAUSE, new PoolEntry<uint16_t>({0}));
|
||||||
|
localDataPoolMap.emplace(pool::ACU_MPPT_TIME, new PoolEntry<uint16_t>({0}));
|
||||||
|
localDataPoolMap.emplace(pool::ACU_MPPT_PERIOD, new PoolEntry<uint16_t>({0}));
|
||||||
|
|
||||||
|
localDataPoolMap.emplace(pool::ACU_DEVICES, new PoolEntry<uint8_t>(8));
|
||||||
|
localDataPoolMap.emplace(pool::ACU_DEVICES_STATUS, new PoolEntry<uint8_t>(8));
|
||||||
|
|
||||||
|
localDataPoolMap.emplace(pool::ACU_WDT_CNT_GND, new PoolEntry<uint32_t>({0}));
|
||||||
|
localDataPoolMap.emplace(pool::ACU_WDT_GND_LEFT, new PoolEntry<uint32_t>({0}));
|
||||||
|
|
||||||
|
poolManager.subscribeForDiagPeriodicPacket(
|
||||||
|
subdp::DiagnosticsHkPeriodicParams(coreHk.getSid(), enableHkSets, 30.0));
|
||||||
|
poolManager.subscribeForRegularPeriodicPacket(
|
||||||
|
subdp::RegularHkPeriodicParams(auxHk.getSid(), enableHkSets, 6000.0));
|
||||||
return returnvalue::OK;
|
return returnvalue::OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
LocalPoolDataSetBase *AcuDummy::getDataSetHandle(sid_t sid) {
|
||||||
|
if (sid == coreHk.getSid()) {
|
||||||
|
return &coreHk;
|
||||||
|
} else if (sid == auxHk.getSid()) {
|
||||||
|
return &auxHk;
|
||||||
|
}
|
||||||
|
return nullptr;
|
||||||
|
}
|
||||||
|
@ -2,6 +2,7 @@
|
|||||||
#define DUMMIES_ACUDUMMY_H_
|
#define DUMMIES_ACUDUMMY_H_
|
||||||
|
|
||||||
#include <fsfw/devicehandlers/DeviceHandlerBase.h>
|
#include <fsfw/devicehandlers/DeviceHandlerBase.h>
|
||||||
|
#include <mission/power/gsDefs.h>
|
||||||
|
|
||||||
class AcuDummy : public DeviceHandlerBase {
|
class AcuDummy : public DeviceHandlerBase {
|
||||||
public:
|
public:
|
||||||
@ -11,10 +12,14 @@ class AcuDummy : public DeviceHandlerBase {
|
|||||||
static const uint8_t SIMPLE_COMMAND_DATA = 1;
|
static const uint8_t SIMPLE_COMMAND_DATA = 1;
|
||||||
static const uint8_t PERIODIC_REPLY_DATA = 2;
|
static const uint8_t PERIODIC_REPLY_DATA = 2;
|
||||||
|
|
||||||
AcuDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie);
|
AcuDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie, bool enableHkSets);
|
||||||
virtual ~AcuDummy();
|
virtual ~AcuDummy();
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
ACU::CoreHk coreHk;
|
||||||
|
ACU::AuxHk auxHk;
|
||||||
|
bool enableHkSets;
|
||||||
|
|
||||||
void doStartUp() override;
|
void doStartUp() override;
|
||||||
void doShutDown() override;
|
void doShutDown() override;
|
||||||
ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t *id) override;
|
ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t *id) override;
|
||||||
@ -28,6 +33,7 @@ class AcuDummy : public DeviceHandlerBase {
|
|||||||
uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override;
|
uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override;
|
||||||
ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
|
ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
|
||||||
LocalDataPoolManager &poolManager) override;
|
LocalDataPoolManager &poolManager) override;
|
||||||
|
LocalPoolDataSetBase *getDataSetHandle(sid_t sid) override;
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* DUMMIES_ACUDUMMY_H_ */
|
#endif /* DUMMIES_ACUDUMMY_H_ */
|
||||||
|
@ -2,8 +2,13 @@
|
|||||||
|
|
||||||
#include <mission/acs/imtqHelpers.h>
|
#include <mission/acs/imtqHelpers.h>
|
||||||
|
|
||||||
ImtqDummy::ImtqDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie)
|
ImtqDummy::ImtqDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie,
|
||||||
: DeviceHandlerBase(objectId, comif, comCookie) {}
|
power::Switch_t pwrSwitcher, bool enableHkSets)
|
||||||
|
: DeviceHandlerBase(objectId, comif, comCookie),
|
||||||
|
setNoTorque(this),
|
||||||
|
setWithTorque(this),
|
||||||
|
enableHkSets(enableHkSets),
|
||||||
|
switcher(pwrSwitcher) {}
|
||||||
|
|
||||||
ImtqDummy::~ImtqDummy() = default;
|
ImtqDummy::~ImtqDummy() = default;
|
||||||
|
|
||||||
@ -11,6 +16,15 @@ void ImtqDummy::doStartUp() { setMode(MODE_NORMAL); }
|
|||||||
|
|
||||||
void ImtqDummy::doShutDown() { setMode(_MODE_POWER_DOWN); }
|
void ImtqDummy::doShutDown() { setMode(_MODE_POWER_DOWN); }
|
||||||
|
|
||||||
|
ReturnValue_t ImtqDummy::getSwitches(const uint8_t **switches, uint8_t *numberOfSwitches) {
|
||||||
|
if (switcher != power::NO_SWITCH) {
|
||||||
|
*numberOfSwitches = 1;
|
||||||
|
*switches = &switcher;
|
||||||
|
return returnvalue::OK;
|
||||||
|
}
|
||||||
|
return DeviceHandlerBase::NO_SWITCH;
|
||||||
|
}
|
||||||
|
|
||||||
ReturnValue_t ImtqDummy::buildNormalDeviceCommand(DeviceCommandId_t *id) { return NOTHING_TO_SEND; }
|
ReturnValue_t ImtqDummy::buildNormalDeviceCommand(DeviceCommandId_t *id) { return NOTHING_TO_SEND; }
|
||||||
|
|
||||||
ReturnValue_t ImtqDummy::buildTransitionDeviceCommand(DeviceCommandId_t *id) {
|
ReturnValue_t ImtqDummy::buildTransitionDeviceCommand(DeviceCommandId_t *id) {
|
||||||
@ -45,5 +59,37 @@ ReturnValue_t ImtqDummy::initializeLocalDataPool(localpool::DataPool &localDataP
|
|||||||
localDataPoolMap.emplace(imtq::ACTUATION_RAW_STATUS, new PoolEntry<uint8_t>({0}));
|
localDataPoolMap.emplace(imtq::ACTUATION_RAW_STATUS, new PoolEntry<uint8_t>({0}));
|
||||||
localDataPoolMap.emplace(imtq::DIPOLES_ID, new PoolEntry<int16_t>({0, 0, 0}));
|
localDataPoolMap.emplace(imtq::DIPOLES_ID, new PoolEntry<int16_t>({0, 0, 0}));
|
||||||
localDataPoolMap.emplace(imtq::CURRENT_TORQUE_DURATION, new PoolEntry<uint16_t>({0}));
|
localDataPoolMap.emplace(imtq::CURRENT_TORQUE_DURATION, new PoolEntry<uint16_t>({0}));
|
||||||
|
|
||||||
|
// ENG HK No Torque
|
||||||
|
localDataPoolMap.emplace(imtq::DIGITAL_VOLTAGE_MV, new PoolEntry<uint16_t>({0}));
|
||||||
|
localDataPoolMap.emplace(imtq::ANALOG_VOLTAGE_MV, new PoolEntry<uint16_t>({0}));
|
||||||
|
localDataPoolMap.emplace(imtq::DIGITAL_CURRENT, new PoolEntry<float>({0}));
|
||||||
|
localDataPoolMap.emplace(imtq::ANALOG_CURRENT, new PoolEntry<float>({0}));
|
||||||
|
localDataPoolMap.emplace(imtq::COIL_CURRENTS, &coilCurrentsMilliampsNoTorque);
|
||||||
|
localDataPoolMap.emplace(imtq::COIL_TEMPERATURES, &coilTempsNoTorque);
|
||||||
|
localDataPoolMap.emplace(imtq::MCU_TEMPERATURE, new PoolEntry<int16_t>({0}));
|
||||||
|
|
||||||
|
// ENG HK With Torque
|
||||||
|
localDataPoolMap.emplace(imtq::DIGITAL_VOLTAGE_MV_WT, new PoolEntry<uint16_t>({0}));
|
||||||
|
localDataPoolMap.emplace(imtq::ANALOG_VOLTAGE_MV_WT, new PoolEntry<uint16_t>({0}));
|
||||||
|
localDataPoolMap.emplace(imtq::DIGITAL_CURRENT_WT, new PoolEntry<float>({0}));
|
||||||
|
localDataPoolMap.emplace(imtq::ANALOG_CURRENT_WT, new PoolEntry<float>({0}));
|
||||||
|
localDataPoolMap.emplace(imtq::COIL_CURRENTS_WT, &coilCurrentsMilliampsWithTorque);
|
||||||
|
localDataPoolMap.emplace(imtq::COIL_TEMPERATURES_WT, &coilTempsWithTorque);
|
||||||
|
localDataPoolMap.emplace(imtq::MCU_TEMPERATURE_WT, new PoolEntry<int16_t>({0}));
|
||||||
|
|
||||||
|
poolManager.subscribeForDiagPeriodicPacket(
|
||||||
|
subdp::DiagnosticsHkPeriodicParams(setNoTorque.getSid(), enableHkSets, 30.0));
|
||||||
|
poolManager.subscribeForDiagPeriodicPacket(
|
||||||
|
subdp::DiagnosticsHkPeriodicParams(setWithTorque.getSid(), enableHkSets, 30.0));
|
||||||
return DeviceHandlerBase::initializeLocalDataPool(localDataPoolMap, poolManager);
|
return DeviceHandlerBase::initializeLocalDataPool(localDataPoolMap, poolManager);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
LocalPoolDataSetBase *ImtqDummy::getDataSetHandle(sid_t sid) {
|
||||||
|
if (sid == setNoTorque.getSid()) {
|
||||||
|
return &setNoTorque;
|
||||||
|
} else if (sid == setWithTorque.getSid()) {
|
||||||
|
return &setWithTorque;
|
||||||
|
}
|
||||||
|
return nullptr;
|
||||||
|
}
|
||||||
|
@ -3,6 +3,8 @@
|
|||||||
|
|
||||||
#include <fsfw/devicehandlers/DeviceHandlerBase.h>
|
#include <fsfw/devicehandlers/DeviceHandlerBase.h>
|
||||||
|
|
||||||
|
#include "mission/acs/imtqHelpers.h"
|
||||||
|
|
||||||
class ImtqDummy : public DeviceHandlerBase {
|
class ImtqDummy : public DeviceHandlerBase {
|
||||||
public:
|
public:
|
||||||
static const DeviceCommandId_t SIMPLE_COMMAND = 1;
|
static const DeviceCommandId_t SIMPLE_COMMAND = 1;
|
||||||
@ -11,10 +13,35 @@ class ImtqDummy : public DeviceHandlerBase {
|
|||||||
static const uint8_t SIMPLE_COMMAND_DATA = 1;
|
static const uint8_t SIMPLE_COMMAND_DATA = 1;
|
||||||
static const uint8_t PERIODIC_REPLY_DATA = 2;
|
static const uint8_t PERIODIC_REPLY_DATA = 2;
|
||||||
|
|
||||||
ImtqDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie);
|
ImtqDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie,
|
||||||
|
power::Switch_t pwrSwitcher, bool enableHkSets);
|
||||||
~ImtqDummy() override;
|
~ImtqDummy() override;
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
ReturnValue_t getSwitches(const uint8_t **switches, uint8_t *numberOfSwitches) override;
|
||||||
|
imtq::HkDatasetNoTorque setNoTorque;
|
||||||
|
imtq::HkDatasetWithTorque setWithTorque;
|
||||||
|
bool enableHkSets;
|
||||||
|
|
||||||
|
PoolEntry<uint8_t> statusMode = PoolEntry<uint8_t>({0});
|
||||||
|
PoolEntry<uint8_t> statusError = PoolEntry<uint8_t>({0});
|
||||||
|
PoolEntry<uint8_t> statusConfig = PoolEntry<uint8_t>({0});
|
||||||
|
PoolEntry<uint32_t> statusUptime = PoolEntry<uint32_t>({0});
|
||||||
|
|
||||||
|
PoolEntry<int32_t> mgmCalEntry = PoolEntry<int32_t>(3);
|
||||||
|
PoolEntry<int16_t> dipolesPoolEntry = PoolEntry<int16_t>({0, 0, 0}, false);
|
||||||
|
PoolEntry<uint16_t> torqueDurationEntry = PoolEntry<uint16_t>({0}, false);
|
||||||
|
PoolEntry<float> coilCurrentsMilliampsNoTorque = PoolEntry<float>(3);
|
||||||
|
PoolEntry<float> coilCurrentsMilliampsWithTorque = PoolEntry<float>(3);
|
||||||
|
PoolEntry<int16_t> coilTempsNoTorque = PoolEntry<int16_t>(3);
|
||||||
|
PoolEntry<int16_t> coilTempsWithTorque = PoolEntry<int16_t>(3);
|
||||||
|
PoolEntry<float> mtmRawNoTorque = PoolEntry<float>(3);
|
||||||
|
PoolEntry<uint8_t> actStatusNoTorque = PoolEntry<uint8_t>(1);
|
||||||
|
PoolEntry<float> mtmRawWithTorque = PoolEntry<float>(3);
|
||||||
|
PoolEntry<uint8_t> actStatusWithTorque = PoolEntry<uint8_t>(1);
|
||||||
|
|
||||||
|
power::Switch_t switcher = power::NO_SWITCH;
|
||||||
|
|
||||||
void doStartUp() override;
|
void doStartUp() override;
|
||||||
void doShutDown() override;
|
void doShutDown() override;
|
||||||
ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t *id) override;
|
ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t *id) override;
|
||||||
@ -28,6 +55,7 @@ class ImtqDummy : public DeviceHandlerBase {
|
|||||||
uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override;
|
uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override;
|
||||||
ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
|
ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
|
||||||
LocalDataPoolManager &poolManager) override;
|
LocalDataPoolManager &poolManager) override;
|
||||||
|
LocalPoolDataSetBase *getDataSetHandle(sid_t sid) override;
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* DUMMIES_IMTQDUMMY_H_ */
|
#endif /* DUMMIES_IMTQDUMMY_H_ */
|
||||||
|
@ -42,7 +42,8 @@
|
|||||||
#include "mission/system/tree/payloadModeTree.h"
|
#include "mission/system/tree/payloadModeTree.h"
|
||||||
#include "mission/tcs/defs.h"
|
#include "mission/tcs/defs.h"
|
||||||
|
|
||||||
void dummy::createDummies(DummyCfg cfg, PowerSwitchIF& pwrSwitcher, GpioIF* gpioIF) {
|
void dummy::createDummies(DummyCfg cfg, PowerSwitchIF& pwrSwitcher, GpioIF* gpioIF,
|
||||||
|
bool enableHkSets) {
|
||||||
new ComIFDummy(objects::DUMMY_COM_IF);
|
new ComIFDummy(objects::DUMMY_COM_IF);
|
||||||
auto* comCookieDummy = new ComCookieDummy();
|
auto* comCookieDummy = new ComCookieDummy();
|
||||||
if (cfg.addBpxBattDummy) {
|
if (cfg.addBpxBattDummy) {
|
||||||
@ -74,12 +75,15 @@ void dummy::createDummies(DummyCfg cfg, PowerSwitchIF& pwrSwitcher, GpioIF* gpio
|
|||||||
}
|
}
|
||||||
auto* imtqAssy = new ImtqAssembly(objects::IMTQ_ASSY);
|
auto* imtqAssy = new ImtqAssembly(objects::IMTQ_ASSY);
|
||||||
imtqAssy->connectModeTreeParent(satsystem::acs::ACS_SUBSYSTEM);
|
imtqAssy->connectModeTreeParent(satsystem::acs::ACS_SUBSYSTEM);
|
||||||
auto* imtqDummy = new ImtqDummy(objects::IMTQ_HANDLER, objects::DUMMY_COM_IF, comCookieDummy);
|
auto* imtqDummy = new ImtqDummy(objects::IMTQ_HANDLER, objects::DUMMY_COM_IF, comCookieDummy,
|
||||||
|
power::Switches::PDU1_CH3_MGT_5V, enableHkSets);
|
||||||
imtqDummy->enableThermalModule(ThermalStateCfg());
|
imtqDummy->enableThermalModule(ThermalStateCfg());
|
||||||
|
imtqDummy->setPowerSwitcher(&pwrSwitcher);
|
||||||
imtqDummy->connectModeTreeParent(*imtqAssy);
|
imtqDummy->connectModeTreeParent(*imtqAssy);
|
||||||
if (cfg.addOnlyAcuDummy) {
|
if (cfg.addOnlyAcuDummy) {
|
||||||
new AcuDummy(objects::ACU_HANDLER, objects::DUMMY_COM_IF, comCookieDummy);
|
new AcuDummy(objects::ACU_HANDLER, objects::DUMMY_COM_IF, comCookieDummy, enableHkSets);
|
||||||
} else if (cfg.addPowerDummies) {
|
} else if (cfg.addPowerDummies) {
|
||||||
|
new AcuDummy(objects::ACU_HANDLER, objects::DUMMY_COM_IF, comCookieDummy, enableHkSets);
|
||||||
new PduDummy(objects::PDU1_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 PduDummy(objects::PDU2_HANDLER, objects::DUMMY_COM_IF, comCookieDummy);
|
||||||
new P60DockDummy(objects::P60DOCK_HANDLER, objects::DUMMY_COM_IF, comCookieDummy);
|
new P60DockDummy(objects::P60DOCK_HANDLER, objects::DUMMY_COM_IF, comCookieDummy);
|
||||||
|
@ -22,6 +22,6 @@ struct DummyCfg {
|
|||||||
bool addCamSwitcherDummy = false;
|
bool addCamSwitcherDummy = false;
|
||||||
};
|
};
|
||||||
|
|
||||||
void createDummies(DummyCfg cfg, PowerSwitchIF& pwrSwitch, GpioIF* gpioIF);
|
void createDummies(DummyCfg cfg, PowerSwitchIF& pwrSwitch, GpioIF* gpioIF, bool enableHkSets);
|
||||||
|
|
||||||
} // namespace dummy
|
} // namespace dummy
|
||||||
|
2
fsfw
2
fsfw
@ -1 +1 @@
|
|||||||
Subproject commit 5eb9ee8bc1e6f8640cbea46febd11e4b92241881
|
Subproject commit 5322de059916efcf874b10ccc766b46e53d2470b
|
@ -177,20 +177,24 @@ Event ID (dec); Event ID (hex); Name; Severity; Description; File Path
|
|||||||
12515;0x30e3;STR_HELPER_FILE_NOT_EXISTS;LOW;Specified file does not exist P1: Internal state of str helper;linux/acs/StrComHandler.h
|
12515;0x30e3;STR_HELPER_FILE_NOT_EXISTS;LOW;Specified file does not exist P1: Internal state of str helper;linux/acs/StrComHandler.h
|
||||||
12516;0x30e4;STR_HELPER_SENDING_PACKET_FAILED;LOW;No description;linux/acs/StrComHandler.h
|
12516;0x30e4;STR_HELPER_SENDING_PACKET_FAILED;LOW;No description;linux/acs/StrComHandler.h
|
||||||
12517;0x30e5;STR_HELPER_REQUESTING_MSG_FAILED;LOW;No description;linux/acs/StrComHandler.h
|
12517;0x30e5;STR_HELPER_REQUESTING_MSG_FAILED;LOW;No description;linux/acs/StrComHandler.h
|
||||||
12600;0x3138;MPSOC_FLASH_WRITE_FAILED;LOW;Flash write fails;linux/payload/PlocMpsocHelper.h
|
12600;0x3138;MPSOC_FLASH_WRITE_FAILED;LOW;Flash write fails;linux/payload/PlocMpsocSpecialComHelper.h
|
||||||
12601;0x3139;MPSOC_FLASH_WRITE_SUCCESSFUL;LOW;Flash write successful;linux/payload/PlocMpsocHelper.h
|
12601;0x3139;MPSOC_FLASH_WRITE_SUCCESSFUL;INFO;Flash write successful;linux/payload/PlocMpsocSpecialComHelper.h
|
||||||
12602;0x313a;MPSOC_SENDING_COMMAND_FAILED;LOW;No description;linux/payload/PlocMpsocHelper.h
|
12602;0x313a;MPSOC_SENDING_COMMAND_FAILED;LOW;No description;linux/payload/PlocMpsocSpecialComHelper.h
|
||||||
12603;0x313b;MPSOC_HELPER_REQUESTING_REPLY_FAILED;LOW;Request receive message of communication interface failed P1: Return value returned by the communication interface requestReceiveMessage function P2: Internal state of MPSoC helper;linux/payload/PlocMpsocHelper.h
|
12603;0x313b;MPSOC_HELPER_REQUESTING_REPLY_FAILED;LOW;Request receive message of communication interface failed P1: Return value returned by the communication interface requestReceiveMessage function P2: Internal state of MPSoC helper;linux/payload/PlocMpsocSpecialComHelper.h
|
||||||
12604;0x313c;MPSOC_HELPER_READING_REPLY_FAILED;LOW;Reading receive message of communication interface failed P1: Return value returned by the communication interface readingReceivedMessage function P2: Internal state of MPSoC helper;linux/payload/PlocMpsocHelper.h
|
12604;0x313c;MPSOC_HELPER_READING_REPLY_FAILED;LOW;Reading receive message of communication interface failed P1: Return value returned by the communication interface readingReceivedMessage function P2: Internal state of MPSoC helper;linux/payload/PlocMpsocSpecialComHelper.h
|
||||||
12605;0x313d;MPSOC_MISSING_ACK;LOW;Did not receive acknowledgment report P1: Number of bytes missing P2: Internal state of MPSoC helper;linux/payload/PlocMpsocHelper.h
|
12605;0x313d;MPSOC_MISSING_ACK;LOW;Did not receive acknowledgment report P1: Number of bytes missing P2: Internal state of MPSoC helper;linux/payload/PlocMpsocSpecialComHelper.h
|
||||||
12606;0x313e;MPSOC_MISSING_EXE;LOW;Did not receive execution report P1: Number of bytes missing P2: Internal state of MPSoC helper;linux/payload/PlocMpsocHelper.h
|
12606;0x313e;MPSOC_MISSING_EXE;LOW;Did not receive execution report P1: Number of bytes missing P2: Internal state of MPSoC helper;linux/payload/PlocMpsocSpecialComHelper.h
|
||||||
12607;0x313f;MPSOC_ACK_FAILURE_REPORT;LOW;Received acknowledgment failure report P1: Internal state of MPSoC;linux/payload/PlocMpsocHelper.h
|
12607;0x313f;MPSOC_ACK_FAILURE_REPORT;LOW;Received acknowledgment failure report P1: Internal state of MPSoC;linux/payload/PlocMpsocSpecialComHelper.h
|
||||||
12608;0x3140;MPSOC_EXE_FAILURE_REPORT;LOW;Received execution failure report P1: Internal state of MPSoC;linux/payload/PlocMpsocHelper.h
|
12608;0x3140;MPSOC_EXE_FAILURE_REPORT;LOW;Received execution failure report P1: Internal state of MPSoC;linux/payload/PlocMpsocSpecialComHelper.h
|
||||||
12609;0x3141;MPSOC_ACK_INVALID_APID;LOW;Expected acknowledgment report but received space packet with other apid P1: Apid of received space packet P2: Internal state of MPSoC;linux/payload/PlocMpsocHelper.h
|
12609;0x3141;MPSOC_ACK_INVALID_APID;LOW;Expected acknowledgment report but received space packet with other apid P1: Apid of received space packet P2: Internal state of MPSoC;linux/payload/PlocMpsocSpecialComHelper.h
|
||||||
12610;0x3142;MPSOC_EXE_INVALID_APID;LOW;Expected execution report but received space packet with other apid P1: Apid of received space packet P2: Internal state of MPSoC;linux/payload/PlocMpsocHelper.h
|
12610;0x3142;MPSOC_EXE_INVALID_APID;LOW;Expected execution report but received space packet with other apid P1: Apid of received space packet P2: Internal state of MPSoC;linux/payload/PlocMpsocSpecialComHelper.h
|
||||||
12611;0x3143;MPSOC_HELPER_SEQ_CNT_MISMATCH;LOW;Received sequence count does not match expected sequence count P1: Expected sequence count P2: Received sequence count;linux/payload/PlocMpsocHelper.h
|
12611;0x3143;MPSOC_HELPER_SEQ_CNT_MISMATCH;LOW;Received sequence count does not match expected sequence count P1: Expected sequence count P2: Received sequence count;linux/payload/PlocMpsocSpecialComHelper.h
|
||||||
12612;0x3144;MPSOC_TM_SIZE_ERROR;LOW;No description;linux/payload/PlocMpsocHelper.h
|
12612;0x3144;MPSOC_TM_SIZE_ERROR;LOW;No description;linux/payload/PlocMpsocSpecialComHelper.h
|
||||||
12613;0x3145;MPSOC_TM_CRC_MISSMATCH;LOW;No description;linux/payload/PlocMpsocHelper.h
|
12613;0x3145;MPSOC_TM_CRC_MISSMATCH;LOW;No description;linux/payload/PlocMpsocSpecialComHelper.h
|
||||||
|
12614;0x3146;MPSOC_FLASH_READ_PACKET_ERROR;LOW;No description;linux/payload/PlocMpsocSpecialComHelper.h
|
||||||
|
12615;0x3147;MPSOC_FLASH_READ_FAILED;LOW;No description;linux/payload/PlocMpsocSpecialComHelper.h
|
||||||
|
12616;0x3148;MPSOC_FLASH_READ_SUCCESSFUL;INFO;No description;linux/payload/PlocMpsocSpecialComHelper.h
|
||||||
|
12617;0x3149;MPSOC_READ_TIMEOUT;LOW;No description;linux/payload/PlocMpsocSpecialComHelper.h
|
||||||
12700;0x319c;TRANSITION_BACK_TO_OFF;MEDIUM;Could not transition properly and went back to ALL OFF;mission/payload/PayloadPcduHandler.h
|
12700;0x319c;TRANSITION_BACK_TO_OFF;MEDIUM;Could not transition properly and went back to ALL OFF;mission/payload/PayloadPcduHandler.h
|
||||||
12701;0x319d;NEG_V_OUT_OF_BOUNDS;MEDIUM;P1: 0 -> too low, 1 -> too high P2: Float value;mission/payload/PayloadPcduHandler.h
|
12701;0x319d;NEG_V_OUT_OF_BOUNDS;MEDIUM;P1: 0 -> too low, 1 -> too high P2: Float value;mission/payload/PayloadPcduHandler.h
|
||||||
12702;0x319e;U_DRO_OUT_OF_BOUNDS;MEDIUM;P1: 0 -> too low, 1 -> too high P2: Float value;mission/payload/PayloadPcduHandler.h
|
12702;0x319e;U_DRO_OUT_OF_BOUNDS;MEDIUM;P1: 0 -> too low, 1 -> too high P2: Float value;mission/payload/PayloadPcduHandler.h
|
||||||
@ -274,7 +278,7 @@ Event ID (dec); Event ID (hex); Name; Severity; Description; File Path
|
|||||||
14105;0x3719;CAMERA_OVERHEATING;HIGH;No description;mission/controller/tcsDefs.h
|
14105;0x3719;CAMERA_OVERHEATING;HIGH;No description;mission/controller/tcsDefs.h
|
||||||
14106;0x371a;PCDU_SYSTEM_OVERHEATING;HIGH;No description;mission/controller/tcsDefs.h
|
14106;0x371a;PCDU_SYSTEM_OVERHEATING;HIGH;No description;mission/controller/tcsDefs.h
|
||||||
14107;0x371b;HEATER_NOT_OFF_FOR_OFF_MODE;MEDIUM;No description;mission/controller/tcsDefs.h
|
14107;0x371b;HEATER_NOT_OFF_FOR_OFF_MODE;MEDIUM;No description;mission/controller/tcsDefs.h
|
||||||
14108;0x371c;MGT_OVERHEATING;MEDIUM;No description;mission/controller/tcsDefs.h
|
14108;0x371c;MGT_OVERHEATING;HIGH;No description;mission/controller/tcsDefs.h
|
||||||
14201;0x3779;TX_TIMER_EXPIRED;INFO;The transmit timer to protect the Syrlinks expired P1: The current timer value;mission/system/com/ComSubsystem.h
|
14201;0x3779;TX_TIMER_EXPIRED;INFO;The transmit timer to protect the Syrlinks expired P1: The current timer value;mission/system/com/ComSubsystem.h
|
||||||
14202;0x377a;BIT_LOCK_TX_ON;INFO;Transmitter will be turned on due to detection of bitlock;mission/system/com/ComSubsystem.h
|
14202;0x377a;BIT_LOCK_TX_ON;INFO;Transmitter will be turned on due to detection of bitlock;mission/system/com/ComSubsystem.h
|
||||||
14300;0x37dc;POSSIBLE_FILE_CORRUPTION;LOW;P1: Result code of TM packet parser. P2: Timestamp of possibly corrupt file as a unix timestamp.;mission/persistentTmStoreDefs.h
|
14300;0x37dc;POSSIBLE_FILE_CORRUPTION;LOW;P1: Result code of TM packet parser. P2: Timestamp of possibly corrupt file as a unix timestamp.;mission/persistentTmStoreDefs.h
|
||||||
|
|
@ -177,20 +177,24 @@ Event ID (dec); Event ID (hex); Name; Severity; Description; File Path
|
|||||||
12515;0x30e3;STR_HELPER_FILE_NOT_EXISTS;LOW;Specified file does not exist P1: Internal state of str helper;linux/acs/StrComHandler.h
|
12515;0x30e3;STR_HELPER_FILE_NOT_EXISTS;LOW;Specified file does not exist P1: Internal state of str helper;linux/acs/StrComHandler.h
|
||||||
12516;0x30e4;STR_HELPER_SENDING_PACKET_FAILED;LOW;No description;linux/acs/StrComHandler.h
|
12516;0x30e4;STR_HELPER_SENDING_PACKET_FAILED;LOW;No description;linux/acs/StrComHandler.h
|
||||||
12517;0x30e5;STR_HELPER_REQUESTING_MSG_FAILED;LOW;No description;linux/acs/StrComHandler.h
|
12517;0x30e5;STR_HELPER_REQUESTING_MSG_FAILED;LOW;No description;linux/acs/StrComHandler.h
|
||||||
12600;0x3138;MPSOC_FLASH_WRITE_FAILED;LOW;Flash write fails;linux/payload/PlocMpsocHelper.h
|
12600;0x3138;MPSOC_FLASH_WRITE_FAILED;LOW;Flash write fails;linux/payload/PlocMpsocSpecialComHelper.h
|
||||||
12601;0x3139;MPSOC_FLASH_WRITE_SUCCESSFUL;LOW;Flash write successful;linux/payload/PlocMpsocHelper.h
|
12601;0x3139;MPSOC_FLASH_WRITE_SUCCESSFUL;INFO;Flash write successful;linux/payload/PlocMpsocSpecialComHelper.h
|
||||||
12602;0x313a;MPSOC_SENDING_COMMAND_FAILED;LOW;No description;linux/payload/PlocMpsocHelper.h
|
12602;0x313a;MPSOC_SENDING_COMMAND_FAILED;LOW;No description;linux/payload/PlocMpsocSpecialComHelper.h
|
||||||
12603;0x313b;MPSOC_HELPER_REQUESTING_REPLY_FAILED;LOW;Request receive message of communication interface failed P1: Return value returned by the communication interface requestReceiveMessage function P2: Internal state of MPSoC helper;linux/payload/PlocMpsocHelper.h
|
12603;0x313b;MPSOC_HELPER_REQUESTING_REPLY_FAILED;LOW;Request receive message of communication interface failed P1: Return value returned by the communication interface requestReceiveMessage function P2: Internal state of MPSoC helper;linux/payload/PlocMpsocSpecialComHelper.h
|
||||||
12604;0x313c;MPSOC_HELPER_READING_REPLY_FAILED;LOW;Reading receive message of communication interface failed P1: Return value returned by the communication interface readingReceivedMessage function P2: Internal state of MPSoC helper;linux/payload/PlocMpsocHelper.h
|
12604;0x313c;MPSOC_HELPER_READING_REPLY_FAILED;LOW;Reading receive message of communication interface failed P1: Return value returned by the communication interface readingReceivedMessage function P2: Internal state of MPSoC helper;linux/payload/PlocMpsocSpecialComHelper.h
|
||||||
12605;0x313d;MPSOC_MISSING_ACK;LOW;Did not receive acknowledgment report P1: Number of bytes missing P2: Internal state of MPSoC helper;linux/payload/PlocMpsocHelper.h
|
12605;0x313d;MPSOC_MISSING_ACK;LOW;Did not receive acknowledgment report P1: Number of bytes missing P2: Internal state of MPSoC helper;linux/payload/PlocMpsocSpecialComHelper.h
|
||||||
12606;0x313e;MPSOC_MISSING_EXE;LOW;Did not receive execution report P1: Number of bytes missing P2: Internal state of MPSoC helper;linux/payload/PlocMpsocHelper.h
|
12606;0x313e;MPSOC_MISSING_EXE;LOW;Did not receive execution report P1: Number of bytes missing P2: Internal state of MPSoC helper;linux/payload/PlocMpsocSpecialComHelper.h
|
||||||
12607;0x313f;MPSOC_ACK_FAILURE_REPORT;LOW;Received acknowledgment failure report P1: Internal state of MPSoC;linux/payload/PlocMpsocHelper.h
|
12607;0x313f;MPSOC_ACK_FAILURE_REPORT;LOW;Received acknowledgment failure report P1: Internal state of MPSoC;linux/payload/PlocMpsocSpecialComHelper.h
|
||||||
12608;0x3140;MPSOC_EXE_FAILURE_REPORT;LOW;Received execution failure report P1: Internal state of MPSoC;linux/payload/PlocMpsocHelper.h
|
12608;0x3140;MPSOC_EXE_FAILURE_REPORT;LOW;Received execution failure report P1: Internal state of MPSoC;linux/payload/PlocMpsocSpecialComHelper.h
|
||||||
12609;0x3141;MPSOC_ACK_INVALID_APID;LOW;Expected acknowledgment report but received space packet with other apid P1: Apid of received space packet P2: Internal state of MPSoC;linux/payload/PlocMpsocHelper.h
|
12609;0x3141;MPSOC_ACK_INVALID_APID;LOW;Expected acknowledgment report but received space packet with other apid P1: Apid of received space packet P2: Internal state of MPSoC;linux/payload/PlocMpsocSpecialComHelper.h
|
||||||
12610;0x3142;MPSOC_EXE_INVALID_APID;LOW;Expected execution report but received space packet with other apid P1: Apid of received space packet P2: Internal state of MPSoC;linux/payload/PlocMpsocHelper.h
|
12610;0x3142;MPSOC_EXE_INVALID_APID;LOW;Expected execution report but received space packet with other apid P1: Apid of received space packet P2: Internal state of MPSoC;linux/payload/PlocMpsocSpecialComHelper.h
|
||||||
12611;0x3143;MPSOC_HELPER_SEQ_CNT_MISMATCH;LOW;Received sequence count does not match expected sequence count P1: Expected sequence count P2: Received sequence count;linux/payload/PlocMpsocHelper.h
|
12611;0x3143;MPSOC_HELPER_SEQ_CNT_MISMATCH;LOW;Received sequence count does not match expected sequence count P1: Expected sequence count P2: Received sequence count;linux/payload/PlocMpsocSpecialComHelper.h
|
||||||
12612;0x3144;MPSOC_TM_SIZE_ERROR;LOW;No description;linux/payload/PlocMpsocHelper.h
|
12612;0x3144;MPSOC_TM_SIZE_ERROR;LOW;No description;linux/payload/PlocMpsocSpecialComHelper.h
|
||||||
12613;0x3145;MPSOC_TM_CRC_MISSMATCH;LOW;No description;linux/payload/PlocMpsocHelper.h
|
12613;0x3145;MPSOC_TM_CRC_MISSMATCH;LOW;No description;linux/payload/PlocMpsocSpecialComHelper.h
|
||||||
|
12614;0x3146;MPSOC_FLASH_READ_PACKET_ERROR;LOW;No description;linux/payload/PlocMpsocSpecialComHelper.h
|
||||||
|
12615;0x3147;MPSOC_FLASH_READ_FAILED;LOW;No description;linux/payload/PlocMpsocSpecialComHelper.h
|
||||||
|
12616;0x3148;MPSOC_FLASH_READ_SUCCESSFUL;INFO;No description;linux/payload/PlocMpsocSpecialComHelper.h
|
||||||
|
12617;0x3149;MPSOC_READ_TIMEOUT;LOW;No description;linux/payload/PlocMpsocSpecialComHelper.h
|
||||||
12700;0x319c;TRANSITION_BACK_TO_OFF;MEDIUM;Could not transition properly and went back to ALL OFF;mission/payload/PayloadPcduHandler.h
|
12700;0x319c;TRANSITION_BACK_TO_OFF;MEDIUM;Could not transition properly and went back to ALL OFF;mission/payload/PayloadPcduHandler.h
|
||||||
12701;0x319d;NEG_V_OUT_OF_BOUNDS;MEDIUM;P1: 0 -> too low, 1 -> too high P2: Float value;mission/payload/PayloadPcduHandler.h
|
12701;0x319d;NEG_V_OUT_OF_BOUNDS;MEDIUM;P1: 0 -> too low, 1 -> too high P2: Float value;mission/payload/PayloadPcduHandler.h
|
||||||
12702;0x319e;U_DRO_OUT_OF_BOUNDS;MEDIUM;P1: 0 -> too low, 1 -> too high P2: Float value;mission/payload/PayloadPcduHandler.h
|
12702;0x319e;U_DRO_OUT_OF_BOUNDS;MEDIUM;P1: 0 -> too low, 1 -> too high P2: Float value;mission/payload/PayloadPcduHandler.h
|
||||||
@ -274,7 +278,7 @@ Event ID (dec); Event ID (hex); Name; Severity; Description; File Path
|
|||||||
14105;0x3719;CAMERA_OVERHEATING;HIGH;No description;mission/controller/tcsDefs.h
|
14105;0x3719;CAMERA_OVERHEATING;HIGH;No description;mission/controller/tcsDefs.h
|
||||||
14106;0x371a;PCDU_SYSTEM_OVERHEATING;HIGH;No description;mission/controller/tcsDefs.h
|
14106;0x371a;PCDU_SYSTEM_OVERHEATING;HIGH;No description;mission/controller/tcsDefs.h
|
||||||
14107;0x371b;HEATER_NOT_OFF_FOR_OFF_MODE;MEDIUM;No description;mission/controller/tcsDefs.h
|
14107;0x371b;HEATER_NOT_OFF_FOR_OFF_MODE;MEDIUM;No description;mission/controller/tcsDefs.h
|
||||||
14108;0x371c;MGT_OVERHEATING;MEDIUM;No description;mission/controller/tcsDefs.h
|
14108;0x371c;MGT_OVERHEATING;HIGH;No description;mission/controller/tcsDefs.h
|
||||||
14201;0x3779;TX_TIMER_EXPIRED;INFO;The transmit timer to protect the Syrlinks expired P1: The current timer value;mission/system/com/ComSubsystem.h
|
14201;0x3779;TX_TIMER_EXPIRED;INFO;The transmit timer to protect the Syrlinks expired P1: The current timer value;mission/system/com/ComSubsystem.h
|
||||||
14202;0x377a;BIT_LOCK_TX_ON;INFO;Transmitter will be turned on due to detection of bitlock;mission/system/com/ComSubsystem.h
|
14202;0x377a;BIT_LOCK_TX_ON;INFO;Transmitter will be turned on due to detection of bitlock;mission/system/com/ComSubsystem.h
|
||||||
14300;0x37dc;POSSIBLE_FILE_CORRUPTION;LOW;P1: Result code of TM packet parser. P2: Timestamp of possibly corrupt file as a unix timestamp.;mission/persistentTmStoreDefs.h
|
14300;0x37dc;POSSIBLE_FILE_CORRUPTION;LOW;P1: Result code of TM packet parser. P2: Timestamp of possibly corrupt file as a unix timestamp.;mission/persistentTmStoreDefs.h
|
||||||
|
|
@ -478,8 +478,8 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path
|
|||||||
0x53b6;STRH_StartrackerAlreadyBooted;Star tracker is already in firmware mode;182;STR_HANDLER;mission/acs/str/StarTrackerHandler.h
|
0x53b6;STRH_StartrackerAlreadyBooted;Star tracker is already in firmware mode;182;STR_HANDLER;mission/acs/str/StarTrackerHandler.h
|
||||||
0x53b7;STRH_StartrackerNotRunningFirmware;Star tracker must be in firmware mode to run this command;183;STR_HANDLER;mission/acs/str/StarTrackerHandler.h
|
0x53b7;STRH_StartrackerNotRunningFirmware;Star tracker must be in firmware mode to run this command;183;STR_HANDLER;mission/acs/str/StarTrackerHandler.h
|
||||||
0x53b8;STRH_StartrackerNotRunningBootloader;Star tracker must be in bootloader mode to run this command;184;STR_HANDLER;mission/acs/str/StarTrackerHandler.h
|
0x53b8;STRH_StartrackerNotRunningBootloader;Star tracker must be in bootloader mode to run this command;184;STR_HANDLER;mission/acs/str/StarTrackerHandler.h
|
||||||
0x54e0;DWLPWRON_InvalidMode;Received command has invalid JESD mode (valid modes are 0 - 5);224;DWLPWRON_CMD;linux/payload/plocMpscoDefs.h
|
0x54e0;DWLPWRON_InvalidMode;Received command has invalid JESD mode (valid modes are 0 - 5);224;DWLPWRON_CMD;linux/payload/plocMpsocHelpers.h
|
||||||
0x54e1;DWLPWRON_InvalidLaneRate;Received command has invalid lane rate (valid lane rate are 0 - 9);225;DWLPWRON_CMD;linux/payload/plocMpscoDefs.h
|
0x54e1;DWLPWRON_InvalidLaneRate;Received command has invalid lane rate (valid lane rate are 0 - 9);225;DWLPWRON_CMD;linux/payload/plocMpsocHelpers.h
|
||||||
0x5700;PLSPVhLP_RequestDone;No description;0;PLOC_SUPV_HELPER;linux/payload/PlocSupvUartMan.h
|
0x5700;PLSPVhLP_RequestDone;No description;0;PLOC_SUPV_HELPER;linux/payload/PlocSupvUartMan.h
|
||||||
0x5701;PLSPVhLP_NoPacketFound;No description;1;PLOC_SUPV_HELPER;linux/payload/PlocSupvUartMan.h
|
0x5701;PLSPVhLP_NoPacketFound;No description;1;PLOC_SUPV_HELPER;linux/payload/PlocSupvUartMan.h
|
||||||
0x5702;PLSPVhLP_DecodeBufTooSmall;No description;2;PLOC_SUPV_HELPER;linux/payload/PlocSupvUartMan.h
|
0x5702;PLSPVhLP_DecodeBufTooSmall;No description;2;PLOC_SUPV_HELPER;linux/payload/PlocSupvUartMan.h
|
||||||
@ -543,7 +543,8 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path
|
|||||||
0x63a0;NVMB_KeyNotExists;Specified key does not exist in json file;160;NVM_PARAM_BASE;mission/memory/NvmParameterBase.h
|
0x63a0;NVMB_KeyNotExists;Specified key does not exist in json file;160;NVM_PARAM_BASE;mission/memory/NvmParameterBase.h
|
||||||
0x64a0;FSHLP_SdNotMounted;SD card specified with path string not mounted;160;FILE_SYSTEM_HELPER;bsp_q7s/fs/FilesystemHelper.h
|
0x64a0;FSHLP_SdNotMounted;SD card specified with path string not mounted;160;FILE_SYSTEM_HELPER;bsp_q7s/fs/FilesystemHelper.h
|
||||||
0x64a1;FSHLP_FileNotExists;Specified file does not exist on filesystem;161;FILE_SYSTEM_HELPER;bsp_q7s/fs/FilesystemHelper.h
|
0x64a1;FSHLP_FileNotExists;Specified file does not exist on filesystem;161;FILE_SYSTEM_HELPER;bsp_q7s/fs/FilesystemHelper.h
|
||||||
0x65a0;PLMPHLP_FileClosedAccidentally;File accidentally close;160;PLOC_MPSOC_HELPER;linux/payload/PlocMpsocHelper.h
|
0x65a0;PLMPHLP_FileWriteError;File error occured for file transfers from OBC to the MPSoC.;160;PLOC_MPSOC_HELPER;linux/payload/PlocMpsocSpecialComHelper.h
|
||||||
|
0x65a1;PLMPHLP_FileReadError;File error occured for file transfers from MPSoC to OBC.;161;PLOC_MPSOC_HELPER;linux/payload/PlocMpsocSpecialComHelper.h
|
||||||
0x66a0;SADPL_CommandNotSupported;No description;160;SA_DEPL_HANDLER;mission/SolarArrayDeploymentHandler.h
|
0x66a0;SADPL_CommandNotSupported;No description;160;SA_DEPL_HANDLER;mission/SolarArrayDeploymentHandler.h
|
||||||
0x66a1;SADPL_DeploymentAlreadyExecuting;No description;161;SA_DEPL_HANDLER;mission/SolarArrayDeploymentHandler.h
|
0x66a1;SADPL_DeploymentAlreadyExecuting;No description;161;SA_DEPL_HANDLER;mission/SolarArrayDeploymentHandler.h
|
||||||
0x66a2;SADPL_MainSwitchTimeoutFailure;No description;162;SA_DEPL_HANDLER;mission/SolarArrayDeploymentHandler.h
|
0x66a2;SADPL_MainSwitchTimeoutFailure;No description;162;SA_DEPL_HANDLER;mission/SolarArrayDeploymentHandler.h
|
||||||
|
|
@ -1,7 +1,7 @@
|
|||||||
/**
|
/**
|
||||||
* @brief Auto-generated event translation file. Contains 291 translations.
|
* @brief Auto-generated event translation file. Contains 295 translations.
|
||||||
* @details
|
* @details
|
||||||
* Generated on: 2023-04-17 11:34:19
|
* Generated on: 2023-05-17 17:15:34
|
||||||
*/
|
*/
|
||||||
#include "translateEvents.h"
|
#include "translateEvents.h"
|
||||||
|
|
||||||
@ -197,6 +197,10 @@ const char *MPSOC_EXE_INVALID_APID_STRING = "MPSOC_EXE_INVALID_APID";
|
|||||||
const char *MPSOC_HELPER_SEQ_CNT_MISMATCH_STRING = "MPSOC_HELPER_SEQ_CNT_MISMATCH";
|
const char *MPSOC_HELPER_SEQ_CNT_MISMATCH_STRING = "MPSOC_HELPER_SEQ_CNT_MISMATCH";
|
||||||
const char *MPSOC_TM_SIZE_ERROR_STRING = "MPSOC_TM_SIZE_ERROR";
|
const char *MPSOC_TM_SIZE_ERROR_STRING = "MPSOC_TM_SIZE_ERROR";
|
||||||
const char *MPSOC_TM_CRC_MISSMATCH_STRING = "MPSOC_TM_CRC_MISSMATCH";
|
const char *MPSOC_TM_CRC_MISSMATCH_STRING = "MPSOC_TM_CRC_MISSMATCH";
|
||||||
|
const char *MPSOC_FLASH_READ_PACKET_ERROR_STRING = "MPSOC_FLASH_READ_PACKET_ERROR";
|
||||||
|
const char *MPSOC_FLASH_READ_FAILED_STRING = "MPSOC_FLASH_READ_FAILED";
|
||||||
|
const char *MPSOC_FLASH_READ_SUCCESSFUL_STRING = "MPSOC_FLASH_READ_SUCCESSFUL";
|
||||||
|
const char *MPSOC_READ_TIMEOUT_STRING = "MPSOC_READ_TIMEOUT";
|
||||||
const char *TRANSITION_BACK_TO_OFF_STRING = "TRANSITION_BACK_TO_OFF";
|
const char *TRANSITION_BACK_TO_OFF_STRING = "TRANSITION_BACK_TO_OFF";
|
||||||
const char *NEG_V_OUT_OF_BOUNDS_STRING = "NEG_V_OUT_OF_BOUNDS";
|
const char *NEG_V_OUT_OF_BOUNDS_STRING = "NEG_V_OUT_OF_BOUNDS";
|
||||||
const char *U_DRO_OUT_OF_BOUNDS_STRING = "U_DRO_OUT_OF_BOUNDS";
|
const char *U_DRO_OUT_OF_BOUNDS_STRING = "U_DRO_OUT_OF_BOUNDS";
|
||||||
@ -683,6 +687,14 @@ const char *translateEvents(Event event) {
|
|||||||
return MPSOC_TM_SIZE_ERROR_STRING;
|
return MPSOC_TM_SIZE_ERROR_STRING;
|
||||||
case (12613):
|
case (12613):
|
||||||
return MPSOC_TM_CRC_MISSMATCH_STRING;
|
return MPSOC_TM_CRC_MISSMATCH_STRING;
|
||||||
|
case (12614):
|
||||||
|
return MPSOC_FLASH_READ_PACKET_ERROR_STRING;
|
||||||
|
case (12615):
|
||||||
|
return MPSOC_FLASH_READ_FAILED_STRING;
|
||||||
|
case (12616):
|
||||||
|
return MPSOC_FLASH_READ_SUCCESSFUL_STRING;
|
||||||
|
case (12617):
|
||||||
|
return MPSOC_READ_TIMEOUT_STRING;
|
||||||
case (12700):
|
case (12700):
|
||||||
return TRANSITION_BACK_TO_OFF_STRING;
|
return TRANSITION_BACK_TO_OFF_STRING;
|
||||||
case (12701):
|
case (12701):
|
||||||
|
@ -2,7 +2,7 @@
|
|||||||
* @brief Auto-generated object translation file.
|
* @brief Auto-generated object translation file.
|
||||||
* @details
|
* @details
|
||||||
* Contains 175 translations.
|
* Contains 175 translations.
|
||||||
* Generated on: 2023-04-17 11:34:19
|
* Generated on: 2023-05-17 17:15:34
|
||||||
*/
|
*/
|
||||||
#include "translateObjects.h"
|
#include "translateObjects.h"
|
||||||
|
|
||||||
|
@ -113,6 +113,7 @@ ReturnValue_t AcsBoardPolling::sendMessage(CookieIF* cookie, const uint8_t* send
|
|||||||
if (req->mode != adis.mode) {
|
if (req->mode != adis.mode) {
|
||||||
if (req->mode == acs::SimpleSensorMode::NORMAL) {
|
if (req->mode == acs::SimpleSensorMode::NORMAL) {
|
||||||
adis.type = req->type;
|
adis.type = req->type;
|
||||||
|
adis.decRate = req->cfg.decRateReg;
|
||||||
// The initial countdown is handled by the device handler now.
|
// The initial countdown is handled by the device handler now.
|
||||||
// adis.countdown.setTimeout(adis1650x::START_UP_TIME);
|
// adis.countdown.setTimeout(adis1650x::START_UP_TIME);
|
||||||
if (adis.type == adis1650x::Type::ADIS16507) {
|
if (adis.type == adis1650x::Type::ADIS16507) {
|
||||||
@ -376,6 +377,80 @@ void AcsBoardPolling::gyroL3gHandler(GyroL3g& l3g) {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
ReturnValue_t AcsBoardPolling::writeAdisReg(SpiCookie& cookie) {
|
||||||
|
ReturnValue_t result = returnvalue::OK;
|
||||||
|
int retval = 0;
|
||||||
|
// Prepare transfer
|
||||||
|
int fileDescriptor = 0;
|
||||||
|
std::string device = spiComIF.getSpiDev();
|
||||||
|
UnixFileGuard fileHelper(device, fileDescriptor, O_RDWR, "SpiComIF::sendMessage");
|
||||||
|
if (fileHelper.getOpenResult() != returnvalue::OK) {
|
||||||
|
return spi::OPENING_FILE_FAILED;
|
||||||
|
}
|
||||||
|
spi::SpiModes spiMode = spi::SpiModes::MODE_0;
|
||||||
|
uint32_t spiSpeed = 0;
|
||||||
|
cookie.getSpiParameters(spiMode, spiSpeed, nullptr);
|
||||||
|
spiComIF.setSpiSpeedAndMode(fileDescriptor, spiMode, spiSpeed);
|
||||||
|
cookie.assignWriteBuffer(cmdBuf.data());
|
||||||
|
cookie.setTransferSize(2);
|
||||||
|
|
||||||
|
gpioId_t gpioId = cookie.getChipSelectPin();
|
||||||
|
MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING;
|
||||||
|
uint32_t timeoutMs = 0;
|
||||||
|
MutexIF* mutex = spiComIF.getCsMutex();
|
||||||
|
cookie.getMutexParams(timeoutType, timeoutMs);
|
||||||
|
if (mutex == nullptr) {
|
||||||
|
sif::warning << "GyroADIS16507Handler::spiSendCallback: "
|
||||||
|
"Mutex or GPIO interface invalid"
|
||||||
|
<< std::endl;
|
||||||
|
return returnvalue::FAILED;
|
||||||
|
}
|
||||||
|
|
||||||
|
size_t idx = 0;
|
||||||
|
spi_ioc_transfer* transferStruct = cookie.getTransferStructHandle();
|
||||||
|
uint64_t origTx = transferStruct->tx_buf;
|
||||||
|
uint64_t origRx = transferStruct->rx_buf;
|
||||||
|
for (idx = 0; idx < 4; idx += 2) {
|
||||||
|
result = mutex->lockMutex(timeoutType, timeoutMs);
|
||||||
|
if (result != returnvalue::OK) {
|
||||||
|
#if FSFW_CPP_OSTREAM_ENABLED == 1
|
||||||
|
sif::error << "AcsBoardPolling: Failed to lock mutex" << std::endl;
|
||||||
|
#endif
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
// Pull SPI CS low. For now, no support for active high given
|
||||||
|
if (gpioId != gpio::NO_GPIO) {
|
||||||
|
gpioIF.pullLow(gpioId);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Execute transfer
|
||||||
|
// Initiate a full duplex SPI transfer.
|
||||||
|
retval = ioctl(fileDescriptor, SPI_IOC_MESSAGE(1), cookie.getTransferStructHandle());
|
||||||
|
if (retval < 0) {
|
||||||
|
utility::handleIoctlError("SpiComIF::sendMessage: ioctl error.");
|
||||||
|
result = spi::FULL_DUPLEX_TRANSFER_FAILED;
|
||||||
|
}
|
||||||
|
#if FSFW_HAL_SPI_WIRETAPPING == 1
|
||||||
|
comIf->performSpiWiretapping(cookie);
|
||||||
|
#endif /* FSFW_LINUX_SPI_WIRETAPPING == 1 */
|
||||||
|
|
||||||
|
if (gpioId != gpio::NO_GPIO) {
|
||||||
|
gpioIF.pullHigh(gpioId);
|
||||||
|
}
|
||||||
|
mutex->unlockMutex();
|
||||||
|
|
||||||
|
transferStruct->tx_buf += 2;
|
||||||
|
transferStruct->rx_buf += 2;
|
||||||
|
if (idx < 4) {
|
||||||
|
usleep(adis1650x::STALL_TIME_MICROSECONDS);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
transferStruct->tx_buf = origTx;
|
||||||
|
transferStruct->rx_buf = origRx;
|
||||||
|
cookie.setTransferSize(0);
|
||||||
|
return returnvalue::OK;
|
||||||
|
}
|
||||||
|
|
||||||
ReturnValue_t AcsBoardPolling::readAdisCfg(SpiCookie& cookie, size_t transferLen) {
|
ReturnValue_t AcsBoardPolling::readAdisCfg(SpiCookie& cookie, size_t transferLen) {
|
||||||
ReturnValue_t result = returnvalue::OK;
|
ReturnValue_t result = returnvalue::OK;
|
||||||
int retval = 0;
|
int retval = 0;
|
||||||
@ -455,15 +530,20 @@ void AcsBoardPolling::gyroAdisHandler(GyroAdis& gyro) {
|
|||||||
ReturnValue_t result;
|
ReturnValue_t result;
|
||||||
acs::SimpleSensorMode mode = acs::SimpleSensorMode::OFF;
|
acs::SimpleSensorMode mode = acs::SimpleSensorMode::OFF;
|
||||||
bool mustPerformStartup = false;
|
bool mustPerformStartup = false;
|
||||||
|
uint16_t decRate = 0;
|
||||||
{
|
{
|
||||||
MutexGuard mg(ipcLock, LOCK_TYPE, LOCK_TIMEOUT, LOCK_CTX);
|
MutexGuard mg(ipcLock, LOCK_TYPE, LOCK_TIMEOUT, LOCK_CTX);
|
||||||
mode = gyro.mode;
|
mode = gyro.mode;
|
||||||
|
decRate = gyro.decRate;
|
||||||
mustPerformStartup = gyro.performStartup;
|
mustPerformStartup = gyro.performStartup;
|
||||||
}
|
}
|
||||||
if (mode == acs::SimpleSensorMode::OFF) {
|
if (mode == acs::SimpleSensorMode::OFF) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
if (mustPerformStartup) {
|
if (mustPerformStartup) {
|
||||||
|
adis1650x::prepareWriteRegCommand(adis1650x::DEC_RATE_REG, decRate, cmdBuf.data(),
|
||||||
|
cmdBuf.size());
|
||||||
|
writeAdisReg(*gyro.cookie);
|
||||||
uint8_t regList[6];
|
uint8_t regList[6];
|
||||||
// Read configuration
|
// Read configuration
|
||||||
regList[0] = adis1650x::DIAG_STAT_REG;
|
regList[0] = adis1650x::DIAG_STAT_REG;
|
||||||
@ -491,13 +571,19 @@ void AcsBoardPolling::gyroAdisHandler(GyroAdis& gyro) {
|
|||||||
gyro.replyResult = returnvalue::FAILED;
|
gyro.replyResult = returnvalue::FAILED;
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
uint16_t decRateReadBack = (rawReply[10] << 8) | rawReply[11];
|
||||||
|
if (decRateReadBack != decRate) {
|
||||||
|
sif::warning << "AcsPollingTask: DEC rate configuration failed. Read " << decRateReadBack
|
||||||
|
<< ", expected " << decRate << std::endl;
|
||||||
|
gyro.replyResult = returnvalue::FAILED;
|
||||||
|
}
|
||||||
MutexGuard mg(ipcLock, LOCK_TYPE, LOCK_TIMEOUT, LOCK_CTX);
|
MutexGuard mg(ipcLock, LOCK_TYPE, LOCK_TIMEOUT, LOCK_CTX);
|
||||||
gyro.ownReply.cfgWasSet = true;
|
gyro.ownReply.cfgWasSet = true;
|
||||||
gyro.ownReply.cfg.diagStat = (rawReply[2] << 8) | rawReply[3];
|
gyro.ownReply.cfg.diagStat = (rawReply[2] << 8) | rawReply[3];
|
||||||
gyro.ownReply.cfg.filterSetting = (rawReply[4] << 8) | rawReply[5];
|
gyro.ownReply.cfg.filterSetting = (rawReply[4] << 8) | rawReply[5];
|
||||||
gyro.ownReply.cfg.rangMdl = (rawReply[6] << 8) | rawReply[7];
|
gyro.ownReply.cfg.rangMdl = (rawReply[6] << 8) | rawReply[7];
|
||||||
gyro.ownReply.cfg.mscCtrlReg = (rawReply[8] << 8) | rawReply[9];
|
gyro.ownReply.cfg.mscCtrlReg = (rawReply[8] << 8) | rawReply[9];
|
||||||
gyro.ownReply.cfg.decRateReg = (rawReply[10] << 8) | rawReply[11];
|
gyro.ownReply.cfg.decRateReg = decRateReadBack;
|
||||||
gyro.ownReply.cfg.prodId = prodId;
|
gyro.ownReply.cfg.prodId = prodId;
|
||||||
gyro.ownReply.data.sensitivity = adis1650x::rangMdlToSensitivity(gyro.ownReply.cfg.rangMdl);
|
gyro.ownReply.data.sensitivity = adis1650x::rangMdlToSensitivity(gyro.ownReply.cfg.rangMdl);
|
||||||
gyro.performStartup = false;
|
gyro.performStartup = false;
|
||||||
|
@ -37,6 +37,7 @@ class AcsBoardPolling : public SystemObject,
|
|||||||
|
|
||||||
struct GyroAdis : public DevBase {
|
struct GyroAdis : public DevBase {
|
||||||
adis1650x::Type type;
|
adis1650x::Type type;
|
||||||
|
uint16_t decRate;
|
||||||
Countdown countdown;
|
Countdown countdown;
|
||||||
acs::Adis1650XReply ownReply;
|
acs::Adis1650XReply ownReply;
|
||||||
acs::Adis1650XReply readerReply;
|
acs::Adis1650XReply readerReply;
|
||||||
@ -84,6 +85,8 @@ class AcsBoardPolling : public SystemObject,
|
|||||||
void gyroAdisHandler(GyroAdis& gyro);
|
void gyroAdisHandler(GyroAdis& gyro);
|
||||||
void mgmLis3Handler(MgmLis3& mgm);
|
void mgmLis3Handler(MgmLis3& mgm);
|
||||||
void mgmRm3100Handler(MgmRm3100& mgm);
|
void mgmRm3100Handler(MgmRm3100& mgm);
|
||||||
|
// This fumction configures the register as specified on p.21 of the datasheet.
|
||||||
|
ReturnValue_t writeAdisReg(SpiCookie& cookie);
|
||||||
// Special readout: 16us stall time between small 2 byte transfers.
|
// Special readout: 16us stall time between small 2 byte transfers.
|
||||||
ReturnValue_t readAdisCfg(SpiCookie& spiCookie, size_t transferLen);
|
ReturnValue_t readAdisCfg(SpiCookie& spiCookie, size_t transferLen);
|
||||||
};
|
};
|
||||||
|
@ -1,7 +1,7 @@
|
|||||||
/**
|
/**
|
||||||
* @brief Auto-generated event translation file. Contains 291 translations.
|
* @brief Auto-generated event translation file. Contains 295 translations.
|
||||||
* @details
|
* @details
|
||||||
* Generated on: 2023-04-17 11:34:19
|
* Generated on: 2023-05-17 17:15:34
|
||||||
*/
|
*/
|
||||||
#include "translateEvents.h"
|
#include "translateEvents.h"
|
||||||
|
|
||||||
@ -197,6 +197,10 @@ const char *MPSOC_EXE_INVALID_APID_STRING = "MPSOC_EXE_INVALID_APID";
|
|||||||
const char *MPSOC_HELPER_SEQ_CNT_MISMATCH_STRING = "MPSOC_HELPER_SEQ_CNT_MISMATCH";
|
const char *MPSOC_HELPER_SEQ_CNT_MISMATCH_STRING = "MPSOC_HELPER_SEQ_CNT_MISMATCH";
|
||||||
const char *MPSOC_TM_SIZE_ERROR_STRING = "MPSOC_TM_SIZE_ERROR";
|
const char *MPSOC_TM_SIZE_ERROR_STRING = "MPSOC_TM_SIZE_ERROR";
|
||||||
const char *MPSOC_TM_CRC_MISSMATCH_STRING = "MPSOC_TM_CRC_MISSMATCH";
|
const char *MPSOC_TM_CRC_MISSMATCH_STRING = "MPSOC_TM_CRC_MISSMATCH";
|
||||||
|
const char *MPSOC_FLASH_READ_PACKET_ERROR_STRING = "MPSOC_FLASH_READ_PACKET_ERROR";
|
||||||
|
const char *MPSOC_FLASH_READ_FAILED_STRING = "MPSOC_FLASH_READ_FAILED";
|
||||||
|
const char *MPSOC_FLASH_READ_SUCCESSFUL_STRING = "MPSOC_FLASH_READ_SUCCESSFUL";
|
||||||
|
const char *MPSOC_READ_TIMEOUT_STRING = "MPSOC_READ_TIMEOUT";
|
||||||
const char *TRANSITION_BACK_TO_OFF_STRING = "TRANSITION_BACK_TO_OFF";
|
const char *TRANSITION_BACK_TO_OFF_STRING = "TRANSITION_BACK_TO_OFF";
|
||||||
const char *NEG_V_OUT_OF_BOUNDS_STRING = "NEG_V_OUT_OF_BOUNDS";
|
const char *NEG_V_OUT_OF_BOUNDS_STRING = "NEG_V_OUT_OF_BOUNDS";
|
||||||
const char *U_DRO_OUT_OF_BOUNDS_STRING = "U_DRO_OUT_OF_BOUNDS";
|
const char *U_DRO_OUT_OF_BOUNDS_STRING = "U_DRO_OUT_OF_BOUNDS";
|
||||||
@ -683,6 +687,14 @@ const char *translateEvents(Event event) {
|
|||||||
return MPSOC_TM_SIZE_ERROR_STRING;
|
return MPSOC_TM_SIZE_ERROR_STRING;
|
||||||
case (12613):
|
case (12613):
|
||||||
return MPSOC_TM_CRC_MISSMATCH_STRING;
|
return MPSOC_TM_CRC_MISSMATCH_STRING;
|
||||||
|
case (12614):
|
||||||
|
return MPSOC_FLASH_READ_PACKET_ERROR_STRING;
|
||||||
|
case (12615):
|
||||||
|
return MPSOC_FLASH_READ_FAILED_STRING;
|
||||||
|
case (12616):
|
||||||
|
return MPSOC_FLASH_READ_SUCCESSFUL_STRING;
|
||||||
|
case (12617):
|
||||||
|
return MPSOC_READ_TIMEOUT_STRING;
|
||||||
case (12700):
|
case (12700):
|
||||||
return TRANSITION_BACK_TO_OFF_STRING;
|
return TRANSITION_BACK_TO_OFF_STRING;
|
||||||
case (12701):
|
case (12701):
|
||||||
|
@ -2,7 +2,7 @@
|
|||||||
* @brief Auto-generated object translation file.
|
* @brief Auto-generated object translation file.
|
||||||
* @details
|
* @details
|
||||||
* Contains 175 translations.
|
* Contains 175 translations.
|
||||||
* Generated on: 2023-04-17 11:34:19
|
* Generated on: 2023-05-17 17:15:34
|
||||||
*/
|
*/
|
||||||
#include "translateObjects.h"
|
#include "translateObjects.h"
|
||||||
|
|
||||||
|
@ -2,7 +2,8 @@ target_sources(
|
|||||||
${OBSW_NAME}
|
${OBSW_NAME}
|
||||||
PUBLIC PlocMemoryDumper.cpp
|
PUBLIC PlocMemoryDumper.cpp
|
||||||
PlocMpsocHandler.cpp
|
PlocMpsocHandler.cpp
|
||||||
PlocMpsocHelper.cpp
|
PlocMpsocSpecialComHelper.cpp
|
||||||
|
plocMpsocHelpers.cpp
|
||||||
PlocSupervisorHandler.cpp
|
PlocSupervisorHandler.cpp
|
||||||
PlocSupvUartMan.cpp
|
PlocSupvUartMan.cpp
|
||||||
ScexDleParser.cpp
|
ScexDleParser.cpp
|
||||||
|
File diff suppressed because it is too large
Load Diff
@ -1,9 +1,9 @@
|
|||||||
#ifndef BSP_Q7S_DEVICES_PLOC_PLOCMPSOCHANDLER_H_
|
#ifndef BSP_Q7S_DEVICES_PLOC_PLOCMPSOCHANDLER_H_
|
||||||
#define BSP_Q7S_DEVICES_PLOC_PLOCMPSOCHANDLER_H_
|
#define BSP_Q7S_DEVICES_PLOC_PLOCMPSOCHANDLER_H_
|
||||||
|
|
||||||
#include <linux/payload/PlocMpsocHelper.h>
|
#include <linux/payload/PlocMpsocSpecialComHelper.h>
|
||||||
#include <linux/payload/mpsocRetvals.h>
|
#include <linux/payload/mpsocRetvals.h>
|
||||||
#include <linux/payload/plocMpscoDefs.h>
|
#include <linux/payload/plocMpsocHelpers.h>
|
||||||
#include <linux/payload/plocSupvDefs.h>
|
#include <linux/payload/plocSupvDefs.h>
|
||||||
|
|
||||||
#include <string>
|
#include <string>
|
||||||
@ -28,9 +28,10 @@
|
|||||||
* @note The sequence count in the space packets must be incremented with each received and sent
|
* @note The sequence count in the space packets must be incremented with each received and sent
|
||||||
* packet otherwise the MPSoC will reply with an acknowledgment failure report.
|
* packet otherwise the MPSoC will reply with an acknowledgment failure report.
|
||||||
*
|
*
|
||||||
* @author J. Meier
|
* NOTE: This is not an example for a good device handler, DO NOT USE THIS AS A REFERENCE HANDLER.
|
||||||
|
|||||||
|
* @author J. Meier, R. Mueller
|
||||||
*/
|
*/
|
||||||
class PlocMPSoCHandler : public DeviceHandlerBase, public CommandsActionsIF {
|
class PlocMpsocHandler : public DeviceHandlerBase, public CommandsActionsIF {
|
||||||
public:
|
public:
|
||||||
/**
|
/**
|
||||||
* @brief Constructor
|
* @brief Constructor
|
||||||
@ -43,10 +44,10 @@ class PlocMPSoCHandler : public DeviceHandlerBase, public CommandsActionsIF {
|
|||||||
* module in the programmable logic
|
* module in the programmable logic
|
||||||
* @param supervisorHandler Object ID of the supervisor handler
|
* @param supervisorHandler Object ID of the supervisor handler
|
||||||
*/
|
*/
|
||||||
PlocMPSoCHandler(object_id_t objectId, object_id_t uartComIFid, CookieIF* comCookie,
|
PlocMpsocHandler(object_id_t objectId, object_id_t uartComIFid, CookieIF* comCookie,
|
||||||
PlocMPSoCHelper* plocMPSoCHelper, Gpio uartIsolatorSwitch,
|
PlocMpsocSpecialComHelper* plocMPSoCHelper, Gpio uartIsolatorSwitch,
|
||||||
object_id_t supervisorHandler);
|
object_id_t supervisorHandler);
|
||||||
virtual ~PlocMPSoCHandler();
|
virtual ~PlocMpsocHandler();
|
||||||
virtual ReturnValue_t initialize() override;
|
virtual ReturnValue_t initialize() override;
|
||||||
ReturnValue_t executeAction(ActionId_t actionId, MessageQueueId_t commandedBy,
|
ReturnValue_t executeAction(ActionId_t actionId, MessageQueueId_t commandedBy,
|
||||||
const uint8_t* data, size_t size) override;
|
const uint8_t* data, size_t size) override;
|
||||||
@ -77,7 +78,9 @@ class PlocMPSoCHandler : public DeviceHandlerBase, public CommandsActionsIF {
|
|||||||
uint8_t expectedReplies = 1, bool useAlternateId = false,
|
uint8_t expectedReplies = 1, bool useAlternateId = false,
|
||||||
DeviceCommandId_t alternateReplyID = 0) override;
|
DeviceCommandId_t alternateReplyID = 0) override;
|
||||||
size_t getNextReplyLength(DeviceCommandId_t deviceCommand) override;
|
size_t getNextReplyLength(DeviceCommandId_t deviceCommand) override;
|
||||||
virtual ReturnValue_t doSendReadHook() override;
|
ReturnValue_t doSendReadHook() override;
|
||||||
|
LocalPoolDataSetBase* getDataSetHandle(sid_t sid) override;
|
||||||
|
bool dontCheckQueue() override;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::PLOC_MPSOC_HANDLER;
|
static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::PLOC_MPSOC_HANDLER;
|
||||||
@ -103,7 +106,8 @@ class PlocMPSoCHandler : public DeviceHandlerBase, public CommandsActionsIF {
|
|||||||
|
|
||||||
static const uint16_t APID_MASK = 0x7FF;
|
static const uint16_t APID_MASK = 0x7FF;
|
||||||
static const uint16_t PACKET_SEQUENCE_COUNT_MASK = 0x3FFF;
|
static const uint16_t PACKET_SEQUENCE_COUNT_MASK = 0x3FFF;
|
||||||
static const uint8_t STATUS_OFFSET = 10;
|
|
||||||
|
mpsoc::HkReport hkReport;
|
||||||
|
|
||||||
MessageQueueIF* eventQueue = nullptr;
|
MessageQueueIF* eventQueue = nullptr;
|
||||||
MessageQueueIF* commandActionHelperQueue = nullptr;
|
MessageQueueIF* commandActionHelperQueue = nullptr;
|
||||||
@ -114,6 +118,41 @@ class PlocMPSoCHandler : public DeviceHandlerBase, public CommandsActionsIF {
|
|||||||
SpacePacketCreator creator;
|
SpacePacketCreator creator;
|
||||||
ploc::SpTcParams spParams = ploc::SpTcParams(creator);
|
ploc::SpTcParams spParams = ploc::SpTcParams(creator);
|
||||||
|
|
||||||
|
PoolEntry<uint32_t> peStatus = PoolEntry<uint32_t>();
|
||||||
|
PoolEntry<uint8_t> peMode = PoolEntry<uint8_t>();
|
||||||
|
PoolEntry<uint8_t> peDownlinkPwrOn = PoolEntry<uint8_t>();
|
||||||
|
PoolEntry<uint8_t> peDownlinkReplyActive = PoolEntry<uint8_t>();
|
||||||
|
PoolEntry<uint8_t> peDownlinkJesdSyncStatus = PoolEntry<uint8_t>();
|
||||||
|
PoolEntry<uint8_t> peDownlinkDacStatus = PoolEntry<uint8_t>();
|
||||||
|
PoolEntry<uint8_t> peCameraStatus = PoolEntry<uint8_t>();
|
||||||
|
PoolEntry<uint8_t> peCameraSdiStatus = PoolEntry<uint8_t>();
|
||||||
|
PoolEntry<float> peCameraFpgaTemp = PoolEntry<float>();
|
||||||
|
PoolEntry<float> peCameraSocTemp = PoolEntry<float>();
|
||||||
|
PoolEntry<float> peSysmonTemp = PoolEntry<float>();
|
||||||
|
PoolEntry<float> peSysmonVccInt = PoolEntry<float>();
|
||||||
|
PoolEntry<float> peSysmonVccAux = PoolEntry<float>();
|
||||||
|
PoolEntry<float> peSysmonVccBram = PoolEntry<float>();
|
||||||
|
PoolEntry<float> peSysmonVccPaux = PoolEntry<float>();
|
||||||
|
PoolEntry<float> peSysmonVccPint = PoolEntry<float>();
|
||||||
|
PoolEntry<float> peSysmonVccPdro = PoolEntry<float>();
|
||||||
|
PoolEntry<float> peSysmonMb12V = PoolEntry<float>();
|
||||||
|
PoolEntry<float> peSysmonMb3V3 = PoolEntry<float>();
|
||||||
|
PoolEntry<float> peSysmonMb1V8 = PoolEntry<float>();
|
||||||
|
PoolEntry<float> peSysmonVcc12V = PoolEntry<float>();
|
||||||
|
PoolEntry<float> peSysmonVcc5V = PoolEntry<float>();
|
||||||
|
PoolEntry<float> peSysmonVcc3V3 = PoolEntry<float>();
|
||||||
|
PoolEntry<float> peSysmonVcc3V3VA = PoolEntry<float>();
|
||||||
|
PoolEntry<float> peSysmonVcc2V5DDR = PoolEntry<float>();
|
||||||
|
PoolEntry<float> peSysmonVcc1V2DDR = PoolEntry<float>();
|
||||||
|
PoolEntry<float> peSysmonVcc0V9 = PoolEntry<float>();
|
||||||
|
PoolEntry<float> peSysmonVcc0V6VTT = PoolEntry<float>();
|
||||||
|
PoolEntry<float> peSysmonSafeCotsCur = PoolEntry<float>();
|
||||||
|
PoolEntry<float> peSysmonNvm4XoCur = PoolEntry<float>();
|
||||||
|
PoolEntry<uint16_t> peSemUncorrectableErrs = PoolEntry<uint16_t>();
|
||||||
|
PoolEntry<uint16_t> peSemCorrectableErrs = PoolEntry<uint16_t>();
|
||||||
|
PoolEntry<uint8_t> peSemStatus = PoolEntry<uint8_t>();
|
||||||
|
PoolEntry<uint8_t> peRebootMpsocRequired = PoolEntry<uint8_t>();
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* This variable is used to store the id of the next reply to receive. This is necessary
|
* This variable is used to store the id of the next reply to receive. This is necessary
|
||||||
* because the PLOC sends as reply to each command at least one acknowledgment and execution
|
* because the PLOC sends as reply to each command at least one acknowledgment and execution
|
||||||
@ -123,13 +162,14 @@ class PlocMPSoCHandler : public DeviceHandlerBase, public CommandsActionsIF {
|
|||||||
|
|
||||||
SerialComIF* uartComIf = nullptr;
|
SerialComIF* uartComIf = nullptr;
|
||||||
|
|
||||||
PlocMPSoCHelper* plocMPSoCHelper = nullptr;
|
PlocMpsocSpecialComHelper* specialComHelper = nullptr;
|
||||||
Gpio uartIsolatorSwitch;
|
Gpio uartIsolatorSwitch;
|
||||||
object_id_t supervisorHandler = 0;
|
object_id_t supervisorHandler = 0;
|
||||||
CommandActionHelper commandActionHelper;
|
CommandActionHelper commandActionHelper;
|
||||||
|
|
||||||
// Used to block incoming commands when MPSoC helper class is currently executing a command
|
// Used to block incoming commands when MPSoC helper class is currently executing a command
|
||||||
bool plocMPSoCHelperExecuting = false;
|
bool specialComHelperExecuting = false;
|
||||||
|
bool commandIsPending = false;
|
||||||
|
|
||||||
struct TmMemReadReport {
|
struct TmMemReadReport {
|
||||||
static const uint8_t FIX_SIZE = 14;
|
static const uint8_t FIX_SIZE = 14;
|
||||||
@ -137,20 +177,18 @@ class PlocMPSoCHandler : public DeviceHandlerBase, public CommandsActionsIF {
|
|||||||
};
|
};
|
||||||
|
|
||||||
TmMemReadReport tmMemReadReport;
|
TmMemReadReport tmMemReadReport;
|
||||||
|
Countdown cmdCountdown = Countdown(10000);
|
||||||
struct TmCamCmdRpt {
|
|
||||||
size_t rememberSpacePacketSize = 0;
|
|
||||||
};
|
|
||||||
|
|
||||||
TmCamCmdRpt tmCamCmdRpt;
|
|
||||||
|
|
||||||
struct TelemetryBuffer {
|
struct TelemetryBuffer {
|
||||||
uint16_t length = 0;
|
uint16_t length = 0;
|
||||||
uint8_t buffer[mpsoc::SP_MAX_SIZE];
|
uint8_t buffer[mpsoc::SP_MAX_SIZE];
|
||||||
};
|
};
|
||||||
|
|
||||||
|
size_t foundPacketLen = 0;
|
||||||
TelemetryBuffer tmBuffer;
|
TelemetryBuffer tmBuffer;
|
||||||
|
uint32_t waitCycles = 0;
|
||||||
|
|
||||||
|
enum class StartupState { IDLE, HW_INIT, WAIT_CYCLES, DONE } startupState = StartupState::IDLE;
|
||||||
enum class PowerState { OFF, BOOTING, SHUTDOWN, ON };
|
enum class PowerState { OFF, BOOTING, SHUTDOWN, ON };
|
||||||
|
|
||||||
PowerState powerState = PowerState::OFF;
|
PowerState powerState = PowerState::OFF;
|
||||||
@ -167,6 +205,8 @@ class PlocMPSoCHandler : public DeviceHandlerBase, public CommandsActionsIF {
|
|||||||
ReturnValue_t prepareTcReplayStop();
|
ReturnValue_t prepareTcReplayStop();
|
||||||
ReturnValue_t prepareTcDownlinkPwrOn(const uint8_t* commandData, size_t commandDataLen);
|
ReturnValue_t prepareTcDownlinkPwrOn(const uint8_t* commandData, size_t commandDataLen);
|
||||||
ReturnValue_t prepareTcDownlinkPwrOff();
|
ReturnValue_t prepareTcDownlinkPwrOff();
|
||||||
|
ReturnValue_t prepareTcGetHkReport();
|
||||||
|
ReturnValue_t prepareTcGetDirContent(const uint8_t* commandData, size_t commandDataLen);
|
||||||
ReturnValue_t prepareTcReplayWriteSequence(const uint8_t* commandData, size_t commandDataLen);
|
ReturnValue_t prepareTcReplayWriteSequence(const uint8_t* commandData, size_t commandDataLen);
|
||||||
ReturnValue_t prepareTcCamCmdSend(const uint8_t* commandData, size_t commandDataLen);
|
ReturnValue_t prepareTcCamCmdSend(const uint8_t* commandData, size_t commandDataLen);
|
||||||
ReturnValue_t prepareTcModeIdle();
|
ReturnValue_t prepareTcModeIdle();
|
||||||
@ -174,7 +214,7 @@ class PlocMPSoCHandler : public DeviceHandlerBase, public CommandsActionsIF {
|
|||||||
ReturnValue_t prepareTcSimplexSendFile(const uint8_t* commandData, size_t commandDataLen);
|
ReturnValue_t prepareTcSimplexSendFile(const uint8_t* commandData, size_t commandDataLen);
|
||||||
ReturnValue_t prepareTcDownlinkDataModulate(const uint8_t* commandData, size_t commandDataLen);
|
ReturnValue_t prepareTcDownlinkDataModulate(const uint8_t* commandData, size_t commandDataLen);
|
||||||
ReturnValue_t prepareTcModeSnapshot();
|
ReturnValue_t prepareTcModeSnapshot();
|
||||||
void finishTcPrep(size_t packetLen);
|
ReturnValue_t finishTcPrep(mpsoc::TcBase& tcBase);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief This function checks the crc of the received PLOC reply.
|
* @brief This function checks the crc of the received PLOC reply.
|
||||||
@ -213,6 +253,7 @@ class PlocMPSoCHandler : public DeviceHandlerBase, public CommandsActionsIF {
|
|||||||
*/
|
*/
|
||||||
ReturnValue_t handleMemoryReadReport(const uint8_t* data);
|
ReturnValue_t handleMemoryReadReport(const uint8_t* data);
|
||||||
|
|
||||||
|
ReturnValue_t handleGetHkReport(const uint8_t* data);
|
||||||
ReturnValue_t handleCamCmdRpt(const uint8_t* data);
|
ReturnValue_t handleCamCmdRpt(const uint8_t* data);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@ -231,7 +272,7 @@ class PlocMPSoCHandler : public DeviceHandlerBase, public CommandsActionsIF {
|
|||||||
* @param dataSize Size of telemetry in bytes.
|
* @param dataSize Size of telemetry in bytes.
|
||||||
* @param replyId Id of the reply. This will be added to the ActionMessage.
|
* @param replyId Id of the reply. This will be added to the ActionMessage.
|
||||||
*/
|
*/
|
||||||
void handleDeviceTM(const uint8_t* data, size_t dataSize, DeviceCommandId_t replyId);
|
void handleDeviceTm(const uint8_t* data, size_t dataSize, DeviceCommandId_t replyId);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief In case an acknowledgment failure reply has been received this function disables
|
* @brief In case an acknowledgment failure reply has been received this function disables
|
||||||
@ -255,15 +296,11 @@ class PlocMPSoCHandler : public DeviceHandlerBase, public CommandsActionsIF {
|
|||||||
*/
|
*/
|
||||||
void disableExeReportReply();
|
void disableExeReportReply();
|
||||||
|
|
||||||
void printStatus(const uint8_t* data);
|
|
||||||
|
|
||||||
ReturnValue_t prepareTcModeReplay();
|
ReturnValue_t prepareTcModeReplay();
|
||||||
|
|
||||||
uint16_t getStatus(const uint8_t* data);
|
void cmdDoneHandler(bool success, ReturnValue_t result);
|
||||||
|
|
||||||
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_ */
|
||||||
|
@ -1,355 +0,0 @@
|
|||||||
#include <linux/payload/PlocMpsocHelper.h>
|
|
||||||
|
|
||||||
#include <filesystem>
|
|
||||||
#include <fstream>
|
|
||||||
|
|
||||||
#ifdef XIPHOS_Q7S
|
|
||||||
#include "bsp_q7s/fs/FilesystemHelper.h"
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#include "mission/utility/Timestamp.h"
|
|
||||||
|
|
||||||
using namespace ploc;
|
|
||||||
|
|
||||||
PlocMPSoCHelper::PlocMPSoCHelper(object_id_t objectId) : SystemObject(objectId) {
|
|
||||||
spParams.buf = commandBuffer;
|
|
||||||
spParams.maxSize = sizeof(commandBuffer);
|
|
||||||
}
|
|
||||||
|
|
||||||
PlocMPSoCHelper::~PlocMPSoCHelper() {}
|
|
||||||
|
|
||||||
ReturnValue_t PlocMPSoCHelper::initialize() {
|
|
||||||
#ifdef XIPHOS_Q7S
|
|
||||||
sdcMan = SdCardManager::instance();
|
|
||||||
if (sdcMan == nullptr) {
|
|
||||||
sif::warning << "PlocMPSoCHelper::initialize: Invalid SD Card Manager" << std::endl;
|
|
||||||
return returnvalue::FAILED;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
return returnvalue::OK;
|
|
||||||
}
|
|
||||||
|
|
||||||
ReturnValue_t PlocMPSoCHelper::performOperation(uint8_t operationCode) {
|
|
||||||
ReturnValue_t result = returnvalue::OK;
|
|
||||||
semaphore.acquire();
|
|
||||||
while (true) {
|
|
||||||
#if OBSW_THREAD_TRACING == 1
|
|
||||||
trace::threadTrace(opCounter, "PLOC MPSOC Helper");
|
|
||||||
#endif
|
|
||||||
switch (internalState) {
|
|
||||||
case InternalState::IDLE: {
|
|
||||||
semaphore.acquire();
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
case InternalState::FLASH_WRITE: {
|
|
||||||
result = performFlashWrite();
|
|
||||||
if (result == returnvalue::OK) {
|
|
||||||
triggerEvent(MPSOC_FLASH_WRITE_SUCCESSFUL);
|
|
||||||
} else {
|
|
||||||
triggerEvent(MPSOC_FLASH_WRITE_FAILED);
|
|
||||||
}
|
|
||||||
internalState = InternalState::IDLE;
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
default:
|
|
||||||
sif::debug << "PlocMPSoCHelper::performOperation: Invalid state" << std::endl;
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
ReturnValue_t PlocMPSoCHelper::setComIF(DeviceCommunicationIF* communicationInterface_) {
|
|
||||||
uartComIF = dynamic_cast<SerialComIF*>(communicationInterface_);
|
|
||||||
if (uartComIF == nullptr) {
|
|
||||||
sif::warning << "PlocMPSoCHelper::initialize: Invalid uart com if" << std::endl;
|
|
||||||
return returnvalue::FAILED;
|
|
||||||
}
|
|
||||||
return returnvalue::OK;
|
|
||||||
}
|
|
||||||
|
|
||||||
void PlocMPSoCHelper::setComCookie(CookieIF* comCookie_) { comCookie = comCookie_; }
|
|
||||||
|
|
||||||
void PlocMPSoCHelper::setSequenceCount(SourceSequenceCounter* sequenceCount_) {
|
|
||||||
sequenceCount = sequenceCount_;
|
|
||||||
}
|
|
||||||
|
|
||||||
ReturnValue_t PlocMPSoCHelper::startFlashWrite(std::string obcFile, std::string mpsocFile) {
|
|
||||||
ReturnValue_t result = returnvalue::OK;
|
|
||||||
#ifdef XIPHOS_Q7S
|
|
||||||
result = FilesystemHelper::checkPath(obcFile);
|
|
||||||
if (result != returnvalue::OK) {
|
|
||||||
return result;
|
|
||||||
}
|
|
||||||
result = FilesystemHelper::fileExists(mpsocFile);
|
|
||||||
if (result != returnvalue::OK) {
|
|
||||||
return result;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
#ifdef TE0720_1CFA
|
|
||||||
if (not std::filesystem::exists(obcFile)) {
|
|
||||||
sif::warning << "PlocMPSoCHelper::startFlashWrite: File " << obcFile << "does not exist"
|
|
||||||
<< std::endl;
|
|
||||||
return returnvalue::FAILED;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
flashWrite.obcFile = obcFile;
|
|
||||||
flashWrite.mpsocFile = mpsocFile;
|
|
||||||
internalState = InternalState::FLASH_WRITE;
|
|
||||||
result = resetHelper();
|
|
||||||
if (result != returnvalue::OK) {
|
|
||||||
return result;
|
|
||||||
}
|
|
||||||
return result;
|
|
||||||
}
|
|
||||||
|
|
||||||
ReturnValue_t PlocMPSoCHelper::resetHelper() {
|
|
||||||
ReturnValue_t result = returnvalue::OK;
|
|
||||||
semaphore.release();
|
|
||||||
spParams.buf = commandBuffer;
|
|
||||||
terminate = false;
|
|
||||||
result = uartComIF->flushUartRxBuffer(comCookie);
|
|
||||||
return result;
|
|
||||||
}
|
|
||||||
|
|
||||||
void PlocMPSoCHelper::stopProcess() { terminate = true; }
|
|
||||||
|
|
||||||
ReturnValue_t PlocMPSoCHelper::performFlashWrite() {
|
|
||||||
ReturnValue_t result = returnvalue::OK;
|
|
||||||
result = flashfopen();
|
|
||||||
if (result != returnvalue::OK) {
|
|
||||||
return result;
|
|
||||||
}
|
|
||||||
uint8_t tempData[mpsoc::MAX_DATA_SIZE];
|
|
||||||
std::ifstream file(flashWrite.obcFile, std::ifstream::binary);
|
|
||||||
// Set position of next character to end of file input stream
|
|
||||||
file.seekg(0, file.end);
|
|
||||||
// tellg returns position of character in input stream
|
|
||||||
size_t remainingSize = file.tellg();
|
|
||||||
size_t dataLength = 0;
|
|
||||||
size_t bytesRead = 0;
|
|
||||||
while (remainingSize > 0) {
|
|
||||||
if (terminate) {
|
|
||||||
return returnvalue::OK;
|
|
||||||
}
|
|
||||||
if (remainingSize > mpsoc::MAX_DATA_SIZE) {
|
|
||||||
dataLength = mpsoc::MAX_DATA_SIZE;
|
|
||||||
} else {
|
|
||||||
dataLength = remainingSize;
|
|
||||||
}
|
|
||||||
if (file.is_open()) {
|
|
||||||
file.seekg(bytesRead, file.beg);
|
|
||||||
file.read(reinterpret_cast<char*>(tempData), dataLength);
|
|
||||||
bytesRead += dataLength;
|
|
||||||
remainingSize -= dataLength;
|
|
||||||
} else {
|
|
||||||
return FILE_CLOSED_ACCIDENTALLY;
|
|
||||||
}
|
|
||||||
(*sequenceCount)++;
|
|
||||||
mpsoc::TcFlashWrite tc(spParams, *sequenceCount);
|
|
||||||
result = tc.buildPacket(tempData, dataLength);
|
|
||||||
if (result != returnvalue::OK) {
|
|
||||||
return result;
|
|
||||||
}
|
|
||||||
result = handlePacketTransmission(tc);
|
|
||||||
if (result != returnvalue::OK) {
|
|
||||||
return result;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
result = flashfclose();
|
|
||||||
if (result != returnvalue::OK) {
|
|
||||||
return result;
|
|
||||||
}
|
|
||||||
return result;
|
|
||||||
}
|
|
||||||
|
|
||||||
ReturnValue_t PlocMPSoCHelper::flashfopen() {
|
|
||||||
ReturnValue_t result = returnvalue::OK;
|
|
||||||
spParams.buf = commandBuffer;
|
|
||||||
(*sequenceCount)++;
|
|
||||||
mpsoc::FlashFopen flashFopen(spParams, *sequenceCount);
|
|
||||||
result = flashFopen.createPacket(flashWrite.mpsocFile, mpsoc::FlashFopen::APPEND);
|
|
||||||
if (result != returnvalue::OK) {
|
|
||||||
return result;
|
|
||||||
}
|
|
||||||
result = handlePacketTransmission(flashFopen);
|
|
||||||
if (result != returnvalue::OK) {
|
|
||||||
return result;
|
|
||||||
}
|
|
||||||
return returnvalue::OK;
|
|
||||||
}
|
|
||||||
|
|
||||||
ReturnValue_t PlocMPSoCHelper::flashfclose() {
|
|
||||||
ReturnValue_t result = returnvalue::OK;
|
|
||||||
spParams.buf = commandBuffer;
|
|
||||||
(*sequenceCount)++;
|
|
||||||
mpsoc::FlashFclose flashFclose(spParams, *sequenceCount);
|
|
||||||
result = flashFclose.createPacket(flashWrite.mpsocFile);
|
|
||||||
if (result != returnvalue::OK) {
|
|
||||||
return result;
|
|
||||||
}
|
|
||||||
result = handlePacketTransmission(flashFclose);
|
|
||||||
if (result != returnvalue::OK) {
|
|
||||||
return result;
|
|
||||||
}
|
|
||||||
return returnvalue::OK;
|
|
||||||
}
|
|
||||||
|
|
||||||
ReturnValue_t PlocMPSoCHelper::handlePacketTransmission(ploc::SpTcBase& tc) {
|
|
||||||
ReturnValue_t result = returnvalue::OK;
|
|
||||||
result = sendCommand(tc);
|
|
||||||
if (result != returnvalue::OK) {
|
|
||||||
return result;
|
|
||||||
}
|
|
||||||
result = handleAck();
|
|
||||||
if (result != returnvalue::OK) {
|
|
||||||
return result;
|
|
||||||
}
|
|
||||||
result = handleExe();
|
|
||||||
if (result != returnvalue::OK) {
|
|
||||||
return result;
|
|
||||||
}
|
|
||||||
return returnvalue::OK;
|
|
||||||
}
|
|
||||||
|
|
||||||
ReturnValue_t PlocMPSoCHelper::sendCommand(ploc::SpTcBase& tc) {
|
|
||||||
ReturnValue_t result = returnvalue::OK;
|
|
||||||
result = uartComIF->sendMessage(comCookie, tc.getFullPacket(), tc.getFullPacketLen());
|
|
||||||
if (result != returnvalue::OK) {
|
|
||||||
sif::warning << "PlocMPSoCHelper::sendCommand: Failed to send command" << std::endl;
|
|
||||||
triggerEvent(MPSOC_SENDING_COMMAND_FAILED, result, static_cast<uint32_t>(internalState));
|
|
||||||
return result;
|
|
||||||
}
|
|
||||||
return result;
|
|
||||||
}
|
|
||||||
|
|
||||||
ReturnValue_t PlocMPSoCHelper::handleAck() {
|
|
||||||
ReturnValue_t result = returnvalue::OK;
|
|
||||||
result = handleTmReception(mpsoc::SIZE_ACK_REPORT);
|
|
||||||
if (result != returnvalue::OK) {
|
|
||||||
return result;
|
|
||||||
}
|
|
||||||
SpTmReader tmPacket(tmBuf.data(), tmBuf.size());
|
|
||||||
result = checkReceivedTm(tmPacket);
|
|
||||||
if (result != returnvalue::OK) {
|
|
||||||
return result;
|
|
||||||
}
|
|
||||||
uint16_t apid = tmPacket.getApid();
|
|
||||||
if (apid != mpsoc::apid::ACK_SUCCESS) {
|
|
||||||
handleAckApidFailure(apid);
|
|
||||||
return returnvalue::FAILED;
|
|
||||||
}
|
|
||||||
return returnvalue::OK;
|
|
||||||
}
|
|
||||||
|
|
||||||
void PlocMPSoCHelper::handleAckApidFailure(uint16_t apid) {
|
|
||||||
if (apid == mpsoc::apid::ACK_FAILURE) {
|
|
||||||
triggerEvent(MPSOC_ACK_FAILURE_REPORT, static_cast<uint32_t>(internalState));
|
|
||||||
sif::warning << "PlocMPSoCHelper::handleAckApidFailure: Received acknowledgement failure "
|
|
||||||
<< "report" << std::endl;
|
|
||||||
} else {
|
|
||||||
triggerEvent(MPSOC_ACK_INVALID_APID, apid, static_cast<uint32_t>(internalState));
|
|
||||||
sif::warning << "PlocMPSoCHelper::handleAckApidFailure: Expected acknowledgement report "
|
|
||||||
<< "but received space packet with apid " << std::hex << apid << std::endl;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
ReturnValue_t PlocMPSoCHelper::handleExe() {
|
|
||||||
ReturnValue_t result = returnvalue::OK;
|
|
||||||
|
|
||||||
result = handleTmReception(mpsoc::SIZE_EXE_REPORT);
|
|
||||||
if (result != returnvalue::OK) {
|
|
||||||
return result;
|
|
||||||
}
|
|
||||||
ploc::SpTmReader tmPacket(tmBuf.data(), tmBuf.size());
|
|
||||||
result = checkReceivedTm(tmPacket);
|
|
||||||
if (result != returnvalue::OK) {
|
|
||||||
return result;
|
|
||||||
}
|
|
||||||
uint16_t apid = tmPacket.getApid();
|
|
||||||
if (apid != mpsoc::apid::EXE_SUCCESS) {
|
|
||||||
handleExeApidFailure(apid);
|
|
||||||
return returnvalue::FAILED;
|
|
||||||
}
|
|
||||||
return returnvalue::OK;
|
|
||||||
}
|
|
||||||
|
|
||||||
void PlocMPSoCHelper::handleExeApidFailure(uint16_t apid) {
|
|
||||||
if (apid == mpsoc::apid::EXE_FAILURE) {
|
|
||||||
triggerEvent(MPSOC_EXE_FAILURE_REPORT, static_cast<uint32_t>(internalState));
|
|
||||||
sif::warning << "PlocMPSoCHelper::handleExeApidFailure: Received execution failure "
|
|
||||||
<< "report" << std::endl;
|
|
||||||
} else {
|
|
||||||
triggerEvent(MPSOC_EXE_INVALID_APID, apid, static_cast<uint32_t>(internalState));
|
|
||||||
sif::warning << "PlocMPSoCHelper::handleExeApidFailure: Expected execution report "
|
|
||||||
<< "but received space packet with apid " << std::hex << apid << std::endl;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
ReturnValue_t PlocMPSoCHelper::handleTmReception(size_t remainingBytes) {
|
|
||||||
ReturnValue_t result = returnvalue::OK;
|
|
||||||
size_t readBytes = 0;
|
|
||||||
size_t currentBytes = 0;
|
|
||||||
for (int retries = 0; retries < RETRIES; retries++) {
|
|
||||||
result = receive(tmBuf.data() + readBytes, ¤tBytes, remainingBytes);
|
|
||||||
if (result != returnvalue::OK) {
|
|
||||||
return result;
|
|
||||||
}
|
|
||||||
readBytes += currentBytes;
|
|
||||||
remainingBytes = remainingBytes - currentBytes;
|
|
||||||
if (remainingBytes == 0) {
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
if (remainingBytes != 0) {
|
|
||||||
sif::warning << "PlocMPSoCHelper::handleTmReception: Failed to receive reply" << std::endl;
|
|
||||||
triggerEvent(MPSOC_MISSING_EXE, remainingBytes, static_cast<uint32_t>(internalState));
|
|
||||||
return returnvalue::FAILED;
|
|
||||||
}
|
|
||||||
return result;
|
|
||||||
}
|
|
||||||
|
|
||||||
ReturnValue_t PlocMPSoCHelper::checkReceivedTm(SpTmReader& reader) {
|
|
||||||
ReturnValue_t result = reader.checkSize();
|
|
||||||
if (result != returnvalue::OK) {
|
|
||||||
sif::error << "PlocMPSoCHelper::handleTmReception: Size check on received TM failed"
|
|
||||||
<< std::endl;
|
|
||||||
triggerEvent(MPSOC_TM_SIZE_ERROR);
|
|
||||||
return result;
|
|
||||||
}
|
|
||||||
reader.checkCrc();
|
|
||||||
if (result != returnvalue::OK) {
|
|
||||||
sif::warning << "PlocMPSoCHelper::handleTmReception: CRC check failed" << std::endl;
|
|
||||||
triggerEvent(MPSOC_TM_CRC_MISSMATCH, *sequenceCount);
|
|
||||||
return result;
|
|
||||||
}
|
|
||||||
(*sequenceCount)++;
|
|
||||||
uint16_t recvSeqCnt = reader.getSequenceCount();
|
|
||||||
if (recvSeqCnt != *sequenceCount) {
|
|
||||||
triggerEvent(MPSOC_HELPER_SEQ_CNT_MISMATCH, *sequenceCount, recvSeqCnt);
|
|
||||||
*sequenceCount = recvSeqCnt;
|
|
||||||
}
|
|
||||||
return returnvalue::OK;
|
|
||||||
}
|
|
||||||
|
|
||||||
ReturnValue_t PlocMPSoCHelper::receive(uint8_t* data, size_t* readBytes, size_t requestBytes) {
|
|
||||||
ReturnValue_t result = returnvalue::OK;
|
|
||||||
uint8_t* buffer = nullptr;
|
|
||||||
result = uartComIF->requestReceiveMessage(comCookie, requestBytes);
|
|
||||||
if (result != returnvalue::OK) {
|
|
||||||
sif::warning << "PlocMPSoCHelper::receive: Failed to request reply" << std::endl;
|
|
||||||
triggerEvent(MPSOC_HELPER_REQUESTING_REPLY_FAILED, result,
|
|
||||||
static_cast<uint32_t>(static_cast<uint32_t>(internalState)));
|
|
||||||
return returnvalue::FAILED;
|
|
||||||
}
|
|
||||||
result = uartComIF->readReceivedMessage(comCookie, &buffer, readBytes);
|
|
||||||
if (result != returnvalue::OK) {
|
|
||||||
sif::warning << "PlocMPSoCHelper::receive: Failed to read received message" << std::endl;
|
|
||||||
triggerEvent(MPSOC_HELPER_READING_REPLY_FAILED, result, static_cast<uint32_t>(internalState));
|
|
||||||
return returnvalue::FAILED;
|
|
||||||
}
|
|
||||||
if (*readBytes > 0) {
|
|
||||||
std::memcpy(data, buffer, *readBytes);
|
|
||||||
}
|
|
||||||
return result;
|
|
||||||
}
|
|
544
linux/payload/PlocMpsocSpecialComHelper.cpp
Normal file
544
linux/payload/PlocMpsocSpecialComHelper.cpp
Normal file
@ -0,0 +1,544 @@
|
|||||||
|
#include <fsfw/globalfunctions/arrayprinter.h>
|
||||||
|
#include <fsfw/tasks/TaskFactory.h>
|
||||||
|
#include <linux/payload/PlocMpsocSpecialComHelper.h>
|
||||||
|
#include <unistd.h>
|
||||||
|
|
||||||
|
#include <filesystem>
|
||||||
|
#include <fstream>
|
||||||
|
|
||||||
|
#ifdef XIPHOS_Q7S
|
||||||
|
#include "bsp_q7s/fs/FilesystemHelper.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include "mission/utility/Timestamp.h"
|
||||||
|
|
||||||
|
using namespace ploc;
|
||||||
|
|
||||||
|
PlocMpsocSpecialComHelper::PlocMpsocSpecialComHelper(object_id_t objectId)
|
||||||
|
: SystemObject(objectId) {
|
||||||
|
spParams.buf = commandBuffer;
|
||||||
|
spParams.maxSize = sizeof(commandBuffer);
|
||||||
|
}
|
||||||
|
|
||||||
|
PlocMpsocSpecialComHelper::~PlocMpsocSpecialComHelper() {}
|
||||||
|
|
||||||
|
ReturnValue_t PlocMpsocSpecialComHelper::initialize() {
|
||||||
|
#ifdef XIPHOS_Q7S
|
||||||
|
sdcMan = SdCardManager::instance();
|
||||||
|
if (sdcMan == nullptr) {
|
||||||
|
sif::warning << "PlocMPSoCHelper::initialize: Invalid SD Card Manager" << std::endl;
|
||||||
|
return returnvalue::FAILED;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
return returnvalue::OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t PlocMpsocSpecialComHelper::performOperation(uint8_t operationCode) {
|
||||||
|
ReturnValue_t result = returnvalue::OK;
|
||||||
|
semaphore.acquire();
|
||||||
|
while (true) {
|
||||||
|
#if OBSW_THREAD_TRACING == 1
|
||||||
|
trace::threadTrace(opCounter, "PLOC MPSOC Helper");
|
||||||
|
#endif
|
||||||
|
switch (internalState) {
|
||||||
|
case InternalState::IDLE: {
|
||||||
|
semaphore.acquire();
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case InternalState::FLASH_WRITE: {
|
||||||
|
result = performFlashWrite();
|
||||||
|
if (result == returnvalue::OK) {
|
||||||
|
triggerEvent(MPSOC_FLASH_WRITE_SUCCESSFUL, sequenceCount->get());
|
||||||
|
} else {
|
||||||
|
triggerEvent(MPSOC_FLASH_WRITE_FAILED, sequenceCount->get());
|
||||||
|
}
|
||||||
|
internalState = InternalState::IDLE;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case InternalState::FLASH_READ: {
|
||||||
|
result = performFlashRead();
|
||||||
|
if (result == returnvalue::OK) {
|
||||||
|
triggerEvent(MPSOC_FLASH_READ_SUCCESSFUL, sequenceCount->get());
|
||||||
|
} else {
|
||||||
|
triggerEvent(MPSOC_FLASH_READ_FAILED, sequenceCount->get());
|
||||||
|
}
|
||||||
|
internalState = InternalState::IDLE;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
default:
|
||||||
|
sif::debug << "PlocMPSoCHelper::performOperation: Invalid state" << std::endl;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t PlocMpsocSpecialComHelper::setComIF(DeviceCommunicationIF* communicationInterface_) {
|
||||||
|
uartComIF = dynamic_cast<SerialComIF*>(communicationInterface_);
|
||||||
|
if (uartComIF == nullptr) {
|
||||||
|
sif::warning << "PlocMPSoCHelper::initialize: Invalid uart com if" << std::endl;
|
||||||
|
return returnvalue::FAILED;
|
||||||
|
}
|
||||||
|
return returnvalue::OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
void PlocMpsocSpecialComHelper::setComCookie(CookieIF* comCookie_) { comCookie = comCookie_; }
|
||||||
|
|
||||||
|
void PlocMpsocSpecialComHelper::setSequenceCount(SourceSequenceCounter* sequenceCount_) {
|
||||||
|
sequenceCount = sequenceCount_;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t PlocMpsocSpecialComHelper::startFlashWrite(std::string obcFile,
|
||||||
|
std::string mpsocFile) {
|
||||||
|
if (internalState != InternalState::IDLE) {
|
||||||
|
return returnvalue::FAILED;
|
||||||
|
}
|
||||||
|
ReturnValue_t result = startFlashReadOrWriteBase(std::move(obcFile), std::move(mpsocFile));
|
||||||
|
if (result != returnvalue::OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
internalState = InternalState::FLASH_WRITE;
|
||||||
|
return semaphore.release();
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t PlocMpsocSpecialComHelper::startFlashRead(std::string obcFile, std::string mpsocFile,
|
||||||
|
size_t readFileSize) {
|
||||||
|
if (internalState != InternalState::IDLE) {
|
||||||
|
return returnvalue::FAILED;
|
||||||
|
}
|
||||||
|
ReturnValue_t result = startFlashReadOrWriteBase(std::move(obcFile), std::move(mpsocFile));
|
||||||
|
if (result != returnvalue::OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
flashReadAndWrite.totalReadSize = readFileSize;
|
||||||
|
internalState = InternalState::FLASH_READ;
|
||||||
|
return semaphore.release();
|
||||||
|
}
|
||||||
|
|
||||||
|
void PlocMpsocSpecialComHelper::resetHelper() {
|
||||||
|
spParams.buf = commandBuffer;
|
||||||
|
terminate = false;
|
||||||
|
uartComIF->flushUartRxBuffer(comCookie);
|
||||||
|
}
|
||||||
|
|
||||||
|
void PlocMpsocSpecialComHelper::stopProcess() { terminate = true; }
|
||||||
|
|
||||||
|
ReturnValue_t PlocMpsocSpecialComHelper::performFlashWrite() {
|
||||||
|
ReturnValue_t result = returnvalue::OK;
|
||||||
|
std::ifstream file(flashReadAndWrite.obcFile, std::ifstream::binary);
|
||||||
|
if (file.bad()) {
|
||||||
|
return returnvalue::FAILED;
|
||||||
|
}
|
||||||
|
result = flashfopen(mpsoc::FileAccessModes::WRITE | mpsoc::FileAccessModes::OPEN_ALWAYS);
|
||||||
|
if (result != returnvalue::OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
// Set position of next character to end of file input stream
|
||||||
|
file.seekg(0, file.end);
|
||||||
|
// tellg returns position of character in input stream
|
||||||
|
size_t remainingSize = file.tellg();
|
||||||
|
size_t dataLength = 0;
|
||||||
|
size_t bytesRead = 0;
|
||||||
|
while (remainingSize > 0) {
|
||||||
|
if (terminate) {
|
||||||
|
return returnvalue::OK;
|
||||||
|
}
|
||||||
|
// The minus 4 is necessary for unknown reasons. Maybe some bug in the ILH software?
|
||||||
|
if (remainingSize > mpsoc::MAX_FLASH_WRITE_DATA_SIZE - 4) {
|
||||||
|
dataLength = mpsoc::MAX_FLASH_WRITE_DATA_SIZE - 4;
|
||||||
|
} else {
|
||||||
|
dataLength = remainingSize;
|
||||||
|
}
|
||||||
|
if (file.bad() or not file.is_open()) {
|
||||||
|
return FILE_WRITE_ERROR;
|
||||||
|
}
|
||||||
|
file.seekg(bytesRead, file.beg);
|
||||||
|
file.read(reinterpret_cast<char*>(fileBuf.data()), dataLength);
|
||||||
|
bytesRead += dataLength;
|
||||||
|
remainingSize -= dataLength;
|
||||||
|
mpsoc::TcFlashWrite tc(spParams, *sequenceCount);
|
||||||
|
result = tc.setPayload(fileBuf.data(), dataLength);
|
||||||
|
if (result != returnvalue::OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
result = tc.finishPacket();
|
||||||
|
if (result != returnvalue::OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
(*sequenceCount)++;
|
||||||
|
result = handlePacketTransmissionNoReply(tc);
|
||||||
|
if (result != returnvalue::OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
result = flashfclose();
|
||||||
|
if (result != returnvalue::OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t PlocMpsocSpecialComHelper::performFlashRead() {
|
||||||
|
std::error_code e;
|
||||||
|
std::ofstream ofile(flashReadAndWrite.obcFile, std::ios::trunc | std::ios::binary);
|
||||||
|
if (ofile.bad()) {
|
||||||
|
return returnvalue::FAILED;
|
||||||
|
}
|
||||||
|
ReturnValue_t result = flashfopen(mpsoc::FileAccessModes::READ);
|
||||||
|
if (result != returnvalue::OK) {
|
||||||
|
std::filesystem::remove(flashReadAndWrite.obcFile, e);
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
size_t readSoFar = 0;
|
||||||
|
size_t nextReadSize = mpsoc::MAX_FLASH_READ_DATA_SIZE;
|
||||||
|
while (readSoFar < flashReadAndWrite.totalReadSize) {
|
||||||
|
if (terminate) {
|
||||||
|
std::filesystem::remove(flashReadAndWrite.obcFile, e);
|
||||||
|
return returnvalue::OK;
|
||||||
|
}
|
||||||
|
nextReadSize = mpsoc::MAX_FLASH_READ_DATA_SIZE;
|
||||||
|
if (flashReadAndWrite.totalReadSize - readSoFar < mpsoc::MAX_FLASH_READ_DATA_SIZE) {
|
||||||
|
nextReadSize = flashReadAndWrite.totalReadSize - readSoFar;
|
||||||
|
}
|
||||||
|
if (ofile.bad() or not ofile.is_open()) {
|
||||||
|
std::filesystem::remove(flashReadAndWrite.obcFile, e);
|
||||||
|
return FILE_READ_ERROR;
|
||||||
|
}
|
||||||
|
mpsoc::TcFlashRead flashReadRequest(spParams, *sequenceCount);
|
||||||
|
result = flashReadRequest.setPayload(nextReadSize);
|
||||||
|
if (result != returnvalue::OK) {
|
||||||
|
std::filesystem::remove(flashReadAndWrite.obcFile, e);
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
result = flashReadRequest.finishPacket();
|
||||||
|
if (result != returnvalue::OK) {
|
||||||
|
std::filesystem::remove(flashReadAndWrite.obcFile, e);
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
(*sequenceCount)++;
|
||||||
|
result = handlePacketTransmissionFlashRead(flashReadRequest, ofile, nextReadSize);
|
||||||
|
if (result != returnvalue::OK) {
|
||||||
|
std::filesystem::remove(flashReadAndWrite.obcFile, e);
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
readSoFar += nextReadSize;
|
||||||
|
}
|
||||||
|
result = flashfclose();
|
||||||
|
if (result != returnvalue::OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t PlocMpsocSpecialComHelper::flashfopen(uint8_t mode) {
|
||||||
|
spParams.buf = commandBuffer;
|
||||||
|
mpsoc::FlashFopen flashFopen(spParams, *sequenceCount);
|
||||||
|
ReturnValue_t result = flashFopen.setPayload(flashReadAndWrite.mpsocFile, mode);
|
||||||
|
if (result != returnvalue::OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
result = flashFopen.finishPacket();
|
||||||
|
if (result != returnvalue::OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
(*sequenceCount)++;
|
||||||
|
result = handlePacketTransmissionNoReply(flashFopen);
|
||||||
|
if (result != returnvalue::OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
return returnvalue::OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t PlocMpsocSpecialComHelper::flashfclose() {
|
||||||
|
spParams.buf = commandBuffer;
|
||||||
|
mpsoc::FlashFclose flashFclose(spParams, *sequenceCount);
|
||||||
|
ReturnValue_t result = flashFclose.finishPacket();
|
||||||
|
if (result != returnvalue::OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
(*sequenceCount)++;
|
||||||
|
result = handlePacketTransmissionNoReply(flashFclose);
|
||||||
|
if (result != returnvalue::OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t PlocMpsocSpecialComHelper::handlePacketTransmissionFlashRead(mpsoc::TcFlashRead& tc,
|
||||||
|
std::ofstream& ofile,
|
||||||
|
size_t expectedReadLen) {
|
||||||
|
ReturnValue_t result = sendCommand(tc);
|
||||||
|
if (result != returnvalue::OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
result = handleAck();
|
||||||
|
if (result != returnvalue::OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
result = handleTmReception();
|
||||||
|
if (result != returnvalue::OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
|
||||||
|
// We have the nominal case where the flash read report appears first, or the case where we
|
||||||
|
// get an EXE failure immediately.
|
||||||
|
if (spReader.getApid() == mpsoc::apid::TM_FLASH_READ_REPORT) {
|
||||||
|
result = handleFlashReadReply(ofile, expectedReadLen);
|
||||||
|
if (result != returnvalue::OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
return handleExe();
|
||||||
|
} else if (spReader.getApid() == mpsoc::apid::EXE_FAILURE) {
|
||||||
|
handleExeFailure();
|
||||||
|
} else {
|
||||||
|
triggerEvent(MPSOC_EXE_INVALID_APID, spReader.getApid(), static_cast<uint32_t>(internalState));
|
||||||
|
sif::warning << "PLOC MPSoC: Expected execution report "
|
||||||
|
<< "but received space packet with apid " << std::hex << spReader.getApid()
|
||||||
|
<< std::endl;
|
||||||
|
}
|
||||||
|
return returnvalue::FAILED;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t PlocMpsocSpecialComHelper::handlePacketTransmissionNoReply(ploc::SpTcBase& tc) {
|
||||||
|
ReturnValue_t result = sendCommand(tc);
|
||||||
|
if (result != returnvalue::OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
result = handleAck();
|
||||||
|
if (result != returnvalue::OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
return handleExe();
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t PlocMpsocSpecialComHelper::sendCommand(ploc::SpTcBase& tc) {
|
||||||
|
ReturnValue_t result = returnvalue::OK;
|
||||||
|
result = uartComIF->sendMessage(comCookie, tc.getFullPacket(), tc.getFullPacketLen());
|
||||||
|
if (result != returnvalue::OK) {
|
||||||
|
sif::warning << "PlocMPSoCHelper::sendCommand: Failed to send command" << std::endl;
|
||||||
|
triggerEvent(MPSOC_SENDING_COMMAND_FAILED, result, static_cast<uint32_t>(internalState));
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t PlocMpsocSpecialComHelper::handleAck() {
|
||||||
|
ReturnValue_t result = returnvalue::OK;
|
||||||
|
result = handleTmReception();
|
||||||
|
if (result != returnvalue::OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
result = checkReceivedTm();
|
||||||
|
if (result != returnvalue::OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
uint16_t apid = spReader.getApid();
|
||||||
|
if (apid != mpsoc::apid::ACK_SUCCESS) {
|
||||||
|
handleAckApidFailure(spReader);
|
||||||
|
return returnvalue::FAILED;
|
||||||
|
}
|
||||||
|
return returnvalue::OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
void PlocMpsocSpecialComHelper::handleAckApidFailure(const ploc::SpTmReader& reader) {
|
||||||
|
uint16_t apid = reader.getApid();
|
||||||
|
if (apid == mpsoc::apid::ACK_FAILURE) {
|
||||||
|
uint16_t status = mpsoc::getStatusFromRawData(reader.getFullData());
|
||||||
|
sif::warning << "PLOC MPSoC ACK Failure: " << mpsoc::getStatusString(status) << std::endl;
|
||||||
|
triggerEvent(MPSOC_ACK_FAILURE_REPORT, static_cast<uint32_t>(internalState), status);
|
||||||
|
} else {
|
||||||
|
triggerEvent(MPSOC_ACK_INVALID_APID, apid, static_cast<uint32_t>(internalState));
|
||||||
|
sif::warning << "PlocMPSoCHelper::handleAckApidFailure: Expected acknowledgement report "
|
||||||
|
<< "but received space packet with apid " << std::hex << apid << std::endl;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t PlocMpsocSpecialComHelper::handleExe() {
|
||||||
|
ReturnValue_t result = returnvalue::OK;
|
||||||
|
|
||||||
|
result = handleTmReception();
|
||||||
|
if (result != returnvalue::OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
result = checkReceivedTm();
|
||||||
|
if (result != returnvalue::OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
uint16_t apid = spReader.getApid();
|
||||||
|
if (apid == mpsoc::apid::EXE_FAILURE) {
|
||||||
|
handleExeFailure();
|
||||||
|
return returnvalue::FAILED;
|
||||||
|
} else if (apid != mpsoc::apid::EXE_SUCCESS) {
|
||||||
|
triggerEvent(MPSOC_EXE_INVALID_APID, apid, static_cast<uint32_t>(internalState));
|
||||||
|
sif::warning << "PLOC MPSoC: Expected execution report "
|
||||||
|
<< "but received space packet with apid " << std::hex << apid << std::endl;
|
||||||
|
}
|
||||||
|
return returnvalue::OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
void PlocMpsocSpecialComHelper::handleExeFailure() {
|
||||||
|
uint16_t status = mpsoc::getStatusFromRawData(spReader.getFullData());
|
||||||
|
sif::warning << "PLOC MPSoC EXE Failure: " << mpsoc::getStatusString(status) << std::endl;
|
||||||
|
triggerEvent(MPSOC_EXE_FAILURE_REPORT, static_cast<uint32_t>(internalState));
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t PlocMpsocSpecialComHelper::handleTmReception() {
|
||||||
|
ReturnValue_t result = returnvalue::OK;
|
||||||
|
tmCountdown.resetTimer();
|
||||||
|
size_t readBytes = 0;
|
||||||
|
size_t currentBytes = 0;
|
||||||
|
uint32_t usleepDelay = 5;
|
||||||
|
size_t fullPacketLen = 0;
|
||||||
|
while (true) {
|
||||||
|
if (tmCountdown.hasTimedOut()) {
|
||||||
|
triggerEvent(MPSOC_READ_TIMEOUT, tmCountdown.getTimeoutMs());
|
||||||
|
return returnvalue::FAILED;
|
||||||
|
}
|
||||||
|
result = receive(tmBuf.data() + readBytes, 6, ¤tBytes);
|
||||||
|
if (result != returnvalue::OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
spReader.setReadOnlyData(tmBuf.data(), tmBuf.size());
|
||||||
|
fullPacketLen = spReader.getFullPacketLen();
|
||||||
|
readBytes += currentBytes;
|
||||||
|
if (readBytes == 6) {
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
usleep(usleepDelay);
|
||||||
|
if (usleepDelay < 200000) {
|
||||||
|
usleepDelay *= 4;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
while (true) {
|
||||||
|
if (tmCountdown.hasTimedOut()) {
|
||||||
|
triggerEvent(MPSOC_READ_TIMEOUT, tmCountdown.getTimeoutMs());
|
||||||
|
return returnvalue::FAILED;
|
||||||
|
}
|
||||||
|
result = receive(tmBuf.data() + readBytes, fullPacketLen - readBytes, ¤tBytes);
|
||||||
|
readBytes += currentBytes;
|
||||||
|
if (fullPacketLen == readBytes) {
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
usleep(usleepDelay);
|
||||||
|
if (usleepDelay < 200000) {
|
||||||
|
usleepDelay *= 4;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
// arrayprinter::print(tmBuf.data(), readBytes);
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t PlocMpsocSpecialComHelper::handleFlashReadReply(std::ofstream& ofile,
|
||||||
|
size_t expectedReadLen) {
|
||||||
|
ReturnValue_t result = checkReceivedTm();
|
||||||
|
if (result != returnvalue::OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
uint16_t apid = spReader.getApid();
|
||||||
|
if (apid != mpsoc::apid::TM_FLASH_READ_REPORT) {
|
||||||
|
triggerEvent(MPSOC_FLASH_READ_PACKET_ERROR, FlashReadErrorType::FLASH_READ_APID_ERROR);
|
||||||
|
sif::warning << "PLOC MPSoC Flash Read: Unexpected APID" << std::endl;
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
const uint8_t* packetData = spReader.getPacketData();
|
||||||
|
size_t deserDummy = spReader.getPacketDataLen() - mpsoc::CRC_SIZE;
|
||||||
|
uint32_t receivedReadLen = 0;
|
||||||
|
// I think this is buggy, weird stuff in the short name field.
|
||||||
|
// std::string receivedShortName = std::string(reinterpret_cast<const char*>(packetData), 12);
|
||||||
|
// if (receivedShortName != flashReadAndWrite.mpsocFile.substr(0, 11)) {
|
||||||
|
// sif::warning << "PLOC MPSoC Flash Read: Missmatch between request file name and "
|
||||||
|
// "received file name"
|
||||||
|
// << std::endl;
|
||||||
|
// triggerEvent(MPSOC_FLASH_READ_PACKET_ERROR, FlashReadErrorType::FLASH_READ_FILENAME_ERROR);
|
||||||
|
// return returnvalue::FAILED;
|
||||||
|
// }
|
||||||
|
packetData += 12;
|
||||||
|
result = SerializeAdapter::deSerialize(&receivedReadLen, &packetData, &deserDummy,
|
||||||
|
SerializeIF::Endianness::NETWORK);
|
||||||
|
if (result != returnvalue::OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
if (receivedReadLen != expectedReadLen) {
|
||||||
|
sif::warning << "PLOC MPSoC Flash Read: Missmatch between request read length and "
|
||||||
|
"received read length"
|
||||||
|
<< std::endl;
|
||||||
|
triggerEvent(MPSOC_FLASH_READ_PACKET_ERROR, FlashReadErrorType::FLASH_READ_READLEN_ERROR);
|
||||||
|
return returnvalue::FAILED;
|
||||||
|
}
|
||||||
|
ofile.write(reinterpret_cast<const char*>(packetData), receivedReadLen);
|
||||||
|
return returnvalue::OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t PlocMpsocSpecialComHelper::fileCheck(std::string obcFile) {
|
||||||
|
#ifdef XIPHOS_Q7S
|
||||||
|
ReturnValue_t result = FilesystemHelper::checkPath(obcFile);
|
||||||
|
if (result != returnvalue::OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
#elif defined(TE0720_1CFA)
|
||||||
|
if (not std::filesystem::exists(obcFile)) {
|
||||||
|
sif::warning << "PlocMPSoCHelper::startFlashWrite: File " << obcFile << "does not exist"
|
||||||
|
<< std::endl;
|
||||||
|
return returnvalue::FAILED;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
return returnvalue::OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t PlocMpsocSpecialComHelper::startFlashReadOrWriteBase(std::string obcFile,
|
||||||
|
std::string mpsocFile) {
|
||||||
|
ReturnValue_t result = fileCheck(obcFile);
|
||||||
|
if (result != returnvalue::OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
|
||||||
|
flashReadAndWrite.obcFile = std::move(obcFile);
|
||||||
|
flashReadAndWrite.mpsocFile = std::move(mpsocFile);
|
||||||
|
resetHelper();
|
||||||
|
return returnvalue::OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t PlocMpsocSpecialComHelper::checkReceivedTm() {
|
||||||
|
ReturnValue_t result = spReader.checkSize();
|
||||||
|
if (result != returnvalue::OK) {
|
||||||
|
sif::error << "PLOC MPSoC: Size check on received TM failed" << std::endl;
|
||||||
|
triggerEvent(MPSOC_TM_SIZE_ERROR);
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
spReader.checkCrc();
|
||||||
|
if (result != returnvalue::OK) {
|
||||||
|
sif::warning << "PLOC MPSoC: CRC check failed" << std::endl;
|
||||||
|
triggerEvent(MPSOC_TM_CRC_MISSMATCH, *sequenceCount);
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
uint16_t recvSeqCnt = spReader.getSequenceCount();
|
||||||
|
if (recvSeqCnt != *sequenceCount) {
|
||||||
|
triggerEvent(MPSOC_HELPER_SEQ_CNT_MISMATCH, *sequenceCount, recvSeqCnt);
|
||||||
|
*sequenceCount = recvSeqCnt;
|
||||||
|
}
|
||||||
|
// This sequence count ping pong does not make any sense but it is how the MPSoC expects it.
|
||||||
|
(*sequenceCount)++;
|
||||||
|
return returnvalue::OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t PlocMpsocSpecialComHelper::receive(uint8_t* data, size_t requestBytes,
|
||||||
|
size_t* readBytes) {
|
||||||
|
ReturnValue_t result = returnvalue::OK;
|
||||||
|
uint8_t* buffer = nullptr;
|
||||||
|
result = uartComIF->requestReceiveMessage(comCookie, requestBytes);
|
||||||
|
if (result != returnvalue::OK) {
|
||||||
|
sif::warning << "PlocMPSoCHelper::receive: Failed to request reply" << std::endl;
|
||||||
|
triggerEvent(MPSOC_HELPER_REQUESTING_REPLY_FAILED, result,
|
||||||
|
static_cast<uint32_t>(static_cast<uint32_t>(internalState)));
|
||||||
|
return returnvalue::FAILED;
|
||||||
|
}
|
||||||
|
result = uartComIF->readReceivedMessage(comCookie, &buffer, readBytes);
|
||||||
|
if (result != returnvalue::OK) {
|
||||||
|
sif::warning << "PlocMPSoCHelper::receive: Failed to read received message" << std::endl;
|
||||||
|
triggerEvent(MPSOC_HELPER_READING_REPLY_FAILED, result, static_cast<uint32_t>(internalState));
|
||||||
|
return returnvalue::FAILED;
|
||||||
|
}
|
||||||
|
if (*readBytes > 0) {
|
||||||
|
std::memcpy(data, buffer, *readBytes);
|
||||||
|
}
|
||||||
|
return result;
|
||||||
|
}
|
@ -1,11 +1,12 @@
|
|||||||
#ifndef BSP_Q7S_DEVICES_PLOCMPSOCHELPER_H_
|
#ifndef BSP_Q7S_DEVICES_PLOCMPSOCHELPER_H_
|
||||||
#define BSP_Q7S_DEVICES_PLOCMPSOCHELPER_H_
|
#define BSP_Q7S_DEVICES_PLOCMPSOCHELPER_H_
|
||||||
|
|
||||||
#include <linux/payload/plocMpscoDefs.h>
|
#include <linux/payload/plocMpsocHelpers.h>
|
||||||
#include <mission/utility/trace.h>
|
#include <mission/utility/trace.h>
|
||||||
|
|
||||||
#include <string>
|
#include <string>
|
||||||
|
|
||||||
|
#include "OBSWConfig.h"
|
||||||
#include "fsfw/devicehandlers/CookieIF.h"
|
#include "fsfw/devicehandlers/CookieIF.h"
|
||||||
#include "fsfw/objectmanager/SystemObject.h"
|
#include "fsfw/objectmanager/SystemObject.h"
|
||||||
#include "fsfw/osal/linux/BinarySemaphore.h"
|
#include "fsfw/osal/linux/BinarySemaphore.h"
|
||||||
@ -22,14 +23,14 @@
|
|||||||
* MPSoC and OBC.
|
* MPSoC and OBC.
|
||||||
* @author J. Meier
|
* @author J. Meier
|
||||||
*/
|
*/
|
||||||
class PlocMPSoCHelper : public SystemObject, public ExecutableObjectIF {
|
class PlocMpsocSpecialComHelper : public SystemObject, public ExecutableObjectIF {
|
||||||
public:
|
public:
|
||||||
static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::PLOC_MPSOC_HELPER;
|
static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::PLOC_MPSOC_HELPER;
|
||||||
|
|
||||||
//! [EXPORT] : [COMMENT] Flash write fails
|
//! [EXPORT] : [COMMENT] Flash write fails
|
||||||
static const Event MPSOC_FLASH_WRITE_FAILED = MAKE_EVENT(0, severity::LOW);
|
static const Event MPSOC_FLASH_WRITE_FAILED = MAKE_EVENT(0, severity::LOW);
|
||||||
//! [EXPORT] : [COMMENT] Flash write successful
|
//! [EXPORT] : [COMMENT] Flash write successful
|
||||||
static const Event MPSOC_FLASH_WRITE_SUCCESSFUL = MAKE_EVENT(1, severity::LOW);
|
static const Event MPSOC_FLASH_WRITE_SUCCESSFUL = MAKE_EVENT(1, severity::INFO);
|
||||||
//! [EXPORT] : [COMMENT] Communication interface returned failure when trying to send the command
|
//! [EXPORT] : [COMMENT] Communication interface returned failure when trying to send the command
|
||||||
//! to the MPSoC
|
//! to the MPSoC
|
||||||
//! P1: Return value returned by the communication interface sendMessage function
|
//! P1: Return value returned by the communication interface sendMessage function
|
||||||
@ -71,9 +72,19 @@ class PlocMPSoCHelper : public SystemObject, public ExecutableObjectIF {
|
|||||||
static const Event MPSOC_HELPER_SEQ_CNT_MISMATCH = MAKE_EVENT(11, severity::LOW);
|
static const Event MPSOC_HELPER_SEQ_CNT_MISMATCH = MAKE_EVENT(11, severity::LOW);
|
||||||
static const Event MPSOC_TM_SIZE_ERROR = MAKE_EVENT(12, severity::LOW);
|
static const Event MPSOC_TM_SIZE_ERROR = MAKE_EVENT(12, severity::LOW);
|
||||||
static const Event MPSOC_TM_CRC_MISSMATCH = MAKE_EVENT(13, severity::LOW);
|
static const Event MPSOC_TM_CRC_MISSMATCH = MAKE_EVENT(13, severity::LOW);
|
||||||
|
static const Event MPSOC_FLASH_READ_PACKET_ERROR = MAKE_EVENT(14, severity::LOW);
|
||||||
|
static const Event MPSOC_FLASH_READ_FAILED = MAKE_EVENT(15, severity::LOW);
|
||||||
|
static const Event MPSOC_FLASH_READ_SUCCESSFUL = MAKE_EVENT(16, severity::INFO);
|
||||||
|
static const Event MPSOC_READ_TIMEOUT = MAKE_EVENT(17, severity::LOW);
|
||||||
|
|
||||||
PlocMPSoCHelper(object_id_t objectId);
|
enum FlashReadErrorType : uint32_t {
|
||||||
virtual ~PlocMPSoCHelper();
|
FLASH_READ_APID_ERROR = 0,
|
||||||
|
FLASH_READ_FILENAME_ERROR = 1,
|
||||||
|
FLASH_READ_READLEN_ERROR = 2
|
||||||
|
};
|
||||||
|
|
||||||
|
PlocMpsocSpecialComHelper(object_id_t objectId);
|
||||||
|
virtual ~PlocMpsocSpecialComHelper();
|
||||||
|
|
||||||
ReturnValue_t initialize() override;
|
ReturnValue_t initialize() override;
|
||||||
ReturnValue_t performOperation(uint8_t operationCode = 0) override;
|
ReturnValue_t performOperation(uint8_t operationCode = 0) override;
|
||||||
@ -90,6 +101,14 @@ class PlocMPSoCHelper : public SystemObject, public ExecutableObjectIF {
|
|||||||
* @return returnvalue::OK if successful, otherwise error return value
|
* @return returnvalue::OK if successful, otherwise error return value
|
||||||
*/
|
*/
|
||||||
ReturnValue_t startFlashWrite(std::string obcFile, std::string mpsocFile);
|
ReturnValue_t startFlashWrite(std::string obcFile, std::string mpsocFile);
|
||||||
|
/**
|
||||||
|
*
|
||||||
|
* @param obcFile Full target file name on OBC
|
||||||
|
* @param mpsocFile The file on the MPSoC which should be copied ot the OBC
|
||||||
|
* @param readFileSize The size of the file on the MPSoC.
|
||||||
|
* @return
|
||||||
|
*/
|
||||||
|
ReturnValue_t startFlashRead(std::string obcFile, std::string mpsocFile, size_t readFileSize);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Can be used to interrupt a running data transfer.
|
* @brief Can be used to interrupt a running data transfer.
|
||||||
@ -104,20 +123,25 @@ class PlocMPSoCHelper : public SystemObject, public ExecutableObjectIF {
|
|||||||
private:
|
private:
|
||||||
static const uint8_t INTERFACE_ID = CLASS_ID::PLOC_MPSOC_HELPER;
|
static const uint8_t INTERFACE_ID = CLASS_ID::PLOC_MPSOC_HELPER;
|
||||||
|
|
||||||
//! [EXPORT] : [COMMENT] File accidentally close
|
//! [EXPORT] : [COMMENT] File error occured for file transfers from OBC to the MPSoC.
|
||||||
static const ReturnValue_t FILE_CLOSED_ACCIDENTALLY = MAKE_RETURN_CODE(0xA0);
|
static const ReturnValue_t FILE_WRITE_ERROR = MAKE_RETURN_CODE(0xA0);
|
||||||
|
//! [EXPORT] : [COMMENT] File error occured for file transfers from MPSoC to OBC.
|
||||||
|
static const ReturnValue_t FILE_READ_ERROR = MAKE_RETURN_CODE(0xA1);
|
||||||
|
|
||||||
// Maximum number of times the communication interface retries polling data from the reply
|
// Maximum number of times the communication interface retries polling data from the reply
|
||||||
// buffer
|
// buffer
|
||||||
static const int RETRIES = 10000;
|
static const int RETRIES = 10000;
|
||||||
|
|
||||||
struct FlashWrite {
|
struct FlashInfo {
|
||||||
std::string obcFile;
|
std::string obcFile;
|
||||||
std::string mpsocFile;
|
std::string mpsocFile;
|
||||||
};
|
};
|
||||||
|
|
||||||
struct FlashWrite flashWrite;
|
struct FlashRead : public FlashInfo {
|
||||||
|
size_t totalReadSize = 0;
|
||||||
|
};
|
||||||
|
|
||||||
|
struct FlashRead flashReadAndWrite;
|
||||||
#if OBSW_THREAD_TRACING == 1
|
#if OBSW_THREAD_TRACING == 1
|
||||||
uint32_t opCounter = 0;
|
uint32_t opCounter = 0;
|
||||||
#endif
|
#endif
|
||||||
@ -134,7 +158,10 @@ class PlocMPSoCHelper : public SystemObject, public ExecutableObjectIF {
|
|||||||
SpacePacketCreator creator;
|
SpacePacketCreator creator;
|
||||||
ploc::SpTcParams spParams = ploc::SpTcParams(creator);
|
ploc::SpTcParams spParams = ploc::SpTcParams(creator);
|
||||||
|
|
||||||
std::array<uint8_t, mpsoc::MAX_REPLY_SIZE> tmBuf;
|
Countdown tmCountdown = Countdown(5000);
|
||||||
|
|
||||||
|
std::array<uint8_t, mpsoc::SP_MAX_DATA_SIZE> fileBuf{};
|
||||||
|
std::array<uint8_t, mpsoc::MAX_REPLY_SIZE> tmBuf{};
|
||||||
|
|
||||||
bool terminate = false;
|
bool terminate = false;
|
||||||
|
|
||||||
@ -147,20 +174,27 @@ class PlocMPSoCHelper : public SystemObject, public ExecutableObjectIF {
|
|||||||
CookieIF* comCookie = nullptr;
|
CookieIF* comCookie = nullptr;
|
||||||
// Sequence count, must be set by Ploc MPSoC Handler
|
// Sequence count, must be set by Ploc MPSoC Handler
|
||||||
SourceSequenceCounter* sequenceCount = nullptr;
|
SourceSequenceCounter* sequenceCount = nullptr;
|
||||||
|
ploc::SpTmReader spReader;
|
||||||
|
|
||||||
ReturnValue_t resetHelper();
|
void resetHelper();
|
||||||
ReturnValue_t performFlashWrite();
|
ReturnValue_t performFlashWrite();
|
||||||
ReturnValue_t flashfopen();
|
ReturnValue_t performFlashRead();
|
||||||
|
ReturnValue_t flashfopen(uint8_t accessMode);
|
||||||
ReturnValue_t flashfclose();
|
ReturnValue_t flashfclose();
|
||||||
ReturnValue_t handlePacketTransmission(ploc::SpTcBase& tc);
|
ReturnValue_t handlePacketTransmissionNoReply(ploc::SpTcBase& tc);
|
||||||
|
ReturnValue_t handlePacketTransmissionFlashRead(mpsoc::TcFlashRead& tc, std::ofstream& ofile,
|
||||||
|
size_t expectedReadLen);
|
||||||
|
ReturnValue_t handleFlashReadReply(std::ofstream& ofile, size_t expectedReadLen);
|
||||||
ReturnValue_t sendCommand(ploc::SpTcBase& tc);
|
ReturnValue_t sendCommand(ploc::SpTcBase& tc);
|
||||||
ReturnValue_t receive(uint8_t* data, size_t* readBytes, size_t requestBytes);
|
ReturnValue_t receive(uint8_t* data, size_t requestBytes, size_t* readBytes);
|
||||||
ReturnValue_t handleAck();
|
ReturnValue_t handleAck();
|
||||||
ReturnValue_t handleExe();
|
ReturnValue_t handleExe();
|
||||||
void handleAckApidFailure(uint16_t apid);
|
ReturnValue_t startFlashReadOrWriteBase(std::string obcFile, std::string mpsocFile);
|
||||||
void handleExeApidFailure(uint16_t apid);
|
ReturnValue_t fileCheck(std::string obcFile);
|
||||||
ReturnValue_t handleTmReception(size_t remainingBytes);
|
void handleAckApidFailure(const ploc::SpTmReader& reader);
|
||||||
ReturnValue_t checkReceivedTm(ploc::SpTmReader& reader);
|
void handleExeFailure();
|
||||||
|
ReturnValue_t handleTmReception();
|
||||||
|
ReturnValue_t checkReceivedTm();
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* BSP_Q7S_DEVICES_PLOCMPSOCHELPER_H_ */
|
#endif /* BSP_Q7S_DEVICES_PLOCMPSOCHELPER_H_ */
|
@ -151,7 +151,7 @@ void PlocSupervisorHandler::doStartUp() {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
if (startupState == StartupState::SET_TIME_EXECUTING) {
|
if (startupState == StartupState::TIME_WAS_SET) {
|
||||||
startupState = StartupState::ON;
|
startupState = StartupState::ON;
|
||||||
}
|
}
|
||||||
if (startupState == StartupState::ON) {
|
if (startupState == StartupState::ON) {
|
||||||
@ -176,7 +176,7 @@ ReturnValue_t PlocSupervisorHandler::buildNormalDeviceCommand(DeviceCommandId_t*
|
|||||||
ReturnValue_t PlocSupervisorHandler::buildTransitionDeviceCommand(DeviceCommandId_t* id) {
|
ReturnValue_t PlocSupervisorHandler::buildTransitionDeviceCommand(DeviceCommandId_t* id) {
|
||||||
if (startupState == StartupState::SET_TIME) {
|
if (startupState == StartupState::SET_TIME) {
|
||||||
*id = supv::SET_TIME_REF;
|
*id = supv::SET_TIME_REF;
|
||||||
startupState = StartupState::SET_TIME_EXECUTING;
|
startupState = StartupState::WAIT_FOR_TIME_REPLY;
|
||||||
return buildCommandFromCommand(*id, nullptr, 0);
|
return buildCommandFromCommand(*id, nullptr, 0);
|
||||||
}
|
}
|
||||||
return NOTHING_TO_SEND;
|
return NOTHING_TO_SEND;
|
||||||
@ -1909,6 +1909,10 @@ ReturnValue_t PlocSupervisorHandler::handleExecutionSuccessReport(ExecutionRepor
|
|||||||
case supv::SET_TIME_REF: {
|
case supv::SET_TIME_REF: {
|
||||||
// We could only allow proper bootup when the time was set successfully, but
|
// We could only allow proper bootup when the time was set successfully, but
|
||||||
// this makes debugging difficult.
|
// this makes debugging difficult.
|
||||||
|
|
||||||
|
if (startupState == StartupState::WAIT_FOR_TIME_REPLY) {
|
||||||
|
startupState = StartupState::TIME_WAS_SET;
|
||||||
|
}
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
default:
|
default:
|
||||||
|
@ -99,7 +99,14 @@ class PlocSupervisorHandler : public DeviceHandlerBase {
|
|||||||
static const uint32_t MRAM_DUMP_TIMEOUT = 60000;
|
static const uint32_t MRAM_DUMP_TIMEOUT = 60000;
|
||||||
// 4 s
|
// 4 s
|
||||||
static const uint32_t BOOT_TIMEOUT = 4000;
|
static const uint32_t BOOT_TIMEOUT = 4000;
|
||||||
enum class StartupState : uint8_t { OFF, BOOTING, SET_TIME, SET_TIME_EXECUTING, ON };
|
enum class StartupState : uint8_t {
|
||||||
|
OFF,
|
||||||
|
BOOTING,
|
||||||
|
SET_TIME,
|
||||||
|
WAIT_FOR_TIME_REPLY,
|
||||||
|
TIME_WAS_SET,
|
||||||
|
ON
|
||||||
|
};
|
||||||
|
|
||||||
static constexpr bool SET_TIME_DURING_BOOT = true;
|
static constexpr bool SET_TIME_DURING_BOOT = true;
|
||||||
|
|
||||||
|
95
linux/payload/plocMpsocHelpers.cpp
Normal file
95
linux/payload/plocMpsocHelpers.cpp
Normal file
@ -0,0 +1,95 @@
|
|||||||
|
#include "plocMpsocHelpers.h"
|
||||||
|
|
||||||
|
uint16_t mpsoc::getStatusFromRawData(const uint8_t* data) {
|
||||||
|
return (*(data + STATUS_OFFSET) << 8) | *(data + STATUS_OFFSET + 1);
|
||||||
|
}
|
||||||
|
std::string mpsoc::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_OPEN): {
|
||||||
|
return "Flash file already open";
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case (mpsoc::status_code::FLASH_FILE_ALREADY_CLOSED): {
|
||||||
|
return "Flash file already closed";
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case (mpsoc::status_code::FLASH_FILE_OPEN_FAILED): {
|
||||||
|
return "Flash file open failed";
|
||||||
|
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;
|
||||||
|
}
|
||||||
|
case (mpsoc::status_code::DEFAULT_ERROR_CODE): {
|
||||||
|
return "Default error code";
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
default:
|
||||||
|
std::stringstream ss;
|
||||||
|
ss << "0x" << std::hex << status;
|
||||||
|
return ss.str().c_str();
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
return "";
|
||||||
|
}
|
@ -1,6 +1,7 @@
|
|||||||
#ifndef MISSION_DEVICES_DEVICEDEFINITIONS_PLOCMPSOCDEFINITIONS_H_
|
#ifndef MISSION_DEVICES_DEVICEDEFINITIONS_PLOCMPSOCDEFINITIONS_H_
|
||||||
#define MISSION_DEVICES_DEVICEDEFINITIONS_PLOCMPSOCDEFINITIONS_H_
|
#define MISSION_DEVICES_DEVICEDEFINITIONS_PLOCMPSOCDEFINITIONS_H_
|
||||||
|
|
||||||
|
#include <fsfw/datapoollocal/StaticLocalDataSet.h>
|
||||||
#include <fsfw/devicehandlers/DeviceHandlerIF.h>
|
#include <fsfw/devicehandlers/DeviceHandlerIF.h>
|
||||||
#include <linux/payload/mpsocRetvals.h>
|
#include <linux/payload/mpsocRetvals.h>
|
||||||
#include <mission/payload/plocSpBase.h>
|
#include <mission/payload/plocSpBase.h>
|
||||||
@ -12,6 +13,61 @@
|
|||||||
|
|
||||||
namespace mpsoc {
|
namespace mpsoc {
|
||||||
|
|
||||||
|
enum FileAccessModes : uint8_t {
|
||||||
|
// Opens a file, fails if the file does not exist.
|
||||||
|
OPEN_EXISTING = 0x00,
|
||||||
|
READ = 0x01,
|
||||||
|
WRITE = 0x02,
|
||||||
|
// Creates a new file, fails if it already exists.
|
||||||
|
CREATE_NEW = 0x04,
|
||||||
|
// Creates a new file, existing file is truncated and overwritten.
|
||||||
|
CREATE_ALWAYS = 0x08,
|
||||||
|
// Opens the file if it is existing. If not, a new file is created.
|
||||||
|
OPEN_ALWAYS = 0x10,
|
||||||
|
OPEN_APPEND = 0x30
|
||||||
|
};
|
||||||
|
|
||||||
|
static constexpr uint32_t HK_SET_ID = 0;
|
||||||
|
|
||||||
|
namespace poolid {
|
||||||
|
enum {
|
||||||
|
STATUS = 0,
|
||||||
|
MODE = 1,
|
||||||
|
DOWNLINK_PWR_ON = 2,
|
||||||
|
DOWNLINK_REPLY_ACTIIVE = 3,
|
||||||
|
DOWNLINK_JESD_SYNC_STATUS = 4,
|
||||||
|
DOWNLINK_DAC_STATUS = 5,
|
||||||
|
CAM_STATUS = 6,
|
||||||
|
CAM_SDI_STATUS = 7,
|
||||||
|
CAM_FPGA_TEMP = 8,
|
||||||
|
CAM_SOC_TEMP = 9,
|
||||||
|
SYSMON_TEMP = 10,
|
||||||
|
SYSMON_VCCINT = 11,
|
||||||
|
SYSMON_VCCAUX = 12,
|
||||||
|
SYSMON_VCCBRAM = 13,
|
||||||
|
SYSMON_VCCPAUX = 14,
|
||||||
|
SYSMON_VCCPINT = 15,
|
||||||
|
SYSMON_VCCPDRO = 16,
|
||||||
|
SYSMON_MB12V = 17,
|
||||||
|
SYSMON_MB3V3 = 18,
|
||||||
|
SYSMON_MB1V8 = 19,
|
||||||
|
SYSMON_VCC12V = 20,
|
||||||
|
SYSMON_VCC5V = 21,
|
||||||
|
SYSMON_VCC3V3 = 22,
|
||||||
|
SYSMON_VCC3V3VA = 23,
|
||||||
|
SYSMON_VCC2V5DDR = 24,
|
||||||
|
SYSMON_VCC1V2DDR = 25,
|
||||||
|
SYSMON_VCC0V9 = 26,
|
||||||
|
SYSMON_VCC0V6VTT = 27,
|
||||||
|
SYSMON_SAFE_COTS_CUR = 28,
|
||||||
|
SYSMON_NVM4_XO_CUR = 29,
|
||||||
|
SEM_UNCORRECTABLE_ERRS = 30,
|
||||||
|
SEM_CORRECTABLE_ERRS = 31,
|
||||||
|
SEM_STATUS = 32,
|
||||||
|
REBOOT_MPSOC_REQUIRED = 33,
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
static const DeviceCommandId_t NONE = 0;
|
static const DeviceCommandId_t NONE = 0;
|
||||||
static const DeviceCommandId_t TC_MEM_WRITE = 1;
|
static const DeviceCommandId_t TC_MEM_WRITE = 1;
|
||||||
static const DeviceCommandId_t TC_MEM_READ = 2;
|
static const DeviceCommandId_t TC_MEM_READ = 2;
|
||||||
@ -20,7 +76,7 @@ static const DeviceCommandId_t EXE_REPORT = 5;
|
|||||||
static const DeviceCommandId_t TM_MEMORY_READ_REPORT = 6;
|
static const DeviceCommandId_t TM_MEMORY_READ_REPORT = 6;
|
||||||
static const DeviceCommandId_t TC_FLASHFOPEN = 7;
|
static const DeviceCommandId_t TC_FLASHFOPEN = 7;
|
||||||
static const DeviceCommandId_t TC_FLASHFCLOSE = 8;
|
static const DeviceCommandId_t TC_FLASHFCLOSE = 8;
|
||||||
static const DeviceCommandId_t TC_FLASHWRITE = 9;
|
static const DeviceCommandId_t TC_FLASH_WRITE_FULL_FILE = 9;
|
||||||
static const DeviceCommandId_t TC_FLASHDELETE = 10;
|
static const DeviceCommandId_t TC_FLASHDELETE = 10;
|
||||||
static const DeviceCommandId_t TC_REPLAY_START = 11;
|
static const DeviceCommandId_t TC_REPLAY_START = 11;
|
||||||
static const DeviceCommandId_t TC_REPLAY_STOP = 12;
|
static const DeviceCommandId_t TC_REPLAY_STOP = 12;
|
||||||
@ -37,6 +93,11 @@ static const DeviceCommandId_t TC_CAM_TAKE_PIC = 22;
|
|||||||
static const DeviceCommandId_t TC_SIMPLEX_SEND_FILE = 23;
|
static const DeviceCommandId_t TC_SIMPLEX_SEND_FILE = 23;
|
||||||
static const DeviceCommandId_t TC_DOWNLINK_DATA_MODULATE = 24;
|
static const DeviceCommandId_t TC_DOWNLINK_DATA_MODULATE = 24;
|
||||||
static const DeviceCommandId_t TC_MODE_SNAPSHOT = 25;
|
static const DeviceCommandId_t TC_MODE_SNAPSHOT = 25;
|
||||||
|
static const DeviceCommandId_t TC_GET_HK_REPORT = 26;
|
||||||
|
static const DeviceCommandId_t TM_GET_HK_REPORT = 27;
|
||||||
|
static const DeviceCommandId_t TC_FLASH_GET_DIRECTORY_CONTENT = 28;
|
||||||
|
static const DeviceCommandId_t TM_FLASH_DIRECTORY_CONTENT = 29;
|
||||||
|
static constexpr DeviceCommandId_t TC_FLASH_READ_FULL_FILE = 30;
|
||||||
|
|
||||||
// Will reset the sequence count of the OBSW
|
// Will reset the sequence count of the OBSW
|
||||||
static const DeviceCommandId_t OBSW_RESET_SEQ_COUNT = 50;
|
static const DeviceCommandId_t OBSW_RESET_SEQ_COUNT = 50;
|
||||||
@ -45,6 +106,7 @@ static const uint16_t SIZE_ACK_REPORT = 14;
|
|||||||
static const uint16_t SIZE_EXE_REPORT = 14;
|
static const uint16_t SIZE_EXE_REPORT = 14;
|
||||||
static const uint16_t SIZE_TM_MEM_READ_REPORT = 18;
|
static const uint16_t SIZE_TM_MEM_READ_REPORT = 18;
|
||||||
static const uint16_t SIZE_TM_CAM_CMD_RPT = 18;
|
static const uint16_t SIZE_TM_CAM_CMD_RPT = 18;
|
||||||
|
static constexpr size_t SIZE_TM_HK_REPORT = 369;
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* SpacePacket apids of PLOC telecommands and telemetry.
|
* SpacePacket apids of PLOC telecommands and telemetry.
|
||||||
@ -57,23 +119,32 @@ static const uint16_t TC_DOWNLINK_PWR_ON = 0x113;
|
|||||||
static const uint16_t TC_MEM_WRITE = 0x114;
|
static const uint16_t TC_MEM_WRITE = 0x114;
|
||||||
static const uint16_t TC_MEM_READ = 0x115;
|
static const uint16_t TC_MEM_READ = 0x115;
|
||||||
static const uint16_t TC_CAM_TAKE_PIC = 0x116;
|
static const uint16_t TC_CAM_TAKE_PIC = 0x116;
|
||||||
static const uint16_t TC_FLASHWRITE = 0x117;
|
static constexpr uint16_t TC_FLASHWRITE = 0x117;
|
||||||
|
static constexpr uint16_t TC_FLASHREAD = 0x118;
|
||||||
static const uint16_t TC_FLASHFOPEN = 0x119;
|
static const uint16_t TC_FLASHFOPEN = 0x119;
|
||||||
static const uint16_t TC_FLASHFCLOSE = 0x11A;
|
static const uint16_t TC_FLASHFCLOSE = 0x11A;
|
||||||
|
static constexpr uint16_t TC_FLASH_GET_DIRECTORY_CONTENT = 0x11B;
|
||||||
static const uint16_t TC_FLASHDELETE = 0x11C;
|
static const uint16_t TC_FLASHDELETE = 0x11C;
|
||||||
|
static constexpr uint16_t TC_FLASH_CREATE_DIR = 0x11D;
|
||||||
static const uint16_t TC_MODE_IDLE = 0x11E;
|
static const uint16_t TC_MODE_IDLE = 0x11E;
|
||||||
static const uint16_t TC_MODE_REPLAY = 0x11F;
|
static const uint16_t TC_MODE_REPLAY = 0x11F;
|
||||||
static const uint16_t TC_MODE_SNAPSHOT = 0x120;
|
static const uint16_t TC_MODE_SNAPSHOT = 0x120;
|
||||||
static const uint16_t TC_DOWNLINK_DATA_MODULATE = 0x121;
|
static const uint16_t TC_DOWNLINK_DATA_MODULATE = 0x121;
|
||||||
|
static constexpr uint16_t TC_HK_GET_REPORT = 0x123;
|
||||||
static const uint16_t TC_DOWNLINK_PWR_OFF = 0x124;
|
static const uint16_t TC_DOWNLINK_PWR_OFF = 0x124;
|
||||||
static const uint16_t TC_CAM_CMD_SEND = 0x12C;
|
static const uint16_t TC_CAM_CMD_SEND = 0x12C;
|
||||||
|
static constexpr uint16_t TC_FLASH_COPY_FILE = 0x12E;
|
||||||
static const uint16_t TC_SIMPLEX_SEND_FILE = 0x130;
|
static const uint16_t TC_SIMPLEX_SEND_FILE = 0x130;
|
||||||
static const uint16_t TM_MEMORY_READ_REPORT = 0x404;
|
|
||||||
static const uint16_t ACK_SUCCESS = 0x400;
|
static const uint16_t ACK_SUCCESS = 0x400;
|
||||||
static const uint16_t ACK_FAILURE = 0x401;
|
static const uint16_t ACK_FAILURE = 0x401;
|
||||||
static const uint16_t EXE_SUCCESS = 0x402;
|
static const uint16_t EXE_SUCCESS = 0x402;
|
||||||
static const uint16_t EXE_FAILURE = 0x403;
|
static const uint16_t EXE_FAILURE = 0x403;
|
||||||
|
static const uint16_t TM_MEMORY_READ_REPORT = 0x404;
|
||||||
|
static const uint16_t TM_FLASH_READ_REPORT = 0x405;
|
||||||
|
static constexpr uint16_t TM_FLASH_DIRECTORY_CONTENT = 0x406;
|
||||||
static const uint16_t TM_CAM_CMD_RPT = 0x407;
|
static const uint16_t TM_CAM_CMD_RPT = 0x407;
|
||||||
|
static constexpr uint16_t TM_HK_GET_REPORT = 0x408;
|
||||||
} // namespace apid
|
} // namespace apid
|
||||||
|
|
||||||
/** Offset from first byte in space packet to first byte of data field */
|
/** Offset from first byte in space packet to first byte of data field */
|
||||||
@ -83,6 +154,8 @@ static const char NULL_TERMINATOR = '\0';
|
|||||||
static const uint8_t MIN_SPACE_PACKET_LENGTH = 7;
|
static const uint8_t MIN_SPACE_PACKET_LENGTH = 7;
|
||||||
static const uint8_t SPACE_PACKET_HEADER_SIZE = 6;
|
static const uint8_t SPACE_PACKET_HEADER_SIZE = 6;
|
||||||
|
|
||||||
|
static const uint8_t STATUS_OFFSET = 10;
|
||||||
|
|
||||||
static constexpr size_t CRC_SIZE = 2;
|
static constexpr size_t CRC_SIZE = 2;
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@ -106,9 +179,15 @@ static const uint16_t LENGTH_TC_MEM_READ = 8;
|
|||||||
* at sheet README
|
* at sheet README
|
||||||
*/
|
*/
|
||||||
static constexpr size_t SP_MAX_SIZE = 1024;
|
static constexpr size_t SP_MAX_SIZE = 1024;
|
||||||
static const size_t MAX_REPLY_SIZE = SP_MAX_SIZE * 3;
|
static constexpr size_t MAX_REPLY_SIZE = SP_MAX_SIZE * 3;
|
||||||
static const size_t MAX_COMMAND_SIZE = SP_MAX_SIZE;
|
static constexpr size_t MAX_COMMAND_SIZE = SP_MAX_SIZE;
|
||||||
static const size_t MAX_DATA_SIZE = 1016;
|
// 1016 bytes.
|
||||||
|
static constexpr size_t SP_MAX_DATA_SIZE = SP_MAX_SIZE - ccsds::HEADER_LEN - CRC_SIZE;
|
||||||
|
static constexpr size_t FLASH_READ_MIN_OVERHEAD = 16;
|
||||||
|
// 1000 bytes.
|
||||||
|
static const size_t MAX_FLASH_READ_DATA_SIZE = SP_MAX_DATA_SIZE - FLASH_READ_MIN_OVERHEAD;
|
||||||
|
// 1012 bytes, 4 bytes for the write length.
|
||||||
|
static constexpr size_t MAX_FLASH_WRITE_DATA_SIZE = SP_MAX_DATA_SIZE - sizeof(uint32_t);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* The replay write sequence command has a maximum delay for the execution report which amounts to
|
* The replay write sequence command has a maximum delay for the execution report which amounts to
|
||||||
@ -131,7 +210,7 @@ static const uint16_t TC_EXEUTION_DISABLED = 0x5E2;
|
|||||||
static const uint16_t FLASH_MOUNT_FAILED = 0x5E3;
|
static const uint16_t FLASH_MOUNT_FAILED = 0x5E3;
|
||||||
static const uint16_t FLASH_FILE_ALREADY_CLOSED = 0x5E4;
|
static const uint16_t FLASH_FILE_ALREADY_CLOSED = 0x5E4;
|
||||||
static const uint16_t FLASH_FILE_OPEN_FAILED = 0x5E5;
|
static const uint16_t FLASH_FILE_OPEN_FAILED = 0x5E5;
|
||||||
static const uint16_t FLASH_FILE_ALREDY_OPEN = 0x5E6;
|
static const uint16_t FLASH_FILE_ALREADY_OPEN = 0x5E6;
|
||||||
static const uint16_t FLASH_FILE_NOT_OPEN = 0x5E7;
|
static const uint16_t FLASH_FILE_NOT_OPEN = 0x5E7;
|
||||||
static const uint16_t FLASH_UNMOUNT_FAILED = 0x5E8;
|
static const uint16_t FLASH_UNMOUNT_FAILED = 0x5E8;
|
||||||
static const uint16_t HEAP_ALLOCATION_FAILED = 0x5E9;
|
static const uint16_t HEAP_ALLOCATION_FAILED = 0x5E9;
|
||||||
@ -156,7 +235,7 @@ class TcBase : public ploc::SpTcBase, public MPSoCReturnValuesIF {
|
|||||||
virtual ~TcBase() = default;
|
virtual ~TcBase() = default;
|
||||||
|
|
||||||
// Initial length field of space packet. Will always be updated when packet is created.
|
// Initial length field of space packet. Will always be updated when packet is created.
|
||||||
static const uint16_t INIT_LENGTH = 2;
|
static const uint16_t INIT_LENGTH = CRC_SIZE;
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Constructor
|
* @brief Constructor
|
||||||
@ -166,47 +245,23 @@ class TcBase : public ploc::SpTcBase, public MPSoCReturnValuesIF {
|
|||||||
*/
|
*/
|
||||||
TcBase(ploc::SpTcParams params, uint16_t apid, uint16_t sequenceCount)
|
TcBase(ploc::SpTcParams params, uint16_t apid, uint16_t sequenceCount)
|
||||||
: ploc::SpTcBase(params, apid, 0, sequenceCount) {
|
: ploc::SpTcBase(params, apid, 0, sequenceCount) {
|
||||||
|
payloadStart = spParams.buf + ccsds::HEADER_LEN;
|
||||||
spParams.setFullPayloadLen(INIT_LENGTH);
|
spParams.setFullPayloadLen(INIT_LENGTH);
|
||||||
}
|
}
|
||||||
|
|
||||||
ReturnValue_t buildPacket() { return buildPacket(nullptr, 0); }
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Function to initialize the space packet
|
* @brief Function to finsh and write the space packet. It is expected that the user has
|
||||||
*
|
* set the payload fields in the child class*
|
||||||
* @param commandData Pointer to command specific data
|
|
||||||
* @param commandDataLen Length of command data
|
|
||||||
*
|
|
||||||
* @return returnvalue::OK if packet creation was successful, otherwise error return value
|
* @return returnvalue::OK if packet creation was successful, otherwise error return value
|
||||||
*/
|
*/
|
||||||
ReturnValue_t buildPacket(const uint8_t* commandData, size_t commandDataLen) {
|
ReturnValue_t finishPacket() {
|
||||||
payloadStart = spParams.buf + ccsds::HEADER_LEN;
|
|
||||||
ReturnValue_t res;
|
|
||||||
if (commandData != nullptr and commandDataLen > 0) {
|
|
||||||
res = initPacket(commandData, commandDataLen);
|
|
||||||
if (res != returnvalue::OK) {
|
|
||||||
return res;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
updateSpFields();
|
updateSpFields();
|
||||||
res = checkSizeAndSerializeHeader();
|
ReturnValue_t res = checkSizeAndSerializeHeader();
|
||||||
if (res != returnvalue::OK) {
|
if (res != returnvalue::OK) {
|
||||||
return res;
|
return res;
|
||||||
}
|
}
|
||||||
return calcAndSetCrc();
|
return calcAndSetCrc();
|
||||||
}
|
}
|
||||||
|
|
||||||
protected:
|
|
||||||
/**
|
|
||||||
* @brief Must be overwritten by the child class to define the command specific parameters
|
|
||||||
*
|
|
||||||
* @param commandData Pointer to received command data
|
|
||||||
* @param commandDataLen Length of received command data
|
|
||||||
*/
|
|
||||||
virtual ReturnValue_t initPacket(const uint8_t* commandData, size_t commandDataLen) {
|
|
||||||
return returnvalue::OK;
|
|
||||||
}
|
|
||||||
};
|
};
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@ -224,8 +279,7 @@ class TcMemRead : public TcBase {
|
|||||||
|
|
||||||
uint16_t getMemLen() const { return memLen; }
|
uint16_t getMemLen() const { return memLen; }
|
||||||
|
|
||||||
protected:
|
ReturnValue_t setPayload(const uint8_t* commandData, size_t commandDataLen) {
|
||||||
ReturnValue_t initPacket(const uint8_t* commandData, size_t commandDataLen) override {
|
|
||||||
ReturnValue_t result = returnvalue::OK;
|
ReturnValue_t result = returnvalue::OK;
|
||||||
result = lengthCheck(commandDataLen);
|
result = lengthCheck(commandDataLen);
|
||||||
if (result != returnvalue::OK) {
|
if (result != returnvalue::OK) {
|
||||||
@ -271,8 +325,7 @@ class TcMemWrite : public TcBase {
|
|||||||
TcMemWrite(ploc::SpTcParams params, uint16_t sequenceCount)
|
TcMemWrite(ploc::SpTcParams params, uint16_t sequenceCount)
|
||||||
: TcBase(params, apid::TC_MEM_WRITE, sequenceCount) {}
|
: TcBase(params, apid::TC_MEM_WRITE, sequenceCount) {}
|
||||||
|
|
||||||
protected:
|
ReturnValue_t setPayload(const uint8_t* commandData, size_t commandDataLen) {
|
||||||
ReturnValue_t initPacket(const uint8_t* commandData, size_t commandDataLen) override {
|
|
||||||
ReturnValue_t result = returnvalue::OK;
|
ReturnValue_t result = returnvalue::OK;
|
||||||
result = lengthCheck(commandDataLen);
|
result = lengthCheck(commandDataLen);
|
||||||
if (result != returnvalue::OK) {
|
if (result != returnvalue::OK) {
|
||||||
@ -314,72 +367,58 @@ class TcMemWrite : public TcBase {
|
|||||||
/**
|
/**
|
||||||
* @brief Class to help creation of flash fopen command.
|
* @brief Class to help creation of flash fopen command.
|
||||||
*/
|
*/
|
||||||
class FlashFopen : public ploc::SpTcBase {
|
class FlashFopen : public TcBase {
|
||||||
public:
|
public:
|
||||||
FlashFopen(ploc::SpTcParams params, uint16_t sequenceCount)
|
FlashFopen(ploc::SpTcParams params, uint16_t sequenceCount)
|
||||||
: ploc::SpTcBase(params, apid::TC_FLASHFOPEN, sequenceCount) {}
|
: TcBase(params, apid::TC_FLASHFOPEN, sequenceCount) {}
|
||||||
|
|
||||||
static const char APPEND = 'a';
|
ReturnValue_t setPayload(std::string filename, uint8_t mode) {
|
||||||
static const char WRITE = 'w';
|
accessMode = mode;
|
||||||
static const char READ = 'r';
|
|
||||||
|
|
||||||
ReturnValue_t createPacket(std::string filename, char accessMode_) {
|
|
||||||
accessMode = accessMode_;
|
|
||||||
size_t nameSize = filename.size();
|
size_t nameSize = filename.size();
|
||||||
spParams.setFullPayloadLen(nameSize + sizeof(NULL_TERMINATOR) + sizeof(accessMode) + CRC_SIZE);
|
spParams.setFullPayloadLen(256 + sizeof(uint8_t) + CRC_SIZE);
|
||||||
ReturnValue_t result = checkPayloadLen();
|
ReturnValue_t result = checkPayloadLen();
|
||||||
if (result != returnvalue::OK) {
|
if (result != returnvalue::OK) {
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
std::memcpy(payloadStart, filename.c_str(), nameSize);
|
std::memcpy(payloadStart, filename.c_str(), nameSize);
|
||||||
*(spParams.buf + nameSize) = NULL_TERMINATOR;
|
// payloadStart[nameSize] = NULL_TERMINATOR;
|
||||||
std::memcpy(payloadStart + nameSize + sizeof(NULL_TERMINATOR), &accessMode, sizeof(accessMode));
|
std::memset(payloadStart + nameSize, 0, 256 - nameSize);
|
||||||
updateSpFields();
|
// payloadStart[255] = NULL_TERMINATOR;
|
||||||
return calcAndSetCrc();
|
payloadStart[256] = accessMode;
|
||||||
|
return returnvalue::OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
private:
|
private:
|
||||||
char accessMode = APPEND;
|
uint8_t accessMode = FileAccessModes::OPEN_EXISTING;
|
||||||
};
|
};
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Class to help creation of flash fclose command.
|
* @brief Class to help creation of flash fclose command.
|
||||||
*/
|
*/
|
||||||
class FlashFclose : public ploc::SpTcBase {
|
class FlashFclose : public TcBase {
|
||||||
public:
|
public:
|
||||||
FlashFclose(ploc::SpTcParams params, uint16_t sequenceCount)
|
FlashFclose(ploc::SpTcParams params, uint16_t sequenceCount)
|
||||||
: ploc::SpTcBase(params, apid::TC_FLASHFCLOSE, sequenceCount) {}
|
: TcBase(params, apid::TC_FLASHFCLOSE, sequenceCount) {
|
||||||
|
spParams.setFullPayloadLen(CRC_SIZE);
|
||||||
ReturnValue_t createPacket(std::string filename) {
|
|
||||||
size_t nameSize = filename.size();
|
|
||||||
spParams.setFullPayloadLen(nameSize + sizeof(NULL_TERMINATOR) + CRC_SIZE);
|
|
||||||
ReturnValue_t result = checkPayloadLen();
|
|
||||||
if (result != returnvalue::OK) {
|
|
||||||
return result;
|
|
||||||
}
|
|
||||||
std::memcpy(payloadStart, filename.c_str(), nameSize);
|
|
||||||
*(payloadStart + nameSize) = NULL_TERMINATOR;
|
|
||||||
return calcAndSetCrc();
|
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Class to build flash write space packet.
|
* @brief Class to build flash write space packet.
|
||||||
*/
|
*/
|
||||||
class TcFlashWrite : public ploc::SpTcBase {
|
class TcFlashWrite : public TcBase {
|
||||||
public:
|
public:
|
||||||
TcFlashWrite(ploc::SpTcParams params, uint16_t sequenceCount)
|
TcFlashWrite(ploc::SpTcParams params, uint16_t sequenceCount)
|
||||||
: ploc::SpTcBase(params, apid::TC_FLASHWRITE, sequenceCount) {}
|
: TcBase(params, apid::TC_FLASHWRITE, sequenceCount) {}
|
||||||
|
|
||||||
ReturnValue_t buildPacket(const uint8_t* writeData, uint32_t writeLen_) {
|
ReturnValue_t setPayload(const uint8_t* writeData, uint32_t writeLen_) {
|
||||||
ReturnValue_t result = returnvalue::OK;
|
|
||||||
writeLen = writeLen_;
|
writeLen = writeLen_;
|
||||||
if (writeLen > MAX_DATA_SIZE) {
|
if (writeLen > MAX_FLASH_WRITE_DATA_SIZE) {
|
||||||
sif::debug << "FlashWrite::createPacket: Command data too big" << std::endl;
|
sif::error << "TcFlashWrite: Command data too big" << std::endl;
|
||||||
return returnvalue::FAILED;
|
return returnvalue::FAILED;
|
||||||
}
|
}
|
||||||
spParams.setFullPayloadLen(static_cast<uint16_t>(writeLen) + 4 + CRC_SIZE);
|
spParams.setFullPayloadLen(sizeof(uint32_t) + static_cast<uint16_t>(writeLen) + CRC_SIZE);
|
||||||
result = checkPayloadLen();
|
ReturnValue_t result = checkPayloadLen();
|
||||||
if (result != returnvalue::OK) {
|
if (result != returnvalue::OK) {
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
@ -389,11 +428,11 @@ class TcFlashWrite : public ploc::SpTcBase {
|
|||||||
if (result != returnvalue::OK) {
|
if (result != returnvalue::OK) {
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
std::memcpy(payloadStart + sizeof(writeLen), writeData, writeLen);
|
std::memcpy(payloadStart + sizeof(uint32_t), writeData, writeLen);
|
||||||
updateSpFields();
|
updateSpFields();
|
||||||
auto res = checkSizeAndSerializeHeader();
|
result = checkSizeAndSerializeHeader();
|
||||||
if (res != returnvalue::OK) {
|
if (result != returnvalue::OK) {
|
||||||
return res;
|
return result;
|
||||||
}
|
}
|
||||||
return calcAndSetCrc();
|
return calcAndSetCrc();
|
||||||
}
|
}
|
||||||
@ -402,15 +441,52 @@ class TcFlashWrite : public ploc::SpTcBase {
|
|||||||
uint32_t writeLen = 0;
|
uint32_t writeLen = 0;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
class TcFlashRead : public TcBase {
|
||||||
|
public:
|
||||||
|
TcFlashRead(ploc::SpTcParams params, uint16_t sequenceCount)
|
||||||
|
: TcBase(params, apid::TC_FLASHREAD, sequenceCount) {}
|
||||||
|
|
||||||
|
ReturnValue_t setPayload(uint32_t readLen) {
|
||||||
|
if (readLen > MAX_FLASH_READ_DATA_SIZE) {
|
||||||
|
sif::error << "TcFlashRead: Read length " << readLen << " too large" << std::endl;
|
||||||
|
return returnvalue::FAILED;
|
||||||
|
}
|
||||||
|
spParams.setFullPayloadLen(sizeof(uint32_t) + CRC_SIZE);
|
||||||
|
ReturnValue_t result = checkPayloadLen();
|
||||||
|
if (result != returnvalue::OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
size_t serializedSize = ccsds::HEADER_LEN;
|
||||||
|
result = SerializeAdapter::serialize(&readLen, payloadStart, &serializedSize, spParams.maxSize,
|
||||||
|
SerializeIF::Endianness::NETWORK);
|
||||||
|
if (result != returnvalue::OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
updateSpFields();
|
||||||
|
result = checkSizeAndSerializeHeader();
|
||||||
|
if (result != returnvalue::OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
result = calcAndSetCrc();
|
||||||
|
if (result != returnvalue::OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
readSize = readLen;
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t readSize = 0;
|
||||||
|
};
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Class to help creation of flash delete command.
|
* @brief Class to help creation of flash delete command.
|
||||||
*/
|
*/
|
||||||
class TcFlashDelete : public ploc::SpTcBase {
|
class TcFlashDelete : public TcBase {
|
||||||
public:
|
public:
|
||||||
TcFlashDelete(ploc::SpTcParams params, uint16_t sequenceCount)
|
TcFlashDelete(ploc::SpTcParams params, uint16_t sequenceCount)
|
||||||
: ploc::SpTcBase(params, apid::TC_FLASHDELETE, sequenceCount) {}
|
: TcBase(params, apid::TC_FLASHDELETE, sequenceCount) {}
|
||||||
|
|
||||||
ReturnValue_t buildPacket(std::string filename) {
|
ReturnValue_t setPayload(std::string filename) {
|
||||||
size_t nameSize = filename.size();
|
size_t nameSize = filename.size();
|
||||||
spParams.setFullPayloadLen(nameSize + sizeof(NULL_TERMINATOR) + CRC_SIZE);
|
spParams.setFullPayloadLen(nameSize + sizeof(NULL_TERMINATOR) + CRC_SIZE);
|
||||||
auto res = checkPayloadLen();
|
auto res = checkPayloadLen();
|
||||||
@ -449,8 +525,7 @@ class TcReplayStart : public TcBase {
|
|||||||
TcReplayStart(ploc::SpTcParams params, uint16_t sequenceCount)
|
TcReplayStart(ploc::SpTcParams params, uint16_t sequenceCount)
|
||||||
: TcBase(params, apid::TC_REPLAY_START, sequenceCount) {}
|
: TcBase(params, apid::TC_REPLAY_START, sequenceCount) {}
|
||||||
|
|
||||||
protected:
|
ReturnValue_t setPayload(const uint8_t* commandData, size_t commandDataLen) {
|
||||||
ReturnValue_t initPacket(const uint8_t* commandData, size_t commandDataLen) override {
|
|
||||||
ReturnValue_t result = returnvalue::OK;
|
ReturnValue_t result = returnvalue::OK;
|
||||||
spParams.setFullPayloadLen(commandDataLen + CRC_SIZE);
|
spParams.setFullPayloadLen(commandDataLen + CRC_SIZE);
|
||||||
result = lengthCheck(commandDataLen);
|
result = lengthCheck(commandDataLen);
|
||||||
@ -498,8 +573,7 @@ class TcDownlinkPwrOn : public TcBase {
|
|||||||
TcDownlinkPwrOn(ploc::SpTcParams params, uint16_t sequenceCount)
|
TcDownlinkPwrOn(ploc::SpTcParams params, uint16_t sequenceCount)
|
||||||
: TcBase(params, apid::TC_DOWNLINK_PWR_ON, sequenceCount) {}
|
: TcBase(params, apid::TC_DOWNLINK_PWR_ON, sequenceCount) {}
|
||||||
|
|
||||||
protected:
|
ReturnValue_t setPayload(const uint8_t* commandData, size_t commandDataLen) {
|
||||||
ReturnValue_t initPacket(const uint8_t* commandData, size_t commandDataLen) override {
|
|
||||||
ReturnValue_t result = returnvalue::OK;
|
ReturnValue_t result = returnvalue::OK;
|
||||||
result = lengthCheck(commandDataLen);
|
result = lengthCheck(commandDataLen);
|
||||||
if (result != returnvalue::OK) {
|
if (result != returnvalue::OK) {
|
||||||
@ -561,6 +635,30 @@ class TcDownlinkPwrOn : public TcBase {
|
|||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
class TcGetHkReport : public TcBase {
|
||||||
|
public:
|
||||||
|
TcGetHkReport(ploc::SpTcParams params, uint16_t sequenceCount)
|
||||||
|
: TcBase(params, apid::TC_HK_GET_REPORT, sequenceCount) {}
|
||||||
|
};
|
||||||
|
|
||||||
|
class TcGetDirContent : public TcBase {
|
||||||
|
public:
|
||||||
|
TcGetDirContent(ploc::SpTcParams params, uint16_t sequenceCount)
|
||||||
|
: TcBase(params, apid::TC_FLASH_GET_DIRECTORY_CONTENT, sequenceCount) {}
|
||||||
|
|
||||||
|
ReturnValue_t setPayload(const uint8_t* commandData, size_t commandDataLen) {
|
||||||
|
ReturnValue_t result = returnvalue::OK;
|
||||||
|
// Yeah it needs to be 256.. even if the path is shorter.
|
||||||
|
spParams.setFullPayloadLen(256 + CRC_SIZE);
|
||||||
|
if (result != returnvalue::OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
std::memcpy(payloadStart, commandData, commandDataLen);
|
||||||
|
payloadStart[255] = '\0';
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Class to build replay stop space packet.
|
* @brief Class to build replay stop space packet.
|
||||||
*/
|
*/
|
||||||
@ -581,8 +679,7 @@ class TcReplayWriteSeq : public TcBase {
|
|||||||
TcReplayWriteSeq(ploc::SpTcParams params, uint16_t sequenceCount)
|
TcReplayWriteSeq(ploc::SpTcParams params, uint16_t sequenceCount)
|
||||||
: TcBase(params, apid::TC_REPLAY_WRITE_SEQUENCE, sequenceCount) {}
|
: TcBase(params, apid::TC_REPLAY_WRITE_SEQUENCE, sequenceCount) {}
|
||||||
|
|
||||||
protected:
|
ReturnValue_t setPayload(const uint8_t* commandData, size_t commandDataLen) {
|
||||||
ReturnValue_t initPacket(const uint8_t* commandData, size_t commandDataLen) override {
|
|
||||||
ReturnValue_t result = returnvalue::OK;
|
ReturnValue_t result = returnvalue::OK;
|
||||||
spParams.setFullPayloadLen(commandDataLen + sizeof(NULL_TERMINATOR) + CRC_SIZE);
|
spParams.setFullPayloadLen(commandDataLen + sizeof(NULL_TERMINATOR) + CRC_SIZE);
|
||||||
result = lengthCheck(commandDataLen);
|
result = lengthCheck(commandDataLen);
|
||||||
@ -611,36 +708,69 @@ class TcReplayWriteSeq : public TcBase {
|
|||||||
/**
|
/**
|
||||||
* @brief Helps to extract the fields of the flash write command from the PUS packet.
|
* @brief Helps to extract the fields of the flash write command from the PUS packet.
|
||||||
*/
|
*/
|
||||||
class FlashWritePusCmd : public MPSoCReturnValuesIF {
|
class FlashBasePusCmd : public MPSoCReturnValuesIF {
|
||||||
public:
|
public:
|
||||||
FlashWritePusCmd(){};
|
FlashBasePusCmd() = default;
|
||||||
|
virtual ~FlashBasePusCmd() = default;
|
||||||
|
|
||||||
ReturnValue_t extractFields(const uint8_t* commandData, size_t commandDataLen) {
|
virtual ReturnValue_t extractFields(const uint8_t* commandData, size_t commandDataLen) {
|
||||||
if (commandDataLen > (config::MAX_PATH_SIZE + config::MAX_FILENAME_SIZE + MAX_FILENAME_SIZE)) {
|
if (commandDataLen > (config::MAX_PATH_SIZE + config::MAX_FILENAME_SIZE + MAX_FILENAME_SIZE)) {
|
||||||
return INVALID_LENGTH;
|
return INVALID_LENGTH;
|
||||||
}
|
}
|
||||||
obcFile = std::string(reinterpret_cast<const char*>(commandData));
|
size_t fileLen = strnlen(reinterpret_cast<const char*>(commandData), commandDataLen);
|
||||||
if (obcFile.size() > (config::MAX_PATH_SIZE + config::MAX_FILENAME_SIZE)) {
|
if (fileLen > (config::MAX_PATH_SIZE + config::MAX_FILENAME_SIZE)) {
|
||||||
return FILENAME_TOO_LONG;
|
return FILENAME_TOO_LONG;
|
||||||
}
|
}
|
||||||
mpsocFile = std::string(
|
obcFile = std::string(reinterpret_cast<const char*>(commandData), fileLen);
|
||||||
reinterpret_cast<const char*>(commandData + obcFile.size() + SIZE_NULL_TERMINATOR));
|
fileLen =
|
||||||
if (mpsocFile.size() > MAX_FILENAME_SIZE) {
|
strnlen(reinterpret_cast<const char*>(commandData + obcFile.size() + SIZE_NULL_TERMINATOR),
|
||||||
|
commandDataLen - obcFile.size() - 1);
|
||||||
|
if (fileLen > MAX_FILENAME_SIZE) {
|
||||||
return MPSOC_FILENAME_TOO_LONG;
|
return MPSOC_FILENAME_TOO_LONG;
|
||||||
}
|
}
|
||||||
|
mpsocFile = std::string(
|
||||||
|
reinterpret_cast<const char*>(commandData + obcFile.size() + SIZE_NULL_TERMINATOR),
|
||||||
|
fileLen);
|
||||||
return returnvalue::OK;
|
return returnvalue::OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
std::string getObcFile() { return obcFile; }
|
const std::string& getObcFile() const { return obcFile; }
|
||||||
|
|
||||||
std::string getMPSoCFile() { return mpsocFile; }
|
const std::string& getMPSoCFile() const { return mpsocFile; }
|
||||||
|
|
||||||
|
protected:
|
||||||
|
size_t getParsedSize() const {
|
||||||
|
return getObcFile().size() + getMPSoCFile().size() + 2 * SIZE_NULL_TERMINATOR;
|
||||||
|
}
|
||||||
|
static const size_t SIZE_NULL_TERMINATOR = 1;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
static const size_t SIZE_NULL_TERMINATOR = 1;
|
std::string obcFile;
|
||||||
std::string obcFile = "";
|
std::string mpsocFile;
|
||||||
std::string mpsocFile = "";
|
|
||||||
};
|
};
|
||||||
|
|
||||||
|
class FlashReadPusCmd : public FlashBasePusCmd {
|
||||||
|
public:
|
||||||
|
FlashReadPusCmd(){};
|
||||||
|
|
||||||
|
ReturnValue_t extractFields(const uint8_t* commandData, size_t commandDataLen) override {
|
||||||
|
ReturnValue_t result = FlashBasePusCmd::extractFields(commandData, commandDataLen);
|
||||||
|
if (result != returnvalue::OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
if (commandDataLen < (getParsedSize() + 4)) {
|
||||||
|
return returnvalue::FAILED;
|
||||||
|
}
|
||||||
|
size_t deserDummy = 4;
|
||||||
|
return SerializeAdapter::deSerialize(&readSize, commandData + getParsedSize(), &deserDummy,
|
||||||
|
SerializeIF::Endianness::NETWORK);
|
||||||
|
}
|
||||||
|
|
||||||
|
size_t getReadSize() const { return readSize; }
|
||||||
|
|
||||||
|
private:
|
||||||
|
size_t readSize = 0;
|
||||||
|
};
|
||||||
/**
|
/**
|
||||||
* @brief Class to build replay stop space packet.
|
* @brief Class to build replay stop space packet.
|
||||||
*/
|
*/
|
||||||
@ -676,7 +806,7 @@ class TcCamTakePic : public TcBase {
|
|||||||
TcCamTakePic(ploc::SpTcParams params, uint16_t sequenceCount)
|
TcCamTakePic(ploc::SpTcParams params, uint16_t sequenceCount)
|
||||||
: TcBase(params, apid::TC_CAM_TAKE_PIC, sequenceCount) {}
|
: TcBase(params, apid::TC_CAM_TAKE_PIC, sequenceCount) {}
|
||||||
|
|
||||||
ReturnValue_t initPacket(const uint8_t* commandData, size_t commandDataLen) override {
|
ReturnValue_t setPayload(const uint8_t* commandData, size_t commandDataLen) {
|
||||||
if (commandDataLen > MAX_DATA_LENGTH) {
|
if (commandDataLen > MAX_DATA_LENGTH) {
|
||||||
return INVALID_LENGTH;
|
return INVALID_LENGTH;
|
||||||
}
|
}
|
||||||
@ -705,7 +835,7 @@ class TcSimplexSendFile : public TcBase {
|
|||||||
TcSimplexSendFile(ploc::SpTcParams params, uint16_t sequenceCount)
|
TcSimplexSendFile(ploc::SpTcParams params, uint16_t sequenceCount)
|
||||||
: TcBase(params, apid::TC_SIMPLEX_SEND_FILE, sequenceCount) {}
|
: TcBase(params, apid::TC_SIMPLEX_SEND_FILE, sequenceCount) {}
|
||||||
|
|
||||||
ReturnValue_t initPacket(const uint8_t* commandData, size_t commandDataLen) override {
|
ReturnValue_t setPayload(const uint8_t* commandData, size_t commandDataLen) {
|
||||||
if (commandDataLen > MAX_DATA_LENGTH) {
|
if (commandDataLen > MAX_DATA_LENGTH) {
|
||||||
return INVALID_LENGTH;
|
return INVALID_LENGTH;
|
||||||
}
|
}
|
||||||
@ -730,7 +860,7 @@ class TcDownlinkDataModulate : public TcBase {
|
|||||||
TcDownlinkDataModulate(ploc::SpTcParams params, uint16_t sequenceCount)
|
TcDownlinkDataModulate(ploc::SpTcParams params, uint16_t sequenceCount)
|
||||||
: TcBase(params, apid::TC_DOWNLINK_DATA_MODULATE, sequenceCount) {}
|
: TcBase(params, apid::TC_DOWNLINK_DATA_MODULATE, sequenceCount) {}
|
||||||
|
|
||||||
ReturnValue_t initPacket(const uint8_t* commandData, size_t commandDataLen) override {
|
ReturnValue_t setPayload(const uint8_t* commandData, size_t commandDataLen) {
|
||||||
if (commandDataLen > MAX_DATA_LENGTH) {
|
if (commandDataLen > MAX_DATA_LENGTH) {
|
||||||
return INVALID_LENGTH;
|
return INVALID_LENGTH;
|
||||||
}
|
}
|
||||||
@ -748,8 +878,7 @@ class TcCamcmdSend : public TcBase {
|
|||||||
TcCamcmdSend(ploc::SpTcParams params, uint16_t sequenceCount)
|
TcCamcmdSend(ploc::SpTcParams params, uint16_t sequenceCount)
|
||||||
: TcBase(params, apid::TC_CAM_CMD_SEND, sequenceCount) {}
|
: TcBase(params, apid::TC_CAM_CMD_SEND, sequenceCount) {}
|
||||||
|
|
||||||
protected:
|
ReturnValue_t setPayload(const uint8_t* commandData, size_t commandDataLen) {
|
||||||
ReturnValue_t initPacket(const uint8_t* commandData, size_t commandDataLen) override {
|
|
||||||
if (commandDataLen > MAX_DATA_LENGTH) {
|
if (commandDataLen > MAX_DATA_LENGTH) {
|
||||||
return INVALID_LENGTH;
|
return INVALID_LENGTH;
|
||||||
}
|
}
|
||||||
@ -774,6 +903,69 @@ class TcCamcmdSend : public TcBase {
|
|||||||
static const uint8_t CARRIAGE_RETURN = 0xD;
|
static const uint8_t CARRIAGE_RETURN = 0xD;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
class HkReport : public StaticLocalDataSet<36> {
|
||||||
|
public:
|
||||||
|
HkReport(HasLocalDataPoolIF* owner) : StaticLocalDataSet(owner, HK_SET_ID) {}
|
||||||
|
|
||||||
|
HkReport(object_id_t objectId) : StaticLocalDataSet(sid_t(objectId, HK_SET_ID)) {}
|
||||||
|
|
||||||
|
lp_var_t<uint32_t> status = lp_var_t<uint32_t>(sid.objectId, mpsoc::poolid::STATUS, this);
|
||||||
|
lp_var_t<uint8_t> mode = lp_var_t<uint8_t>(sid.objectId, mpsoc::poolid::MODE, this);
|
||||||
|
lp_var_t<uint8_t> downlinkPwrOn =
|
||||||
|
lp_var_t<uint8_t>(sid.objectId, mpsoc::poolid::DOWNLINK_PWR_ON, this);
|
||||||
|
lp_var_t<uint8_t> downlinkReplyActive =
|
||||||
|
lp_var_t<uint8_t>(sid.objectId, mpsoc::poolid::DOWNLINK_REPLY_ACTIIVE, this);
|
||||||
|
lp_var_t<uint8_t> downlinkJesdSyncStatus =
|
||||||
|
lp_var_t<uint8_t>(sid.objectId, mpsoc::poolid::DOWNLINK_JESD_SYNC_STATUS, this);
|
||||||
|
lp_var_t<uint8_t> downlinkDacStatus =
|
||||||
|
lp_var_t<uint8_t>(sid.objectId, mpsoc::poolid::DOWNLINK_DAC_STATUS, this);
|
||||||
|
lp_var_t<uint8_t> camStatus = lp_var_t<uint8_t>(sid.objectId, mpsoc::poolid::CAM_STATUS, this);
|
||||||
|
lp_var_t<uint8_t> camSdiStatus =
|
||||||
|
lp_var_t<uint8_t>(sid.objectId, mpsoc::poolid::CAM_SDI_STATUS, this);
|
||||||
|
lp_var_t<float> camFpgaTemp = lp_var_t<float>(sid.objectId, mpsoc::poolid::CAM_FPGA_TEMP, this);
|
||||||
|
lp_var_t<float> camSocTemp = lp_var_t<float>(sid.objectId, mpsoc::poolid::CAM_SOC_TEMP, this);
|
||||||
|
lp_var_t<float> sysmonTemp = lp_var_t<float>(sid.objectId, mpsoc::poolid::SYSMON_TEMP, this);
|
||||||
|
lp_var_t<float> sysmonVccInt = lp_var_t<float>(sid.objectId, mpsoc::poolid::SYSMON_VCCINT, this);
|
||||||
|
lp_var_t<float> sysmonVccAux = lp_var_t<float>(sid.objectId, mpsoc::poolid::SYSMON_VCCAUX, this);
|
||||||
|
lp_var_t<float> sysmonVccBram =
|
||||||
|
lp_var_t<float>(sid.objectId, mpsoc::poolid::SYSMON_VCCBRAM, this);
|
||||||
|
lp_var_t<float> sysmonVccPaux =
|
||||||
|
lp_var_t<float>(sid.objectId, mpsoc::poolid::SYSMON_VCCPAUX, this);
|
||||||
|
lp_var_t<float> sysmonVccPint =
|
||||||
|
lp_var_t<float>(sid.objectId, mpsoc::poolid::SYSMON_VCCPINT, this);
|
||||||
|
lp_var_t<float> sysmonVccPdro =
|
||||||
|
lp_var_t<float>(sid.objectId, mpsoc::poolid::SYSMON_VCCPDRO, this);
|
||||||
|
lp_var_t<float> sysmonMb12V = lp_var_t<float>(sid.objectId, mpsoc::poolid::SYSMON_MB12V, this);
|
||||||
|
lp_var_t<float> sysmonMb3V3 = lp_var_t<float>(sid.objectId, mpsoc::poolid::SYSMON_MB3V3, this);
|
||||||
|
lp_var_t<float> sysmonMb1V8 = lp_var_t<float>(sid.objectId, mpsoc::poolid::SYSMON_MB1V8, this);
|
||||||
|
lp_var_t<float> sysmonVcc12V = lp_var_t<float>(sid.objectId, mpsoc::poolid::SYSMON_VCC12V, this);
|
||||||
|
lp_var_t<float> sysmonVcc5V = lp_var_t<float>(sid.objectId, mpsoc::poolid::SYSMON_VCC5V, this);
|
||||||
|
lp_var_t<float> sysmonVcc3V3 = lp_var_t<float>(sid.objectId, mpsoc::poolid::SYSMON_VCC3V3, this);
|
||||||
|
lp_var_t<float> sysmonVcc3V3VA =
|
||||||
|
lp_var_t<float>(sid.objectId, mpsoc::poolid::SYSMON_VCC3V3VA, this);
|
||||||
|
lp_var_t<float> sysmonVcc2V5DDR =
|
||||||
|
lp_var_t<float>(sid.objectId, mpsoc::poolid::SYSMON_VCC2V5DDR, this);
|
||||||
|
lp_var_t<float> sysmonVcc1V2DDR =
|
||||||
|
lp_var_t<float>(sid.objectId, mpsoc::poolid::SYSMON_VCC1V2DDR, this);
|
||||||
|
lp_var_t<float> sysmonVcc0V9 = lp_var_t<float>(sid.objectId, mpsoc::poolid::SYSMON_VCC0V9, this);
|
||||||
|
lp_var_t<float> sysmonVcc0V6VTT =
|
||||||
|
lp_var_t<float>(sid.objectId, mpsoc::poolid::SYSMON_VCC0V6VTT, this);
|
||||||
|
lp_var_t<float> sysmonSafeCotsCur =
|
||||||
|
lp_var_t<float>(sid.objectId, mpsoc::poolid::SYSMON_SAFE_COTS_CUR, this);
|
||||||
|
lp_var_t<float> sysmonNvm4XoCur =
|
||||||
|
lp_var_t<float>(sid.objectId, mpsoc::poolid::SYSMON_NVM4_XO_CUR, this);
|
||||||
|
lp_var_t<uint16_t> semUncorrectableErrs =
|
||||||
|
lp_var_t<uint16_t>(sid.objectId, mpsoc::poolid::SEM_UNCORRECTABLE_ERRS, this);
|
||||||
|
lp_var_t<uint16_t> semCorrectableErrs =
|
||||||
|
lp_var_t<uint16_t>(sid.objectId, mpsoc::poolid::SEM_CORRECTABLE_ERRS, this);
|
||||||
|
lp_var_t<uint8_t> semStatus = lp_var_t<uint8_t>(sid.objectId, mpsoc::poolid::SEM_STATUS, this);
|
||||||
|
lp_var_t<uint8_t> rebootMpsocRequired =
|
||||||
|
lp_var_t<uint8_t>(sid.objectId, mpsoc::poolid::REBOOT_MPSOC_REQUIRED, this);
|
||||||
|
};
|
||||||
|
|
||||||
|
uint16_t getStatusFromRawData(const uint8_t* data);
|
||||||
|
std::string getStatusString(uint16_t status);
|
||||||
|
|
||||||
} // namespace mpsoc
|
} // namespace mpsoc
|
||||||
|
|
||||||
#endif /* MISSION_DEVICES_DEVICEDEFINITIONS_PLOCMPSOCDEFINITIONS_H_ */
|
#endif /* MISSION_DEVICES_DEVICEDEFINITIONS_PLOCMPSOCDEFINITIONS_H_ */
|
@ -15,7 +15,7 @@ GyrAdis1650XHandler::GyrAdis1650XHandler(object_id_t objectId, object_id_t devic
|
|||||||
}
|
}
|
||||||
|
|
||||||
void GyrAdis1650XHandler::doStartUp() {
|
void GyrAdis1650XHandler::doStartUp() {
|
||||||
if (internalState != InternalState::STARTUP) {
|
if (internalState == InternalState::NONE) {
|
||||||
internalState = InternalState::STARTUP;
|
internalState = InternalState::STARTUP;
|
||||||
commandExecuted = false;
|
commandExecuted = false;
|
||||||
}
|
}
|
||||||
@ -24,13 +24,14 @@ void GyrAdis1650XHandler::doStartUp() {
|
|||||||
if (not commandExecuted) {
|
if (not commandExecuted) {
|
||||||
warningSwitch = true;
|
warningSwitch = true;
|
||||||
breakCountdown.setTimeout(adis1650x::START_UP_TIME);
|
breakCountdown.setTimeout(adis1650x::START_UP_TIME);
|
||||||
|
updatePeriodicReply(true, adis1650x::REPLY);
|
||||||
commandExecuted = true;
|
commandExecuted = true;
|
||||||
}
|
}
|
||||||
if (breakCountdown.hasTimedOut()) {
|
|
||||||
updatePeriodicReply(true, adis1650x::REPLY);
|
|
||||||
setMode(MODE_ON);
|
|
||||||
internalState = InternalState::NONE;
|
|
||||||
}
|
}
|
||||||
|
if (internalState == InternalState::STARTUP_DONE) {
|
||||||
|
setMode(MODE_ON);
|
||||||
|
commandExecuted = false;
|
||||||
|
internalState = InternalState::NONE;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -61,6 +62,7 @@ ReturnValue_t GyrAdis1650XHandler::buildTransitionDeviceCommand(DeviceCommandId_
|
|||||||
return NOTHING_TO_SEND;
|
return NOTHING_TO_SEND;
|
||||||
}
|
}
|
||||||
*id = adis1650x::REQUEST;
|
*id = adis1650x::REQUEST;
|
||||||
|
adisRequest.cfg.decRateReg = adis1650x::DEC_RATE;
|
||||||
return preparePeriodicRequest(acs::SimpleSensorMode::NORMAL);
|
return preparePeriodicRequest(acs::SimpleSensorMode::NORMAL);
|
||||||
}
|
}
|
||||||
case (InternalState::SHUTDOWN): {
|
case (InternalState::SHUTDOWN): {
|
||||||
@ -91,6 +93,9 @@ ReturnValue_t GyrAdis1650XHandler::scanForReply(const uint8_t *start, size_t rem
|
|||||||
getMode() == _MODE_POWER_DOWN) {
|
getMode() == _MODE_POWER_DOWN) {
|
||||||
return IGNORE_FULL_PACKET;
|
return IGNORE_FULL_PACKET;
|
||||||
}
|
}
|
||||||
|
if (internalState == InternalState::STARTUP) {
|
||||||
|
internalState = InternalState::STARTUP_DONE;
|
||||||
|
}
|
||||||
*foundLen = remainingSize;
|
*foundLen = remainingSize;
|
||||||
if (remainingSize != sizeof(acs::Adis1650XReply)) {
|
if (remainingSize != sizeof(acs::Adis1650XReply)) {
|
||||||
return returnvalue::FAILED;
|
return returnvalue::FAILED;
|
||||||
|
@ -48,7 +48,7 @@ class GyrAdis1650XHandler : public DeviceHandlerBase {
|
|||||||
|
|
||||||
bool warningSwitch = true;
|
bool warningSwitch = true;
|
||||||
|
|
||||||
enum class InternalState { NONE, STARTUP, SHUTDOWN };
|
enum class InternalState { NONE, STARTUP, STARTUP_DONE, SHUTDOWN };
|
||||||
|
|
||||||
InternalState internalState = InternalState::STARTUP;
|
InternalState internalState = InternalState::STARTUP;
|
||||||
bool commandExecuted = false;
|
bool commandExecuted = false;
|
||||||
|
@ -8,11 +8,6 @@
|
|||||||
|
|
||||||
namespace acs {
|
namespace acs {
|
||||||
|
|
||||||
struct Adis1650XRequest {
|
|
||||||
SimpleSensorMode mode;
|
|
||||||
adis1650x::Type type;
|
|
||||||
};
|
|
||||||
|
|
||||||
struct Adis1650XConfig {
|
struct Adis1650XConfig {
|
||||||
uint16_t diagStat;
|
uint16_t diagStat;
|
||||||
uint16_t filterSetting;
|
uint16_t filterSetting;
|
||||||
@ -22,6 +17,12 @@ struct Adis1650XConfig {
|
|||||||
uint16_t prodId;
|
uint16_t prodId;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
struct Adis1650XRequest {
|
||||||
|
SimpleSensorMode mode;
|
||||||
|
adis1650x::Type type;
|
||||||
|
Adis1650XConfig cfg;
|
||||||
|
};
|
||||||
|
|
||||||
struct Adis1650XData {
|
struct Adis1650XData {
|
||||||
double sensitivity = 0.0;
|
double sensitivity = 0.0;
|
||||||
// Angular velocities in all axes (X, Y and Z)
|
// Angular velocities in all axes (X, Y and Z)
|
||||||
|
@ -52,3 +52,14 @@ double adis1650x::rangMdlToSensitivity(uint16_t rangMdl) {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void adis1650x::prepareWriteRegCommand(uint8_t regStart, uint16_t val, uint8_t* outBuf,
|
||||||
|
size_t maxLen) {
|
||||||
|
if (maxLen < 4) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
outBuf[0] = regStart | adis1650x::WRITE_MASK;
|
||||||
|
outBuf[1] = val & 0xff;
|
||||||
|
outBuf[2] = (regStart + 1) | adis1650x::WRITE_MASK;
|
||||||
|
outBuf[3] = (val >> 8) & 0xff;
|
||||||
|
}
|
||||||
|
@ -16,6 +16,8 @@ enum class BurstModes {
|
|||||||
};
|
};
|
||||||
|
|
||||||
size_t prepareReadCommand(const uint8_t* regList, size_t len, uint8_t* outBuf, size_t maxLen);
|
size_t prepareReadCommand(const uint8_t* regList, size_t len, uint8_t* outBuf, size_t maxLen);
|
||||||
|
void prepareWriteRegCommand(uint8_t regStart, uint16_t val, uint8_t* outBuf, size_t maxLen);
|
||||||
|
|
||||||
BurstModes burstModeFromMscCtrl(uint16_t mscCtrl);
|
BurstModes burstModeFromMscCtrl(uint16_t mscCtrl);
|
||||||
double rangMdlToSensitivity(uint16_t rangMdl);
|
double rangMdlToSensitivity(uint16_t rangMdl);
|
||||||
|
|
||||||
@ -92,6 +94,9 @@ static constexpr size_t SENSOR_READOUT_SIZE = 20 + 2;
|
|||||||
static constexpr uint32_t ADIS_DATASET_ID = READ_SENSOR_DATA;
|
static constexpr uint32_t ADIS_DATASET_ID = READ_SENSOR_DATA;
|
||||||
static constexpr uint32_t ADIS_CFG_DATASET_ID = READ_OUT_CONFIG;
|
static constexpr uint32_t ADIS_CFG_DATASET_ID = READ_OUT_CONFIG;
|
||||||
|
|
||||||
|
static constexpr uint16_t FILT_CTRL = 0x0000;
|
||||||
|
static constexpr uint16_t DEC_RATE = 0x00C7;
|
||||||
|
|
||||||
enum GlobCmds : uint8_t {
|
enum GlobCmds : uint8_t {
|
||||||
FACTORY_CALIBRATION = 0b0000'0010,
|
FACTORY_CALIBRATION = 0b0000'0010,
|
||||||
SENSOR_SELF_TEST = 0b0000'0100,
|
SENSOR_SELF_TEST = 0b0000'0100,
|
||||||
|
@ -17,6 +17,7 @@ extern "C" {
|
|||||||
#include <thread>
|
#include <thread>
|
||||||
|
|
||||||
#include "OBSWConfig.h"
|
#include "OBSWConfig.h"
|
||||||
|
#include "eive/definitions.h"
|
||||||
|
|
||||||
std::atomic_bool JCFG_DONE(false);
|
std::atomic_bool JCFG_DONE(false);
|
||||||
|
|
||||||
@ -99,6 +100,19 @@ void StarTrackerHandler::doShutDown() {
|
|||||||
startupState = StartupState::IDLE;
|
startupState = StartupState::IDLE;
|
||||||
bootState = FwBootState::NONE;
|
bootState = FwBootState::NONE;
|
||||||
solutionSet.setReportingEnabled(false);
|
solutionSet.setReportingEnabled(false);
|
||||||
|
{
|
||||||
|
PoolReadGuard pg(&solutionSet);
|
||||||
|
solutionSet.caliQw.value = 0.0;
|
||||||
|
solutionSet.caliQx.value = 0.0;
|
||||||
|
solutionSet.caliQy.value = 0.0;
|
||||||
|
solutionSet.caliQz.value = 0.0;
|
||||||
|
solutionSet.isTrustWorthy = 0;
|
||||||
|
solutionSet.setValidity(false, true);
|
||||||
|
}
|
||||||
|
{
|
||||||
|
PoolReadGuard pg(&temperatureSet);
|
||||||
|
temperatureSet.setValidity(false, true);
|
||||||
|
}
|
||||||
reinitNextSetParam = false;
|
reinitNextSetParam = false;
|
||||||
setMode(_MODE_POWER_DOWN);
|
setMode(_MODE_POWER_DOWN);
|
||||||
}
|
}
|
||||||
@ -152,7 +166,7 @@ ReturnValue_t StarTrackerHandler::executeAction(ActionId_t actionId, MessageQueu
|
|||||||
return EXECUTION_FINISHED;
|
return EXECUTION_FINISHED;
|
||||||
}
|
}
|
||||||
case (startracker::SET_JSON_FILE_NAME): {
|
case (startracker::SET_JSON_FILE_NAME): {
|
||||||
if (size > MAX_PATH_SIZE) {
|
if (size > config::MAX_PATH_SIZE) {
|
||||||
return FILE_PATH_TOO_LONG;
|
return FILE_PATH_TOO_LONG;
|
||||||
}
|
}
|
||||||
paramJsonFile = std::string(reinterpret_cast<const char*>(data), size);
|
paramJsonFile = std::string(reinterpret_cast<const char*>(data), size);
|
||||||
@ -189,7 +203,7 @@ ReturnValue_t StarTrackerHandler::executeAction(ActionId_t actionId, MessageQueu
|
|||||||
if (result != returnvalue::OK) {
|
if (result != returnvalue::OK) {
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
if (size > MAX_PATH_SIZE + MAX_FILE_NAME) {
|
if (size > config::MAX_PATH_SIZE + config::MAX_FILENAME_SIZE) {
|
||||||
return FILE_PATH_TOO_LONG;
|
return FILE_PATH_TOO_LONG;
|
||||||
}
|
}
|
||||||
result = strHelper->startImageUpload(std::string(reinterpret_cast<const char*>(data), size));
|
result = strHelper->startImageUpload(std::string(reinterpret_cast<const char*>(data), size));
|
||||||
@ -204,7 +218,7 @@ ReturnValue_t StarTrackerHandler::executeAction(ActionId_t actionId, MessageQueu
|
|||||||
if (result != returnvalue::OK) {
|
if (result != returnvalue::OK) {
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
if (size > MAX_PATH_SIZE) {
|
if (size > config::MAX_PATH_SIZE) {
|
||||||
return FILE_PATH_TOO_LONG;
|
return FILE_PATH_TOO_LONG;
|
||||||
}
|
}
|
||||||
result =
|
result =
|
||||||
@ -228,14 +242,14 @@ ReturnValue_t StarTrackerHandler::executeAction(ActionId_t actionId, MessageQueu
|
|||||||
return EXECUTION_FINISHED;
|
return EXECUTION_FINISHED;
|
||||||
}
|
}
|
||||||
case (startracker::CHANGE_IMAGE_DOWNLOAD_FILE): {
|
case (startracker::CHANGE_IMAGE_DOWNLOAD_FILE): {
|
||||||
if (size > MAX_FILE_NAME) {
|
if (size > config::MAX_FILENAME_SIZE) {
|
||||||
return FILENAME_TOO_LONG;
|
return FILENAME_TOO_LONG;
|
||||||
}
|
}
|
||||||
strHelper->setDownloadImageName(std::string(reinterpret_cast<const char*>(data), size));
|
strHelper->setDownloadImageName(std::string(reinterpret_cast<const char*>(data), size));
|
||||||
return EXECUTION_FINISHED;
|
return EXECUTION_FINISHED;
|
||||||
}
|
}
|
||||||
case (startracker::SET_FLASH_READ_FILENAME): {
|
case (startracker::SET_FLASH_READ_FILENAME): {
|
||||||
if (size > MAX_FILE_NAME) {
|
if (size > config::MAX_FILENAME_SIZE) {
|
||||||
return FILENAME_TOO_LONG;
|
return FILENAME_TOO_LONG;
|
||||||
}
|
}
|
||||||
strHelper->setFlashReadFilename(std::string(reinterpret_cast<const char*>(data), size));
|
strHelper->setFlashReadFilename(std::string(reinterpret_cast<const char*>(data), size));
|
||||||
@ -246,7 +260,7 @@ ReturnValue_t StarTrackerHandler::executeAction(ActionId_t actionId, MessageQueu
|
|||||||
if (result != returnvalue::OK) {
|
if (result != returnvalue::OK) {
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
if (size > MAX_PATH_SIZE + MAX_FILE_NAME) {
|
if (size > config::MAX_PATH_SIZE + config::MAX_FILENAME_SIZE) {
|
||||||
return FILE_PATH_TOO_LONG;
|
return FILE_PATH_TOO_LONG;
|
||||||
}
|
}
|
||||||
result =
|
result =
|
||||||
@ -1568,7 +1582,7 @@ ReturnValue_t StarTrackerHandler::executeFlashReadCommand(const uint8_t* command
|
|||||||
<< std::endl;
|
<< std::endl;
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
if (commandDataLen - sizeof(startRegion) - sizeof(length) > MAX_PATH_SIZE) {
|
if (commandDataLen - sizeof(startRegion) - sizeof(length) > config::MAX_PATH_SIZE) {
|
||||||
sif::warning << "StarTrackerHandler::executeFlashReadCommand: Received command with invalid"
|
sif::warning << "StarTrackerHandler::executeFlashReadCommand: Received command with invalid"
|
||||||
<< " path and filename" << std::endl;
|
<< " path and filename" << std::endl;
|
||||||
return FILE_PATH_TOO_LONG;
|
return FILE_PATH_TOO_LONG;
|
||||||
@ -1708,7 +1722,7 @@ ReturnValue_t StarTrackerHandler::prepareParamCommand(const uint8_t* commandData
|
|||||||
bool reinitSet) {
|
bool reinitSet) {
|
||||||
// Stopwatch watch;
|
// Stopwatch watch;
|
||||||
ReturnValue_t result = returnvalue::OK;
|
ReturnValue_t result = returnvalue::OK;
|
||||||
if (commandDataLen > MAX_PATH_SIZE) {
|
if (commandDataLen > config::MAX_PATH_SIZE) {
|
||||||
return FILE_PATH_TOO_LONG;
|
return FILE_PATH_TOO_LONG;
|
||||||
}
|
}
|
||||||
if (reinitSet) {
|
if (reinitSet) {
|
||||||
|
@ -144,9 +144,6 @@ class StarTrackerHandler : public DeviceHandlerBase {
|
|||||||
//! [EXPORT] : [COMMENT] Failed to boot star tracker into bootloader mode
|
//! [EXPORT] : [COMMENT] Failed to boot star tracker into bootloader mode
|
||||||
static const Event BOOTING_BOOTLOADER_FAILED_EVENT = MAKE_EVENT(2, severity::LOW);
|
static const Event BOOTING_BOOTLOADER_FAILED_EVENT = MAKE_EVENT(2, severity::LOW);
|
||||||
|
|
||||||
static const size_t MAX_PATH_SIZE = 50;
|
|
||||||
static const size_t MAX_FILE_NAME = 30;
|
|
||||||
|
|
||||||
static const uint8_t STATUS_OFFSET = 2;
|
static const uint8_t STATUS_OFFSET = 2;
|
||||||
static const uint8_t PARAMS_OFFSET = 2;
|
static const uint8_t PARAMS_OFFSET = 2;
|
||||||
static const uint8_t TICKS_OFFSET = 3;
|
static const uint8_t TICKS_OFFSET = 3;
|
||||||
|
@ -94,13 +94,6 @@ void TmStoreTaskBase::cancelDump(DumpContext& ctx, PersistentTmStore& store, boo
|
|||||||
ReturnValue_t TmStoreTaskBase::handleOneDump(PersistentTmStoreWithTmQueue& store,
|
ReturnValue_t TmStoreTaskBase::handleOneDump(PersistentTmStoreWithTmQueue& store,
|
||||||
DumpContext& dumpContext, bool& dumpPerformed) {
|
DumpContext& dumpContext, bool& dumpPerformed) {
|
||||||
ReturnValue_t result = returnvalue::OK;
|
ReturnValue_t result = returnvalue::OK;
|
||||||
// The PTME might have been reset an transmitter state change, so there is no point in continuing
|
|
||||||
// the dump.
|
|
||||||
// TODO: Will be solved in a cleaner way, this is kind of a hack.
|
|
||||||
if (not channel.isTxOn()) {
|
|
||||||
cancelDump(dumpContext, store, false);
|
|
||||||
return returnvalue::FAILED;
|
|
||||||
}
|
|
||||||
// It is assumed that the PTME will only be locked for a short period (e.g. to change datarate).
|
// It is assumed that the PTME will only be locked for a short period (e.g. to change datarate).
|
||||||
if (not channel.isBusy() and not ptmeLocked) {
|
if (not channel.isBusy() and not ptmeLocked) {
|
||||||
performDump(store, dumpContext, dumpPerformed);
|
performDump(store, dumpContext, dumpPerformed);
|
||||||
@ -138,25 +131,22 @@ ReturnValue_t TmStoreTaskBase::performDump(PersistentTmStoreWithTmQueue& store,
|
|||||||
dumpContext.ptmeBusyCounter = 0;
|
dumpContext.ptmeBusyCounter = 0;
|
||||||
tmSinkBusyCd.resetTimer();
|
tmSinkBusyCd.resetTimer();
|
||||||
ReturnValue_t result = store.getNextDumpPacket(tmReader, fileHasSwapped);
|
ReturnValue_t result = store.getNextDumpPacket(tmReader, fileHasSwapped);
|
||||||
if (result != returnvalue::OK) {
|
if (fileHasSwapped and result == PersistentTmStore::DUMP_DONE) {
|
||||||
sif::error << "PersistentTmStore: Getting next dump packet failed" << std::endl;
|
|
||||||
} else if (fileHasSwapped or result == PersistentTmStore::DUMP_DONE) {
|
|
||||||
// This can happen if a file is corrupted and the next file swap completes the dump.
|
// This can happen if a file is corrupted and the next file swap completes the dump.
|
||||||
dumpDoneHandler();
|
dumpDoneHandler();
|
||||||
return returnvalue::OK;
|
return returnvalue::OK;
|
||||||
|
} else if (result != returnvalue::OK) {
|
||||||
|
sif::error << "PersistentTmStore: Getting next dump packet failed" << std::endl;
|
||||||
|
return result;
|
||||||
}
|
}
|
||||||
dumpedLen = tmReader.getFullPacketLen();
|
dumpedLen = tmReader.getFullPacketLen();
|
||||||
// Only write to VC if mode is on, but always confirm the dump.
|
|
||||||
// If the mode is OFF, it is assumed the PTME is not usable and is not allowed to be written
|
|
||||||
// (e.g. to confirm a reset or the transmitter is off anyway).
|
|
||||||
if (mode == MODE_ON) {
|
|
||||||
result = channel.write(tmReader.getFullData(), dumpedLen);
|
result = channel.write(tmReader.getFullData(), dumpedLen);
|
||||||
if (result == DirectTmSinkIF::IS_BUSY) {
|
if (result == DirectTmSinkIF::IS_BUSY) {
|
||||||
sif::warning << "PersistentTmStore: Unexpected VC channel busy" << std::endl;
|
sif::warning << "PersistentTmStore: Unexpected VC channel busy" << std::endl;
|
||||||
} else if (result != returnvalue::OK) {
|
} else if (result != returnvalue::OK) {
|
||||||
sif::warning << "PersistentTmStore: Unexpected VC channel write failure" << std::endl;
|
sif::warning << "PersistentTmStore: Unexpected VC channel write failure" << std::endl;
|
||||||
}
|
}
|
||||||
}
|
|
||||||
result = store.confirmDump(tmReader, fileHasSwapped);
|
result = store.confirmDump(tmReader, fileHasSwapped);
|
||||||
if ((result == PersistentTmStore::DUMP_DONE or result == returnvalue::OK)) {
|
if ((result == PersistentTmStore::DUMP_DONE or result == returnvalue::OK)) {
|
||||||
dumpPerformed = true;
|
dumpPerformed = true;
|
||||||
|
@ -11,23 +11,14 @@ ReturnValue_t VirtualChannel::sendNextTm(const uint8_t* data, size_t size) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
ReturnValue_t VirtualChannel::write(const uint8_t* data, size_t size) {
|
ReturnValue_t VirtualChannel::write(const uint8_t* data, size_t size) {
|
||||||
if (txOn) {
|
|
||||||
return ptme.writeToVc(vcId, data, size);
|
return ptme.writeToVc(vcId, data, size);
|
||||||
}
|
}
|
||||||
return returnvalue::OK;
|
|
||||||
}
|
|
||||||
|
|
||||||
uint8_t VirtualChannel::getVcid() const { return vcId; }
|
uint8_t VirtualChannel::getVcid() const { return vcId; }
|
||||||
|
|
||||||
const char* VirtualChannel::getName() const { return vcName.c_str(); }
|
const char* VirtualChannel::getName() const { return vcName.c_str(); }
|
||||||
|
|
||||||
bool VirtualChannel::isBusy() const {
|
bool VirtualChannel::isBusy() const { return ptme.isBusy(vcId); }
|
||||||
// Data is discarded, so channel is not busy.
|
|
||||||
if (not txOn) {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
return ptme.isBusy(vcId);
|
|
||||||
}
|
|
||||||
|
|
||||||
void VirtualChannel::cancelTransfer() { ptme.cancelTransfer(vcId); }
|
void VirtualChannel::cancelTransfer() { ptme.cancelTransfer(vcId); }
|
||||||
|
|
||||||
|
@ -169,7 +169,7 @@ void AcsController::performSafe() {
|
|||||||
guidance.getTargetParamsSafe(sunTargetDir);
|
guidance.getTargetParamsSafe(sunTargetDir);
|
||||||
|
|
||||||
double magMomMtq[3] = {0, 0, 0}, errAng = 0.0;
|
double magMomMtq[3] = {0, 0, 0}, errAng = 0.0;
|
||||||
uint8_t safeCtrlStrat = safeCtrl.safeCtrlStrategy(
|
acs::SafeModeStrategy safeCtrlStrat = safeCtrl.safeCtrlStrategy(
|
||||||
mgmDataProcessed.mgmVecTot.isValid(), not mekfInvalidFlag,
|
mgmDataProcessed.mgmVecTot.isValid(), not mekfInvalidFlag,
|
||||||
gyrDataProcessed.gyrVecTot.isValid(), susDataProcessed.susVecTot.isValid(),
|
gyrDataProcessed.gyrVecTot.isValid(), susDataProcessed.susVecTot.isValid(),
|
||||||
acsParameters.safeModeControllerParameters.useMekf,
|
acsParameters.safeModeControllerParameters.useMekf,
|
||||||
@ -205,11 +205,13 @@ void AcsController::performSafe() {
|
|||||||
case (acs::SafeModeStrategy::SAFECTRL_NO_SENSORS_FOR_CONTROL):
|
case (acs::SafeModeStrategy::SAFECTRL_NO_SENSORS_FOR_CONTROL):
|
||||||
safeCtrlFailure(0, 1);
|
safeCtrlFailure(0, 1);
|
||||||
break;
|
break;
|
||||||
|
default:
|
||||||
|
sif::error << "AcsController: Invalid safe mode strategy for performSafe" << std::endl;
|
||||||
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
actuatorCmd.cmdDipolMtq(magMomMtq, cmdDipolMtqs,
|
actuatorCmd.cmdDipoleMtq(*acsParameters.magnetorquerParameter.inverseAlignment,
|
||||||
*acsParameters.magnetorquerParameter.inverseAlignment,
|
acsParameters.magnetorquerParameter.dipoleMax, magMomMtq, cmdDipoleMtqs);
|
||||||
acsParameters.magnetorquerParameter.dipolMax);
|
|
||||||
|
|
||||||
// detumble check and switch
|
// detumble check and switch
|
||||||
if (mekfData.satRotRateMekf.isValid() && acsParameters.safeModeControllerParameters.useMekf &&
|
if (mekfData.satRotRateMekf.isValid() && acsParameters.safeModeControllerParameters.useMekf &&
|
||||||
@ -231,8 +233,8 @@ void AcsController::performSafe() {
|
|||||||
}
|
}
|
||||||
|
|
||||||
updateCtrlValData(errAng, safeCtrlStrat);
|
updateCtrlValData(errAng, safeCtrlStrat);
|
||||||
updateActuatorCmdData(cmdDipolMtqs);
|
updateActuatorCmdData(cmdDipoleMtqs);
|
||||||
commandActuators(cmdDipolMtqs[0], cmdDipolMtqs[1], cmdDipolMtqs[2],
|
commandActuators(cmdDipoleMtqs[0], cmdDipoleMtqs[1], cmdDipoleMtqs[2],
|
||||||
acsParameters.magnetorquerParameter.torqueDuration);
|
acsParameters.magnetorquerParameter.torqueDuration);
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -259,7 +261,7 @@ void AcsController::performDetumble() {
|
|||||||
triggerEvent(acs::MEKF_RECOVERY);
|
triggerEvent(acs::MEKF_RECOVERY);
|
||||||
mekfInvalidFlag = false;
|
mekfInvalidFlag = false;
|
||||||
}
|
}
|
||||||
uint8_t safeCtrlStrat = detumble.detumbleStrategy(
|
acs::SafeModeStrategy safeCtrlStrat = detumble.detumbleStrategy(
|
||||||
mgmDataProcessed.mgmVecTot.isValid(), gyrDataProcessed.gyrVecTot.isValid(),
|
mgmDataProcessed.mgmVecTot.isValid(), gyrDataProcessed.gyrVecTot.isValid(),
|
||||||
mgmDataProcessed.mgmVecTotDerivative.isValid(),
|
mgmDataProcessed.mgmVecTotDerivative.isValid(),
|
||||||
acsParameters.detumbleParameter.useFullDetumbleLaw);
|
acsParameters.detumbleParameter.useFullDetumbleLaw);
|
||||||
@ -279,11 +281,13 @@ void AcsController::performDetumble() {
|
|||||||
case (acs::SafeModeStrategy::SAFECTRL_NO_SENSORS_FOR_CONTROL):
|
case (acs::SafeModeStrategy::SAFECTRL_NO_SENSORS_FOR_CONTROL):
|
||||||
safeCtrlFailure(0, 1);
|
safeCtrlFailure(0, 1);
|
||||||
break;
|
break;
|
||||||
|
default:
|
||||||
|
sif::error << "AcsController: Invalid safe mode strategy for performDetumble" << std::endl;
|
||||||
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
actuatorCmd.cmdDipolMtq(magMomMtq, cmdDipolMtqs,
|
actuatorCmd.cmdDipoleMtq(*acsParameters.magnetorquerParameter.inverseAlignment,
|
||||||
*acsParameters.magnetorquerParameter.inverseAlignment,
|
acsParameters.magnetorquerParameter.dipoleMax, magMomMtq, cmdDipoleMtqs);
|
||||||
acsParameters.magnetorquerParameter.dipolMax);
|
|
||||||
|
|
||||||
if (mekfData.satRotRateMekf.isValid() &&
|
if (mekfData.satRotRateMekf.isValid() &&
|
||||||
VectorOperations<double>::norm(mekfData.satRotRateMekf.value, 3) <
|
VectorOperations<double>::norm(mekfData.satRotRateMekf.value, 3) <
|
||||||
@ -304,8 +308,8 @@ void AcsController::performDetumble() {
|
|||||||
}
|
}
|
||||||
|
|
||||||
disableCtrlValData();
|
disableCtrlValData();
|
||||||
updateActuatorCmdData(cmdDipolMtqs);
|
updateActuatorCmdData(cmdDipoleMtqs);
|
||||||
commandActuators(cmdDipolMtqs[0], cmdDipolMtqs[1], cmdDipolMtqs[2],
|
commandActuators(cmdDipoleMtqs[0], cmdDipoleMtqs[1], cmdDipoleMtqs[2],
|
||||||
acsParameters.magnetorquerParameter.torqueDuration);
|
acsParameters.magnetorquerParameter.torqueDuration);
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -349,8 +353,10 @@ void AcsController::performPointingCtrl() {
|
|||||||
double rwPseudoInv[4][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}, {0, 0, 0}};
|
double rwPseudoInv[4][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}, {0, 0, 0}};
|
||||||
result = guidance.getDistributionMatrixRw(&sensorValues, *rwPseudoInv);
|
result = guidance.getDistributionMatrixRw(&sensorValues, *rwPseudoInv);
|
||||||
if (result == returnvalue::FAILED) {
|
if (result == returnvalue::FAILED) {
|
||||||
if (multipleRwUnavailableCounter == 5) {
|
if (multipleRwUnavailableCounter >=
|
||||||
|
acsParameters.rwHandlingParameters.multipleRwInvalidTimeout) {
|
||||||
triggerEvent(acs::MULTIPLE_RW_INVALID);
|
triggerEvent(acs::MULTIPLE_RW_INVALID);
|
||||||
|
multipleRwUnavailableCounter = 0;
|
||||||
}
|
}
|
||||||
multipleRwUnavailableCounter++;
|
multipleRwUnavailableCounter++;
|
||||||
return;
|
return;
|
||||||
@ -364,24 +370,26 @@ void AcsController::performPointingCtrl() {
|
|||||||
// Variables required for setting actuators
|
// Variables required for setting actuators
|
||||||
double torquePtgRws[4] = {0, 0, 0, 0}, rwTrqNs[4] = {0, 0, 0, 0}, torqueRws[4] = {0, 0, 0, 0},
|
double torquePtgRws[4] = {0, 0, 0, 0}, rwTrqNs[4] = {0, 0, 0, 0}, torqueRws[4] = {0, 0, 0, 0},
|
||||||
mgtDpDes[3] = {0, 0, 0};
|
mgtDpDes[3] = {0, 0, 0};
|
||||||
|
|
||||||
switch (mode) {
|
switch (mode) {
|
||||||
case acs::PTG_IDLE:
|
case acs::PTG_IDLE:
|
||||||
guidance.targetQuatPtgSun(susDataProcessed.sunIjkModel.value, targetQuat, targetSatRotRate);
|
guidance.targetQuatPtgSun(now, susDataProcessed.sunIjkModel.value, targetQuat,
|
||||||
|
targetSatRotRate);
|
||||||
guidance.comparePtg(mekfData.quatMekf.value, mekfData.satRotRateMekf.value, targetQuat,
|
guidance.comparePtg(mekfData.quatMekf.value, mekfData.satRotRateMekf.value, targetQuat,
|
||||||
targetSatRotRate, errorQuat, errorSatRotRate, errorAngle);
|
targetSatRotRate, errorQuat, errorSatRotRate, errorAngle);
|
||||||
ptgCtrl.ptgLaw(&acsParameters.idleModeControllerParameters, errorQuat, errorSatRotRate,
|
ptgCtrl.ptgLaw(&acsParameters.idleModeControllerParameters, errorQuat, errorSatRotRate,
|
||||||
*rwPseudoInv, torquePtgRws);
|
*rwPseudoInv, torquePtgRws);
|
||||||
ptgCtrl.ptgNullspace(
|
ptgCtrl.ptgNullspace(&acsParameters.idleModeControllerParameters,
|
||||||
&acsParameters.idleModeControllerParameters, &(sensorValues.rw1Set.currSpeed.value),
|
sensorValues.rw1Set.currSpeed.value, sensorValues.rw2Set.currSpeed.value,
|
||||||
&(sensorValues.rw2Set.currSpeed.value), &(sensorValues.rw3Set.currSpeed.value),
|
sensorValues.rw3Set.currSpeed.value, sensorValues.rw4Set.currSpeed.value,
|
||||||
&(sensorValues.rw4Set.currSpeed.value), rwTrqNs);
|
rwTrqNs);
|
||||||
VectorOperations<double>::add(torquePtgRws, rwTrqNs, torqueRws, 4);
|
VectorOperations<double>::add(torquePtgRws, rwTrqNs, torqueRws, 4);
|
||||||
actuatorCmd.scalingTorqueRws(torqueRws, acsParameters.rwHandlingParameters.maxTrq);
|
actuatorCmd.scalingTorqueRws(torqueRws, acsParameters.rwHandlingParameters.maxTrq);
|
||||||
ptgCtrl.ptgDesaturation(
|
ptgCtrl.ptgDesaturation(
|
||||||
&acsParameters.idleModeControllerParameters, mgmDataProcessed.mgmVecTot.value,
|
&acsParameters.idleModeControllerParameters, mgmDataProcessed.mgmVecTot.value,
|
||||||
mgmDataProcessed.mgmVecTot.isValid(), mekfData.satRotRateMekf.value,
|
mgmDataProcessed.mgmVecTot.isValid(), mekfData.satRotRateMekf.value,
|
||||||
&(sensorValues.rw1Set.currSpeed.value), &(sensorValues.rw2Set.currSpeed.value),
|
sensorValues.rw1Set.currSpeed.value, sensorValues.rw2Set.currSpeed.value,
|
||||||
&(sensorValues.rw3Set.currSpeed.value), &(sensorValues.rw4Set.currSpeed.value), mgtDpDes);
|
sensorValues.rw3Set.currSpeed.value, sensorValues.rw4Set.currSpeed.value, mgtDpDes);
|
||||||
enableAntiStiction = acsParameters.idleModeControllerParameters.enableAntiStiction;
|
enableAntiStiction = acsParameters.idleModeControllerParameters.enableAntiStiction;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
@ -395,17 +403,17 @@ void AcsController::performPointingCtrl() {
|
|||||||
errorSatRotRate, errorAngle);
|
errorSatRotRate, errorAngle);
|
||||||
ptgCtrl.ptgLaw(&acsParameters.targetModeControllerParameters, errorQuat, errorSatRotRate,
|
ptgCtrl.ptgLaw(&acsParameters.targetModeControllerParameters, errorQuat, errorSatRotRate,
|
||||||
*rwPseudoInv, torquePtgRws);
|
*rwPseudoInv, torquePtgRws);
|
||||||
ptgCtrl.ptgNullspace(
|
ptgCtrl.ptgNullspace(&acsParameters.targetModeControllerParameters,
|
||||||
&acsParameters.targetModeControllerParameters, &(sensorValues.rw1Set.currSpeed.value),
|
sensorValues.rw1Set.currSpeed.value, sensorValues.rw2Set.currSpeed.value,
|
||||||
&(sensorValues.rw2Set.currSpeed.value), &(sensorValues.rw3Set.currSpeed.value),
|
sensorValues.rw3Set.currSpeed.value, sensorValues.rw4Set.currSpeed.value,
|
||||||
&(sensorValues.rw4Set.currSpeed.value), rwTrqNs);
|
rwTrqNs);
|
||||||
VectorOperations<double>::add(torquePtgRws, rwTrqNs, torqueRws, 4);
|
VectorOperations<double>::add(torquePtgRws, rwTrqNs, torqueRws, 4);
|
||||||
actuatorCmd.scalingTorqueRws(torqueRws, acsParameters.rwHandlingParameters.maxTrq);
|
actuatorCmd.scalingTorqueRws(torqueRws, acsParameters.rwHandlingParameters.maxTrq);
|
||||||
ptgCtrl.ptgDesaturation(
|
ptgCtrl.ptgDesaturation(
|
||||||
&acsParameters.targetModeControllerParameters, mgmDataProcessed.mgmVecTot.value,
|
&acsParameters.targetModeControllerParameters, mgmDataProcessed.mgmVecTot.value,
|
||||||
mgmDataProcessed.mgmVecTot.isValid(), mekfData.satRotRateMekf.value,
|
mgmDataProcessed.mgmVecTot.isValid(), mekfData.satRotRateMekf.value,
|
||||||
&(sensorValues.rw1Set.currSpeed.value), &(sensorValues.rw2Set.currSpeed.value),
|
sensorValues.rw1Set.currSpeed.value, sensorValues.rw2Set.currSpeed.value,
|
||||||
&(sensorValues.rw3Set.currSpeed.value), &(sensorValues.rw4Set.currSpeed.value), mgtDpDes);
|
sensorValues.rw3Set.currSpeed.value, sensorValues.rw4Set.currSpeed.value, mgtDpDes);
|
||||||
enableAntiStiction = acsParameters.targetModeControllerParameters.enableAntiStiction;
|
enableAntiStiction = acsParameters.targetModeControllerParameters.enableAntiStiction;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
@ -416,17 +424,17 @@ void AcsController::performPointingCtrl() {
|
|||||||
targetSatRotRate, errorQuat, errorSatRotRate, errorAngle);
|
targetSatRotRate, errorQuat, errorSatRotRate, errorAngle);
|
||||||
ptgCtrl.ptgLaw(&acsParameters.gsTargetModeControllerParameters, errorQuat, errorSatRotRate,
|
ptgCtrl.ptgLaw(&acsParameters.gsTargetModeControllerParameters, errorQuat, errorSatRotRate,
|
||||||
*rwPseudoInv, torquePtgRws);
|
*rwPseudoInv, torquePtgRws);
|
||||||
ptgCtrl.ptgNullspace(
|
ptgCtrl.ptgNullspace(&acsParameters.gsTargetModeControllerParameters,
|
||||||
&acsParameters.gsTargetModeControllerParameters, &(sensorValues.rw1Set.currSpeed.value),
|
sensorValues.rw1Set.currSpeed.value, sensorValues.rw2Set.currSpeed.value,
|
||||||
&(sensorValues.rw2Set.currSpeed.value), &(sensorValues.rw3Set.currSpeed.value),
|
sensorValues.rw3Set.currSpeed.value, sensorValues.rw4Set.currSpeed.value,
|
||||||
&(sensorValues.rw4Set.currSpeed.value), rwTrqNs);
|
rwTrqNs);
|
||||||
VectorOperations<double>::add(torquePtgRws, rwTrqNs, torqueRws, 4);
|
VectorOperations<double>::add(torquePtgRws, rwTrqNs, torqueRws, 4);
|
||||||
actuatorCmd.scalingTorqueRws(torqueRws, acsParameters.rwHandlingParameters.maxTrq);
|
actuatorCmd.scalingTorqueRws(torqueRws, acsParameters.rwHandlingParameters.maxTrq);
|
||||||
ptgCtrl.ptgDesaturation(
|
ptgCtrl.ptgDesaturation(
|
||||||
&acsParameters.gsTargetModeControllerParameters, mgmDataProcessed.mgmVecTot.value,
|
&acsParameters.gsTargetModeControllerParameters, mgmDataProcessed.mgmVecTot.value,
|
||||||
mgmDataProcessed.mgmVecTot.isValid(), mekfData.satRotRateMekf.value,
|
mgmDataProcessed.mgmVecTot.isValid(), mekfData.satRotRateMekf.value,
|
||||||
&(sensorValues.rw1Set.currSpeed.value), &(sensorValues.rw2Set.currSpeed.value),
|
sensorValues.rw1Set.currSpeed.value, sensorValues.rw2Set.currSpeed.value,
|
||||||
&(sensorValues.rw3Set.currSpeed.value), &(sensorValues.rw4Set.currSpeed.value), mgtDpDes);
|
sensorValues.rw3Set.currSpeed.value, sensorValues.rw4Set.currSpeed.value, mgtDpDes);
|
||||||
enableAntiStiction = acsParameters.gsTargetModeControllerParameters.enableAntiStiction;
|
enableAntiStiction = acsParameters.gsTargetModeControllerParameters.enableAntiStiction;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
@ -440,63 +448,61 @@ void AcsController::performPointingCtrl() {
|
|||||||
errorSatRotRate, errorAngle);
|
errorSatRotRate, errorAngle);
|
||||||
ptgCtrl.ptgLaw(&acsParameters.nadirModeControllerParameters, errorQuat, errorSatRotRate,
|
ptgCtrl.ptgLaw(&acsParameters.nadirModeControllerParameters, errorQuat, errorSatRotRate,
|
||||||
*rwPseudoInv, torquePtgRws);
|
*rwPseudoInv, torquePtgRws);
|
||||||
ptgCtrl.ptgNullspace(
|
ptgCtrl.ptgNullspace(&acsParameters.nadirModeControllerParameters,
|
||||||
&acsParameters.nadirModeControllerParameters, &(sensorValues.rw1Set.currSpeed.value),
|
sensorValues.rw1Set.currSpeed.value, sensorValues.rw2Set.currSpeed.value,
|
||||||
&(sensorValues.rw2Set.currSpeed.value), &(sensorValues.rw3Set.currSpeed.value),
|
sensorValues.rw3Set.currSpeed.value, sensorValues.rw4Set.currSpeed.value,
|
||||||
&(sensorValues.rw4Set.currSpeed.value), rwTrqNs);
|
rwTrqNs);
|
||||||
VectorOperations<double>::add(torquePtgRws, rwTrqNs, torqueRws, 4);
|
VectorOperations<double>::add(torquePtgRws, rwTrqNs, torqueRws, 4);
|
||||||
actuatorCmd.scalingTorqueRws(torqueRws, acsParameters.rwHandlingParameters.maxTrq);
|
actuatorCmd.scalingTorqueRws(torqueRws, acsParameters.rwHandlingParameters.maxTrq);
|
||||||
ptgCtrl.ptgDesaturation(
|
ptgCtrl.ptgDesaturation(
|
||||||
&acsParameters.nadirModeControllerParameters, mgmDataProcessed.mgmVecTot.value,
|
&acsParameters.nadirModeControllerParameters, mgmDataProcessed.mgmVecTot.value,
|
||||||
mgmDataProcessed.mgmVecTot.isValid(), mekfData.satRotRateMekf.value,
|
mgmDataProcessed.mgmVecTot.isValid(), mekfData.satRotRateMekf.value,
|
||||||
&(sensorValues.rw1Set.currSpeed.value), &(sensorValues.rw2Set.currSpeed.value),
|
sensorValues.rw1Set.currSpeed.value, sensorValues.rw2Set.currSpeed.value,
|
||||||
&(sensorValues.rw3Set.currSpeed.value), &(sensorValues.rw4Set.currSpeed.value), mgtDpDes);
|
sensorValues.rw3Set.currSpeed.value, sensorValues.rw4Set.currSpeed.value, mgtDpDes);
|
||||||
enableAntiStiction = acsParameters.nadirModeControllerParameters.enableAntiStiction;
|
enableAntiStiction = acsParameters.nadirModeControllerParameters.enableAntiStiction;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case acs::PTG_INERTIAL:
|
case acs::PTG_INERTIAL:
|
||||||
std::memcpy(targetQuat, acsParameters.inertialModeControllerParameters.tgtQuat,
|
std::memcpy(targetQuat, acsParameters.inertialModeControllerParameters.tgtQuat,
|
||||||
4 * sizeof(double));
|
sizeof(targetQuat));
|
||||||
guidance.comparePtg(mekfData.quatMekf.value, mekfData.satRotRateMekf.value, targetQuat,
|
guidance.comparePtg(mekfData.quatMekf.value, mekfData.satRotRateMekf.value, targetQuat,
|
||||||
targetSatRotRate, acsParameters.inertialModeControllerParameters.quatRef,
|
targetSatRotRate, acsParameters.inertialModeControllerParameters.quatRef,
|
||||||
acsParameters.inertialModeControllerParameters.refRotRate, errorQuat,
|
acsParameters.inertialModeControllerParameters.refRotRate, errorQuat,
|
||||||
errorSatRotRate, errorAngle);
|
errorSatRotRate, errorAngle);
|
||||||
ptgCtrl.ptgLaw(&acsParameters.inertialModeControllerParameters, errorQuat, errorSatRotRate,
|
ptgCtrl.ptgLaw(&acsParameters.inertialModeControllerParameters, errorQuat, errorSatRotRate,
|
||||||
*rwPseudoInv, torquePtgRws);
|
*rwPseudoInv, torquePtgRws);
|
||||||
ptgCtrl.ptgNullspace(
|
ptgCtrl.ptgNullspace(&acsParameters.inertialModeControllerParameters,
|
||||||
&acsParameters.inertialModeControllerParameters, &(sensorValues.rw1Set.currSpeed.value),
|
sensorValues.rw1Set.currSpeed.value, sensorValues.rw2Set.currSpeed.value,
|
||||||
&(sensorValues.rw2Set.currSpeed.value), &(sensorValues.rw3Set.currSpeed.value),
|
sensorValues.rw3Set.currSpeed.value, sensorValues.rw4Set.currSpeed.value,
|
||||||
&(sensorValues.rw4Set.currSpeed.value), rwTrqNs);
|
rwTrqNs);
|
||||||
VectorOperations<double>::add(torquePtgRws, rwTrqNs, torqueRws, 4);
|
VectorOperations<double>::add(torquePtgRws, rwTrqNs, torqueRws, 4);
|
||||||
actuatorCmd.scalingTorqueRws(torqueRws, acsParameters.rwHandlingParameters.maxTrq);
|
actuatorCmd.scalingTorqueRws(torqueRws, acsParameters.rwHandlingParameters.maxTrq);
|
||||||
ptgCtrl.ptgDesaturation(
|
ptgCtrl.ptgDesaturation(
|
||||||
&acsParameters.inertialModeControllerParameters, mgmDataProcessed.mgmVecTot.value,
|
&acsParameters.inertialModeControllerParameters, mgmDataProcessed.mgmVecTot.value,
|
||||||
mgmDataProcessed.mgmVecTot.isValid(), mekfData.satRotRateMekf.value,
|
mgmDataProcessed.mgmVecTot.isValid(), mekfData.satRotRateMekf.value,
|
||||||
&(sensorValues.rw1Set.currSpeed.value), &(sensorValues.rw2Set.currSpeed.value),
|
sensorValues.rw1Set.currSpeed.value, sensorValues.rw2Set.currSpeed.value,
|
||||||
&(sensorValues.rw3Set.currSpeed.value), &(sensorValues.rw4Set.currSpeed.value), mgtDpDes);
|
sensorValues.rw3Set.currSpeed.value, sensorValues.rw4Set.currSpeed.value, mgtDpDes);
|
||||||
enableAntiStiction = acsParameters.inertialModeControllerParameters.enableAntiStiction;
|
enableAntiStiction = acsParameters.inertialModeControllerParameters.enableAntiStiction;
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
sif::error << "AcsController: Invalid mode for performPointingCtrl";
|
sif::error << "AcsController: Invalid mode for performPointingCtrl" << std::endl;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
actuatorCmd.cmdSpeedToRws(
|
actuatorCmd.cmdSpeedToRws(
|
||||||
sensorValues.rw1Set.currSpeed.value, sensorValues.rw2Set.currSpeed.value,
|
sensorValues.rw1Set.currSpeed.value, sensorValues.rw2Set.currSpeed.value,
|
||||||
sensorValues.rw3Set.currSpeed.value, sensorValues.rw4Set.currSpeed.value, torqueRws,
|
sensorValues.rw3Set.currSpeed.value, sensorValues.rw4Set.currSpeed.value,
|
||||||
cmdSpeedRws, acsParameters.onBoardParams.sampleTime,
|
acsParameters.onBoardParams.sampleTime, acsParameters.rwHandlingParameters.inertiaWheel,
|
||||||
acsParameters.rwHandlingParameters.maxRwSpeed,
|
acsParameters.rwHandlingParameters.maxRwSpeed, torqueRws, cmdSpeedRws);
|
||||||
acsParameters.rwHandlingParameters.inertiaWheel);
|
|
||||||
if (enableAntiStiction) {
|
if (enableAntiStiction) {
|
||||||
ptgCtrl.rwAntistiction(&sensorValues, cmdSpeedRws);
|
ptgCtrl.rwAntistiction(&sensorValues, cmdSpeedRws);
|
||||||
}
|
}
|
||||||
actuatorCmd.cmdDipolMtq(mgtDpDes, cmdDipolMtqs,
|
actuatorCmd.cmdDipoleMtq(*acsParameters.magnetorquerParameter.inverseAlignment,
|
||||||
*acsParameters.magnetorquerParameter.inverseAlignment,
|
acsParameters.magnetorquerParameter.dipoleMax, mgtDpDes, cmdDipoleMtqs);
|
||||||
acsParameters.magnetorquerParameter.dipolMax);
|
|
||||||
|
|
||||||
updateCtrlValData(targetQuat, errorQuat, errorAngle, targetSatRotRate);
|
updateCtrlValData(targetQuat, errorQuat, errorAngle, targetSatRotRate);
|
||||||
updateActuatorCmdData(torqueRws, cmdSpeedRws, cmdDipolMtqs);
|
updateActuatorCmdData(torqueRws, cmdSpeedRws, cmdDipoleMtqs);
|
||||||
commandActuators(cmdDipolMtqs[0], cmdDipolMtqs[1], cmdDipolMtqs[2],
|
commandActuators(cmdDipoleMtqs[0], cmdDipoleMtqs[1], cmdDipoleMtqs[2],
|
||||||
acsParameters.magnetorquerParameter.torqueDuration, cmdSpeedRws[0],
|
acsParameters.magnetorquerParameter.torqueDuration, cmdSpeedRws[0],
|
||||||
cmdSpeedRws[1], cmdSpeedRws[2], cmdSpeedRws[3],
|
cmdSpeedRws[1], cmdSpeedRws[2], cmdSpeedRws[3],
|
||||||
acsParameters.rwHandlingParameters.rampTime);
|
acsParameters.rwHandlingParameters.rampTime);
|
||||||
|
@ -69,7 +69,7 @@ class AcsController : public ExtendedControllerBase, public ReceivesParameterMes
|
|||||||
bool mekfLost = false;
|
bool mekfLost = false;
|
||||||
|
|
||||||
int32_t cmdSpeedRws[4] = {0, 0, 0, 0};
|
int32_t cmdSpeedRws[4] = {0, 0, 0, 0};
|
||||||
int16_t cmdDipolMtqs[3] = {0, 0, 0};
|
int16_t cmdDipoleMtqs[3] = {0, 0, 0};
|
||||||
|
|
||||||
#if OBSW_THREAD_TRACING == 1
|
#if OBSW_THREAD_TRACING == 1
|
||||||
uint32_t opCounter = 0;
|
uint32_t opCounter = 0;
|
||||||
|
@ -175,7 +175,7 @@ void ThermalController::performControlOperation() {
|
|||||||
heaterHandler.getAllSwitchStates(heaterSwitchStateArray);
|
heaterHandler.getAllSwitchStates(heaterSwitchStateArray);
|
||||||
{
|
{
|
||||||
PoolReadGuard pg(&heaterInfo);
|
PoolReadGuard pg(&heaterInfo);
|
||||||
std::memcpy(heaterInfo.heaterSwitchState.value, heaterStates.data(), 8);
|
std::memcpy(heaterInfo.heaterSwitchState.value, heaterSwitchStateArray.data(), 8);
|
||||||
{
|
{
|
||||||
PoolReadGuard pg2(¤tVecPdu2);
|
PoolReadGuard pg2(¤tVecPdu2);
|
||||||
if (pg.getReadResult() == returnvalue::OK and pg2.getReadResult() == returnvalue::OK) {
|
if (pg.getReadResult() == returnvalue::OK and pg2.getReadResult() == returnvalue::OK) {
|
||||||
@ -1631,14 +1631,19 @@ bool ThermalController::selectAndReadSensorTemp(HeaterContext& htrCtx) {
|
|||||||
bool ThermalController::chooseHeater(heater::Switch& switchNr, heater::Switch redSwitchNr) {
|
bool ThermalController::chooseHeater(heater::Switch& switchNr, heater::Switch redSwitchNr) {
|
||||||
bool heaterAvailable = true;
|
bool heaterAvailable = true;
|
||||||
|
|
||||||
if (heaterHandler.getHealth(switchNr) != HasHealthIF::HEALTHY) {
|
HasHealthIF::HealthState mainHealth = heaterHandler.getHealth(switchNr);
|
||||||
if (heaterHandler.getHealth(redSwitchNr) == HasHealthIF::HEALTHY) {
|
HasHealthIF::HealthState redHealth = heaterHandler.getHealth(redSwitchNr);
|
||||||
|
if (mainHealth != HasHealthIF::HEALTHY) {
|
||||||
|
if (redHealth == HasHealthIF::HEALTHY) {
|
||||||
switchNr = redSwitchNr;
|
switchNr = redSwitchNr;
|
||||||
redSwitchNrInUse = true;
|
redSwitchNrInUse = true;
|
||||||
} else {
|
} else {
|
||||||
heaterAvailable = false;
|
heaterAvailable = false;
|
||||||
|
// Special case: Ground might command/do something with the heaters, so prevent spam.
|
||||||
|
if (not(mainHealth == EXTERNAL_CONTROL and redHealth == EXTERNAL_CONTROL)) {
|
||||||
triggerEvent(tcsCtrl::NO_HEALTHY_HEATER_AVAILABLE, switchNr, redSwitchNr);
|
triggerEvent(tcsCtrl::NO_HEALTHY_HEATER_AVAILABLE, switchNr, redSwitchNr);
|
||||||
}
|
}
|
||||||
|
}
|
||||||
} else {
|
} else {
|
||||||
redSwitchNrInUse = false;
|
redSwitchNrInUse = false;
|
||||||
}
|
}
|
||||||
|
@ -290,6 +290,9 @@ ReturnValue_t AcsParameters::getParameter(uint8_t domainId, uint8_t parameterId,
|
|||||||
case 0x6:
|
case 0x6:
|
||||||
parameterWrapper->set(rwHandlingParameters.rampTime);
|
parameterWrapper->set(rwHandlingParameters.rampTime);
|
||||||
break;
|
break;
|
||||||
|
case 0x7:
|
||||||
|
parameterWrapper->set(rwHandlingParameters.multipleRwInvalidTimeout);
|
||||||
|
break;
|
||||||
default:
|
default:
|
||||||
return INVALID_IDENTIFIER_ID;
|
return INVALID_IDENTIFIER_ID;
|
||||||
}
|
}
|
||||||
@ -315,7 +318,7 @@ ReturnValue_t AcsParameters::getParameter(uint8_t domainId, uint8_t parameterId,
|
|||||||
parameterWrapper->setMatrix(rwMatrices.without4);
|
parameterWrapper->setMatrix(rwMatrices.without4);
|
||||||
break;
|
break;
|
||||||
case 0x6:
|
case 0x6:
|
||||||
parameterWrapper->setVector(rwMatrices.nullspace);
|
parameterWrapper->setVector(rwMatrices.nullspaceVector);
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
return INVALID_IDENTIFIER_ID;
|
return INVALID_IDENTIFIER_ID;
|
||||||
@ -375,15 +378,18 @@ ReturnValue_t AcsParameters::getParameter(uint8_t domainId, uint8_t parameterId,
|
|||||||
parameterWrapper->set(idleModeControllerParameters.gainNullspace);
|
parameterWrapper->set(idleModeControllerParameters.gainNullspace);
|
||||||
break;
|
break;
|
||||||
case 0x5:
|
case 0x5:
|
||||||
parameterWrapper->setVector(idleModeControllerParameters.desatMomentumRef);
|
parameterWrapper->set(idleModeControllerParameters.nullspaceSpeed);
|
||||||
break;
|
break;
|
||||||
case 0x6:
|
case 0x6:
|
||||||
parameterWrapper->set(idleModeControllerParameters.deSatGainFactor);
|
parameterWrapper->setVector(idleModeControllerParameters.desatMomentumRef);
|
||||||
break;
|
break;
|
||||||
case 0x7:
|
case 0x7:
|
||||||
parameterWrapper->set(idleModeControllerParameters.desatOn);
|
parameterWrapper->set(idleModeControllerParameters.deSatGainFactor);
|
||||||
break;
|
break;
|
||||||
case 0x8:
|
case 0x8:
|
||||||
|
parameterWrapper->set(idleModeControllerParameters.desatOn);
|
||||||
|
break;
|
||||||
|
case 0x9:
|
||||||
parameterWrapper->set(idleModeControllerParameters.enableAntiStiction);
|
parameterWrapper->set(idleModeControllerParameters.enableAntiStiction);
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
@ -408,48 +414,51 @@ ReturnValue_t AcsParameters::getParameter(uint8_t domainId, uint8_t parameterId,
|
|||||||
parameterWrapper->set(targetModeControllerParameters.gainNullspace);
|
parameterWrapper->set(targetModeControllerParameters.gainNullspace);
|
||||||
break;
|
break;
|
||||||
case 0x5:
|
case 0x5:
|
||||||
parameterWrapper->setVector(targetModeControllerParameters.desatMomentumRef);
|
parameterWrapper->set(targetModeControllerParameters.nullspaceSpeed);
|
||||||
break;
|
break;
|
||||||
case 0x6:
|
case 0x6:
|
||||||
parameterWrapper->set(targetModeControllerParameters.deSatGainFactor);
|
parameterWrapper->setVector(targetModeControllerParameters.desatMomentumRef);
|
||||||
break;
|
break;
|
||||||
case 0x7:
|
case 0x7:
|
||||||
parameterWrapper->set(targetModeControllerParameters.desatOn);
|
parameterWrapper->set(targetModeControllerParameters.deSatGainFactor);
|
||||||
break;
|
break;
|
||||||
case 0x8:
|
case 0x8:
|
||||||
parameterWrapper->set(targetModeControllerParameters.enableAntiStiction);
|
parameterWrapper->set(targetModeControllerParameters.desatOn);
|
||||||
break;
|
break;
|
||||||
case 0x9:
|
case 0x9:
|
||||||
parameterWrapper->setVector(targetModeControllerParameters.refDirection);
|
parameterWrapper->set(targetModeControllerParameters.enableAntiStiction);
|
||||||
break;
|
break;
|
||||||
case 0xA:
|
case 0xA:
|
||||||
parameterWrapper->setVector(targetModeControllerParameters.refRotRate);
|
parameterWrapper->setVector(targetModeControllerParameters.refDirection);
|
||||||
break;
|
break;
|
||||||
case 0xB:
|
case 0xB:
|
||||||
parameterWrapper->setVector(targetModeControllerParameters.quatRef);
|
parameterWrapper->setVector(targetModeControllerParameters.refRotRate);
|
||||||
break;
|
break;
|
||||||
case 0xC:
|
case 0xC:
|
||||||
parameterWrapper->set(targetModeControllerParameters.timeElapsedMax);
|
parameterWrapper->setVector(targetModeControllerParameters.quatRef);
|
||||||
break;
|
break;
|
||||||
case 0xD:
|
case 0xD:
|
||||||
parameterWrapper->set(targetModeControllerParameters.latitudeTgt);
|
parameterWrapper->set(targetModeControllerParameters.timeElapsedMax);
|
||||||
break;
|
break;
|
||||||
case 0xE:
|
case 0xE:
|
||||||
parameterWrapper->set(targetModeControllerParameters.longitudeTgt);
|
parameterWrapper->set(targetModeControllerParameters.latitudeTgt);
|
||||||
break;
|
break;
|
||||||
case 0xF:
|
case 0xF:
|
||||||
parameterWrapper->set(targetModeControllerParameters.altitudeTgt);
|
parameterWrapper->set(targetModeControllerParameters.longitudeTgt);
|
||||||
break;
|
break;
|
||||||
case 0x10:
|
case 0x10:
|
||||||
parameterWrapper->set(targetModeControllerParameters.avoidBlindStr);
|
parameterWrapper->set(targetModeControllerParameters.altitudeTgt);
|
||||||
break;
|
break;
|
||||||
case 0x11:
|
case 0x11:
|
||||||
parameterWrapper->set(targetModeControllerParameters.blindAvoidStart);
|
parameterWrapper->set(targetModeControllerParameters.avoidBlindStr);
|
||||||
break;
|
break;
|
||||||
case 0x12:
|
case 0x12:
|
||||||
parameterWrapper->set(targetModeControllerParameters.blindAvoidStop);
|
parameterWrapper->set(targetModeControllerParameters.blindAvoidStart);
|
||||||
break;
|
break;
|
||||||
case 0x13:
|
case 0x13:
|
||||||
|
parameterWrapper->set(targetModeControllerParameters.blindAvoidStop);
|
||||||
|
break;
|
||||||
|
case 0x14:
|
||||||
parameterWrapper->set(targetModeControllerParameters.blindRotRate);
|
parameterWrapper->set(targetModeControllerParameters.blindRotRate);
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
@ -474,30 +483,33 @@ ReturnValue_t AcsParameters::getParameter(uint8_t domainId, uint8_t parameterId,
|
|||||||
parameterWrapper->set(gsTargetModeControllerParameters.gainNullspace);
|
parameterWrapper->set(gsTargetModeControllerParameters.gainNullspace);
|
||||||
break;
|
break;
|
||||||
case 0x5:
|
case 0x5:
|
||||||
parameterWrapper->setVector(gsTargetModeControllerParameters.desatMomentumRef);
|
parameterWrapper->set(gsTargetModeControllerParameters.nullspaceSpeed);
|
||||||
break;
|
break;
|
||||||
case 0x6:
|
case 0x6:
|
||||||
parameterWrapper->set(gsTargetModeControllerParameters.deSatGainFactor);
|
parameterWrapper->setVector(gsTargetModeControllerParameters.desatMomentumRef);
|
||||||
break;
|
break;
|
||||||
case 0x7:
|
case 0x7:
|
||||||
parameterWrapper->set(gsTargetModeControllerParameters.desatOn);
|
parameterWrapper->set(gsTargetModeControllerParameters.deSatGainFactor);
|
||||||
break;
|
break;
|
||||||
case 0x8:
|
case 0x8:
|
||||||
parameterWrapper->set(gsTargetModeControllerParameters.enableAntiStiction);
|
parameterWrapper->set(gsTargetModeControllerParameters.desatOn);
|
||||||
break;
|
break;
|
||||||
case 0x9:
|
case 0x9:
|
||||||
parameterWrapper->setVector(gsTargetModeControllerParameters.refDirection);
|
parameterWrapper->set(gsTargetModeControllerParameters.enableAntiStiction);
|
||||||
break;
|
break;
|
||||||
case 0xA:
|
case 0xA:
|
||||||
parameterWrapper->set(gsTargetModeControllerParameters.timeElapsedMax);
|
parameterWrapper->setVector(gsTargetModeControllerParameters.refDirection);
|
||||||
break;
|
break;
|
||||||
case 0xB:
|
case 0xB:
|
||||||
parameterWrapper->set(gsTargetModeControllerParameters.latitudeTgt);
|
parameterWrapper->set(gsTargetModeControllerParameters.timeElapsedMax);
|
||||||
break;
|
break;
|
||||||
case 0xC:
|
case 0xC:
|
||||||
parameterWrapper->set(gsTargetModeControllerParameters.longitudeTgt);
|
parameterWrapper->set(gsTargetModeControllerParameters.latitudeTgt);
|
||||||
break;
|
break;
|
||||||
case 0xD:
|
case 0xD:
|
||||||
|
parameterWrapper->set(gsTargetModeControllerParameters.longitudeTgt);
|
||||||
|
break;
|
||||||
|
case 0xE:
|
||||||
parameterWrapper->set(gsTargetModeControllerParameters.altitudeTgt);
|
parameterWrapper->set(gsTargetModeControllerParameters.altitudeTgt);
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
@ -522,24 +534,30 @@ ReturnValue_t AcsParameters::getParameter(uint8_t domainId, uint8_t parameterId,
|
|||||||
parameterWrapper->set(nadirModeControllerParameters.gainNullspace);
|
parameterWrapper->set(nadirModeControllerParameters.gainNullspace);
|
||||||
break;
|
break;
|
||||||
case 0x5:
|
case 0x5:
|
||||||
parameterWrapper->setVector(nadirModeControllerParameters.desatMomentumRef);
|
parameterWrapper->set(nadirModeControllerParameters.nullspaceSpeed);
|
||||||
break;
|
break;
|
||||||
case 0x6:
|
case 0x6:
|
||||||
parameterWrapper->set(nadirModeControllerParameters.deSatGainFactor);
|
parameterWrapper->setVector(nadirModeControllerParameters.desatMomentumRef);
|
||||||
break;
|
break;
|
||||||
case 0x7:
|
case 0x7:
|
||||||
parameterWrapper->set(nadirModeControllerParameters.desatOn);
|
parameterWrapper->set(nadirModeControllerParameters.deSatGainFactor);
|
||||||
break;
|
break;
|
||||||
case 0x8:
|
case 0x8:
|
||||||
parameterWrapper->set(nadirModeControllerParameters.enableAntiStiction);
|
parameterWrapper->set(nadirModeControllerParameters.desatOn);
|
||||||
break;
|
break;
|
||||||
case 0x9:
|
case 0x9:
|
||||||
parameterWrapper->setVector(nadirModeControllerParameters.refDirection);
|
parameterWrapper->set(nadirModeControllerParameters.enableAntiStiction);
|
||||||
break;
|
break;
|
||||||
case 0xA:
|
case 0xA:
|
||||||
|
parameterWrapper->setVector(nadirModeControllerParameters.refDirection);
|
||||||
|
break;
|
||||||
|
case 0xB:
|
||||||
parameterWrapper->setVector(nadirModeControllerParameters.quatRef);
|
parameterWrapper->setVector(nadirModeControllerParameters.quatRef);
|
||||||
break;
|
break;
|
||||||
case 0xC:
|
case 0xC:
|
||||||
|
parameterWrapper->setVector(nadirModeControllerParameters.refRotRate);
|
||||||
|
break;
|
||||||
|
case 0xD:
|
||||||
parameterWrapper->set(nadirModeControllerParameters.timeElapsedMax);
|
parameterWrapper->set(nadirModeControllerParameters.timeElapsedMax);
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
@ -564,21 +582,24 @@ ReturnValue_t AcsParameters::getParameter(uint8_t domainId, uint8_t parameterId,
|
|||||||
parameterWrapper->set(inertialModeControllerParameters.gainNullspace);
|
parameterWrapper->set(inertialModeControllerParameters.gainNullspace);
|
||||||
break;
|
break;
|
||||||
case 0x5:
|
case 0x5:
|
||||||
parameterWrapper->setVector(inertialModeControllerParameters.desatMomentumRef);
|
parameterWrapper->set(inertialModeControllerParameters.nullspaceSpeed);
|
||||||
break;
|
break;
|
||||||
case 0x6:
|
case 0x6:
|
||||||
parameterWrapper->set(inertialModeControllerParameters.deSatGainFactor);
|
parameterWrapper->setVector(inertialModeControllerParameters.desatMomentumRef);
|
||||||
break;
|
break;
|
||||||
case 0x7:
|
case 0x7:
|
||||||
parameterWrapper->set(inertialModeControllerParameters.desatOn);
|
parameterWrapper->set(inertialModeControllerParameters.deSatGainFactor);
|
||||||
break;
|
break;
|
||||||
case 0x8:
|
case 0x8:
|
||||||
parameterWrapper->set(inertialModeControllerParameters.enableAntiStiction);
|
parameterWrapper->set(inertialModeControllerParameters.desatOn);
|
||||||
break;
|
break;
|
||||||
case 0x9:
|
case 0x9:
|
||||||
parameterWrapper->setVector(inertialModeControllerParameters.tgtQuat);
|
parameterWrapper->set(inertialModeControllerParameters.enableAntiStiction);
|
||||||
break;
|
break;
|
||||||
case 0xA:
|
case 0xA:
|
||||||
|
parameterWrapper->setVector(inertialModeControllerParameters.tgtQuat);
|
||||||
|
break;
|
||||||
|
case 0xB:
|
||||||
parameterWrapper->setVector(inertialModeControllerParameters.refRotRate);
|
parameterWrapper->setVector(inertialModeControllerParameters.refRotRate);
|
||||||
break;
|
break;
|
||||||
case 0xC:
|
case 0xC:
|
||||||
@ -690,7 +711,7 @@ ReturnValue_t AcsParameters::getParameter(uint8_t domainId, uint8_t parameterId,
|
|||||||
parameterWrapper->setMatrix(magnetorquerParameter.inverseAlignment);
|
parameterWrapper->setMatrix(magnetorquerParameter.inverseAlignment);
|
||||||
break;
|
break;
|
||||||
case 0x5:
|
case 0x5:
|
||||||
parameterWrapper->set(magnetorquerParameter.dipolMax);
|
parameterWrapper->set(magnetorquerParameter.dipoleMax);
|
||||||
break;
|
break;
|
||||||
case 0x6:
|
case 0x6:
|
||||||
parameterWrapper->set(magnetorquerParameter.torqueDuration);
|
parameterWrapper->set(magnetorquerParameter.torqueDuration);
|
||||||
|
@ -781,9 +781,9 @@ class AcsParameters : public HasParametersIF {
|
|||||||
|
|
||||||
/* var = sigma^2, sigma = RND*sqrt(freq), following values are RND^2 and not var as freq is
|
/* var = sigma^2, sigma = RND*sqrt(freq), following values are RND^2 and not var as freq is
|
||||||
* assumed to be equal for the same class of sensors */
|
* assumed to be equal for the same class of sensors */
|
||||||
float gyr02variance[3] = {pow(3.0e-3, 2), // RND_x = 3.0e-3 deg/s/sqrt(Hz) rms
|
float gyr02variance[3] = {pow(4.6e-3, 2), // RND_x = 3.0e-3 deg/s/sqrt(Hz) rms
|
||||||
pow(3.0e-3, 2), // RND_y = 3.0e-3 deg/s/sqrt(Hz) rms
|
pow(4.6e-3, 2), // RND_y = 3.0e-3 deg/s/sqrt(Hz) rms
|
||||||
pow(4.3e-3, 2)}; // RND_z = 4.3e-3 deg/s/sqrt(Hz) rms
|
pow(6.1e-3, 2)}; // RND_z = 4.3e-3 deg/s/sqrt(Hz) rms
|
||||||
float gyr13variance[3] = {pow(11e-3, 2), pow(11e-3, 2), pow(11e-3, 2)};
|
float gyr13variance[3] = {pow(11e-3, 2), pow(11e-3, 2), pow(11e-3, 2)};
|
||||||
uint8_t preferAdis = false;
|
uint8_t preferAdis = false;
|
||||||
float gyrFilterWeight = 0.6;
|
float gyrFilterWeight = 0.6;
|
||||||
@ -798,6 +798,8 @@ class AcsParameters : public HasParametersIF {
|
|||||||
double stictionTorque = 0.0006;
|
double stictionTorque = 0.0006;
|
||||||
|
|
||||||
uint16_t rampTime = 10;
|
uint16_t rampTime = 10;
|
||||||
|
|
||||||
|
uint32_t multipleRwInvalidTimeout = 25;
|
||||||
} rwHandlingParameters;
|
} rwHandlingParameters;
|
||||||
|
|
||||||
struct RwMatrices {
|
struct RwMatrices {
|
||||||
@ -814,7 +816,7 @@ class AcsParameters : public HasParametersIF {
|
|||||||
{1.0864, 0, 0}, {-0.5432, -0.5432, 1.2797}, {0, 0, 0}, {-0.5432, 0.5432, 1.2797}};
|
{1.0864, 0, 0}, {-0.5432, -0.5432, 1.2797}, {0, 0, 0}, {-0.5432, 0.5432, 1.2797}};
|
||||||
double without4[4][3] = {
|
double without4[4][3] = {
|
||||||
{0.5432, 0.5432, 1.2797}, {0, -1.0864, 0}, {-0.5432, 0.5432, 1.2797}, {0, 0, 0}};
|
{0.5432, 0.5432, 1.2797}, {0, -1.0864, 0}, {-0.5432, 0.5432, 1.2797}, {0, 0, 0}};
|
||||||
double nullspace[4] = {-0.5000, 0.5000, -0.5000, 0.5000};
|
double nullspaceVector[4] = {-1, 1, -1, 1};
|
||||||
} rwMatrices;
|
} rwMatrices;
|
||||||
|
|
||||||
struct SafeModeControllerParameters {
|
struct SafeModeControllerParameters {
|
||||||
@ -838,7 +840,9 @@ class AcsParameters : public HasParametersIF {
|
|||||||
double om = 0.3;
|
double om = 0.3;
|
||||||
double omMax = 1 * M_PI / 180;
|
double omMax = 1 * M_PI / 180;
|
||||||
double qiMin = 0.1;
|
double qiMin = 0.1;
|
||||||
|
|
||||||
double gainNullspace = 0.01;
|
double gainNullspace = 0.01;
|
||||||
|
double nullspaceSpeed = 32500; // 0.1 RPM
|
||||||
|
|
||||||
double desatMomentumRef[3] = {0, 0, 0};
|
double desatMomentumRef[3] = {0, 0, 0};
|
||||||
double deSatGainFactor = 1000;
|
double deSatGainFactor = 1000;
|
||||||
@ -931,7 +935,7 @@ class AcsParameters : public HasParametersIF {
|
|||||||
double mtq2orientationMatrix[3][3] = {{0, 0, 1}, {0, 1, 0}, {-1, 0, 0}};
|
double mtq2orientationMatrix[3][3] = {{0, 0, 1}, {0, 1, 0}, {-1, 0, 0}};
|
||||||
double alignmentMatrixMtq[3][3] = {{0, 0, -1}, {-1, 0, 0}, {0, 1, 0}};
|
double alignmentMatrixMtq[3][3] = {{0, 0, -1}, {-1, 0, 0}, {0, 1, 0}};
|
||||||
double inverseAlignment[3][3] = {{0, -1, 0}, {0, 0, 1}, {-1, 0, 0}};
|
double inverseAlignment[3][3] = {{0, -1, 0}, {0, 0, 1}, {-1, 0, 0}};
|
||||||
double dipolMax = 0.2; // [Am^2]
|
double dipoleMax = 0.2; // [Am^2]
|
||||||
|
|
||||||
uint16_t torqueDuration = 300; // [ms]
|
uint16_t torqueDuration = 300; // [ms]
|
||||||
} magnetorquerParameter;
|
} magnetorquerParameter;
|
||||||
|
@ -5,11 +5,6 @@
|
|||||||
#include <fsfw/globalfunctions/math/QuaternionOperations.h>
|
#include <fsfw/globalfunctions/math/QuaternionOperations.h>
|
||||||
#include <fsfw/globalfunctions/math/VectorOperations.h>
|
#include <fsfw/globalfunctions/math/VectorOperations.h>
|
||||||
|
|
||||||
#include <cmath>
|
|
||||||
|
|
||||||
#include "util/CholeskyDecomposition.h"
|
|
||||||
#include "util/MathOperations.h"
|
|
||||||
|
|
||||||
ActuatorCmd::ActuatorCmd() {}
|
ActuatorCmd::ActuatorCmd() {}
|
||||||
|
|
||||||
ActuatorCmd::~ActuatorCmd() {}
|
ActuatorCmd::~ActuatorCmd() {}
|
||||||
@ -25,24 +20,30 @@ void ActuatorCmd::scalingTorqueRws(double *rwTrq, double maxTorque) {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void ActuatorCmd::cmdSpeedToRws(int32_t speedRw0, int32_t speedRw1, int32_t speedRw2,
|
void ActuatorCmd::cmdSpeedToRws(const int32_t speedRw0, const int32_t speedRw1,
|
||||||
int32_t speedRw3, const double *rwTorque, int32_t *rwCmdSpeed,
|
const int32_t speedRw2, const int32_t speedRw3,
|
||||||
double sampleTime, int32_t maxRwSpeed, double inertiaWheel) {
|
const double sampleTime, const double inertiaWheel,
|
||||||
using namespace Math;
|
const int32_t maxRwSpeed, const double *rwTorque,
|
||||||
|
int32_t *rwCmdSpeed) {
|
||||||
// Calculating the commanded speed in RPM for every reaction wheel
|
// group RW speed values (in 0.1 [RPM]) in vector
|
||||||
int32_t speedRws[4] = {speedRw0, speedRw1, speedRw2, speedRw3};
|
int32_t speedRws[4] = {speedRw0, speedRw1, speedRw2, speedRw3};
|
||||||
|
|
||||||
|
// calculate required RW speed as sum of current RW speed and RW speed delta
|
||||||
|
// delta w_rw = delta t / I_RW * torque_RW [rad/s]
|
||||||
double deltaSpeed[4] = {0, 0, 0, 0};
|
double deltaSpeed[4] = {0, 0, 0, 0};
|
||||||
double radToRpm = 60 / (2 * PI); // factor for conversion to RPM
|
const double factor = sampleTime / inertiaWheel * RAD_PER_SEC_TO_RPM * 10;
|
||||||
// W_RW = Torque_RW / I_RW * delta t [rad/s]
|
|
||||||
double factor = sampleTime / inertiaWheel * radToRpm;
|
|
||||||
int32_t deltaSpeedInt[4] = {0, 0, 0, 0};
|
|
||||||
VectorOperations<double>::mulScalar(rwTorque, factor, deltaSpeed, 4);
|
VectorOperations<double>::mulScalar(rwTorque, factor, deltaSpeed, 4);
|
||||||
|
|
||||||
|
// convert double to int32
|
||||||
|
int32_t deltaSpeedInt[4] = {0, 0, 0, 0};
|
||||||
for (int i = 0; i < 4; i++) {
|
for (int i = 0; i < 4; i++) {
|
||||||
deltaSpeedInt[i] = std::round(deltaSpeed[i]);
|
deltaSpeedInt[i] = std::round(deltaSpeed[i]);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// sum of current RW speed and RW speed delta
|
||||||
VectorOperations<int32_t>::add(speedRws, deltaSpeedInt, rwCmdSpeed, 4);
|
VectorOperations<int32_t>::add(speedRws, deltaSpeedInt, rwCmdSpeed, 4);
|
||||||
VectorOperations<int32_t>::mulScalar(rwCmdSpeed, 10, rwCmdSpeed, 4);
|
|
||||||
|
// crop values which would exceed the maximum possible RPM
|
||||||
for (uint8_t i = 0; i < 4; i++) {
|
for (uint8_t i = 0; i < 4; i++) {
|
||||||
if (rwCmdSpeed[i] > maxRwSpeed) {
|
if (rwCmdSpeed[i] > maxRwSpeed) {
|
||||||
rwCmdSpeed[i] = maxRwSpeed;
|
rwCmdSpeed[i] = maxRwSpeed;
|
||||||
@ -52,24 +53,25 @@ void ActuatorCmd::cmdSpeedToRws(int32_t speedRw0, int32_t speedRw1, int32_t spee
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void ActuatorCmd::cmdDipolMtq(const double *dipolMoment, int16_t *dipolMomentActuator,
|
void ActuatorCmd::cmdDipoleMtq(const double *inverseAlignment, const double maxDipole,
|
||||||
const double *inverseAlignment, double maxDipol) {
|
const double *dipoleMoment, int16_t *dipoleMomentActuator) {
|
||||||
// Convert to actuator frame
|
// convert to actuator frame
|
||||||
double dipolMomentActuatorDouble[3] = {0, 0, 0};
|
double dipoleMomentActuatorDouble[3] = {0, 0, 0};
|
||||||
MatrixOperations<double>::multiply(inverseAlignment, dipolMoment, dipolMomentActuatorDouble, 3, 3,
|
MatrixOperations<double>::multiply(inverseAlignment, dipoleMoment, dipoleMomentActuatorDouble, 3,
|
||||||
1);
|
3, 1);
|
||||||
// Scaling along largest element if dipol exceeds maximum
|
// scaling along largest element if dipole exceeds maximum
|
||||||
uint8_t maxIdx = 0;
|
uint8_t maxIdx = 0;
|
||||||
VectorOperations<double>::maxAbsValue(dipolMomentActuatorDouble, 3, &maxIdx);
|
VectorOperations<double>::maxAbsValue(dipoleMomentActuatorDouble, 3, &maxIdx);
|
||||||
double maxAbsValue = abs(dipolMomentActuatorDouble[maxIdx]);
|
double maxAbsValue = std::abs(dipoleMomentActuatorDouble[maxIdx]);
|
||||||
if (maxAbsValue > maxDipol) {
|
if (maxAbsValue > maxDipole) {
|
||||||
double scalingFactor = maxDipol / maxAbsValue;
|
double scalingFactor = maxDipole / maxAbsValue;
|
||||||
VectorOperations<double>::mulScalar(dipolMomentActuatorDouble, scalingFactor,
|
VectorOperations<double>::mulScalar(dipoleMomentActuatorDouble, scalingFactor,
|
||||||
dipolMomentActuatorDouble, 3);
|
dipoleMomentActuatorDouble, 3);
|
||||||
}
|
}
|
||||||
// scale dipole from 1 Am^2 to 1e^-4 Am^2
|
// scale dipole from 1 Am^2 to 1e^-4 Am^2
|
||||||
VectorOperations<double>::mulScalar(dipolMomentActuatorDouble, 1e4, dipolMomentActuatorDouble, 3);
|
VectorOperations<double>::mulScalar(dipoleMomentActuatorDouble, 1e4, dipoleMomentActuatorDouble,
|
||||||
|
3);
|
||||||
for (int i = 0; i < 3; i++) {
|
for (int i = 0; i < 3; i++) {
|
||||||
dipolMomentActuator[i] = std::round(dipolMomentActuatorDouble[i]);
|
dipoleMomentActuator[i] = std::round(dipoleMomentActuatorDouble[i]);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -1,9 +1,7 @@
|
|||||||
#ifndef ACTUATORCMD_H_
|
#ifndef ACTUATORCMD_H_
|
||||||
#define ACTUATORCMD_H_
|
#define ACTUATORCMD_H_
|
||||||
|
|
||||||
#include "MultiplicativeKalmanFilter.h"
|
#include <cmath>
|
||||||
#include "SensorProcessing.h"
|
|
||||||
#include "SensorValues.h"
|
|
||||||
|
|
||||||
class ActuatorCmd {
|
class ActuatorCmd {
|
||||||
public:
|
public:
|
||||||
@ -19,29 +17,30 @@ class ActuatorCmd {
|
|||||||
void scalingTorqueRws(double *rwTrq, double maxTorque);
|
void scalingTorqueRws(double *rwTrq, double maxTorque);
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* @brief: cmdSpeedToRws() will set the maximum possible torque for the reaction
|
* @brief: cmdSpeedToRws() Calculates the RPM for the reaction wheel configuration,
|
||||||
* wheels, also will calculate the needed revolutions per minute for the RWs, which will be given
|
* given the required torque calculated by the controller. Will also scale down the RPM of the
|
||||||
* as Input to the RWs
|
* wheels if they exceed the maximum possible RPM
|
||||||
* @param: rwTrqIn given torque from pointing controller
|
* @param: rwTrq given torque from pointing controller
|
||||||
* rwTrqNS Nullspace torque
|
|
||||||
* rwCmdSpeed output revolutions per minute for every
|
* rwCmdSpeed output revolutions per minute for every
|
||||||
* reaction wheel
|
* reaction wheel
|
||||||
*/
|
*/
|
||||||
void cmdSpeedToRws(int32_t speedRw0, int32_t speedRw1, int32_t speedRw2, int32_t speedRw3,
|
void cmdSpeedToRws(const int32_t speedRw0, const int32_t speedRw1, const int32_t speedRw2,
|
||||||
const double *rwTorque, int32_t *rwCmdSpeed, double sampleTime,
|
const int32_t speedRw3, const double sampleTime, const double inertiaWheel,
|
||||||
int32_t maxRwSpeed, double inertiaWheel);
|
const int32_t maxRwSpeed, const double *rwTorque, int32_t *rwCmdSpeed);
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* @brief: cmdDipolMtq() gives the commanded dipol moment for the magnetorques
|
* @brief: cmdDipoleMtq() gives the commanded dipole moment for the
|
||||||
|
* magnetorquer
|
||||||
*
|
*
|
||||||
* @param: dipolMoment given dipol moment in spacecraft frame
|
* @param: dipoleMoment given dipole moment in spacecraft frame
|
||||||
* dipolMomentActuator resulting dipol moment in actuator reference frame
|
* dipoleMomentActuator resulting dipole moment in actuator reference frame
|
||||||
*/
|
*/
|
||||||
void cmdDipolMtq(const double *dipolMoment, int16_t *dipolMomentActuator,
|
void cmdDipoleMtq(const double *inverseAlignment, const double maxDipole,
|
||||||
const double *inverseAlignment, double maxDipol);
|
const double *dipoleMoment, int16_t *dipoleMomentActuator);
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
private:
|
private:
|
||||||
|
static constexpr double RAD_PER_SEC_TO_RPM = 60 / (2 * M_PI);
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* ACTUATORCMD_H_ */
|
#endif /* ACTUATORCMD_H_ */
|
||||||
|
@ -266,7 +266,8 @@ void Guidance::targetQuatPtgGs(timeval now, double posSatE[3], double sunDirI[3]
|
|||||||
targetRotationRate(timeElapsedMax, now, targetQuat, targetSatRotRate);
|
targetRotationRate(timeElapsedMax, now, targetQuat, targetSatRotRate);
|
||||||
}
|
}
|
||||||
|
|
||||||
void Guidance::targetQuatPtgSun(double sunDirI[3], double targetQuat[4], double refSatRate[3]) {
|
void Guidance::targetQuatPtgSun(timeval now, double sunDirI[3], double targetQuat[4],
|
||||||
|
double targetSatRotRate[3]) {
|
||||||
//-------------------------------------------------------------------------------------
|
//-------------------------------------------------------------------------------------
|
||||||
// Calculation of target quaternion to sun
|
// Calculation of target quaternion to sun
|
||||||
//-------------------------------------------------------------------------------------
|
//-------------------------------------------------------------------------------------
|
||||||
@ -296,9 +297,8 @@ void Guidance::targetQuatPtgSun(double sunDirI[3], double targetQuat[4], double
|
|||||||
//----------------------------------------------------------------------------
|
//----------------------------------------------------------------------------
|
||||||
// Calculation of reference rotation rate
|
// Calculation of reference rotation rate
|
||||||
//----------------------------------------------------------------------------
|
//----------------------------------------------------------------------------
|
||||||
refSatRate[0] = 0;
|
int8_t timeElapsedMax = acsParameters->gsTargetModeControllerParameters.timeElapsedMax;
|
||||||
refSatRate[1] = 0;
|
targetRotationRate(timeElapsedMax, now, targetQuat, targetSatRotRate);
|
||||||
refSatRate[2] = 0;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void Guidance::targetQuatPtgNadirSingleAxis(timeval now, double posSatE[3], double quatBI[4],
|
void Guidance::targetQuatPtgNadirSingleAxis(timeval now, double posSatE[3], double quatBI[4],
|
||||||
@ -412,7 +412,7 @@ void Guidance::targetQuatPtgNadirThreeAxes(timeval now, double posSatE[3], doubl
|
|||||||
|
|
||||||
void Guidance::comparePtg(double currentQuat[4], double currentSatRotRate[3], double targetQuat[4],
|
void Guidance::comparePtg(double currentQuat[4], double currentSatRotRate[3], double targetQuat[4],
|
||||||
double targetSatRotRate[3], double refQuat[4], double refSatRotRate[3],
|
double targetSatRotRate[3], double refQuat[4], double refSatRotRate[3],
|
||||||
double errorQuat[4], double errorSatRotRate[3], double errorAngle) {
|
double errorQuat[4], double errorSatRotRate[3], double &errorAngle) {
|
||||||
// First calculate error quaternion between current and target orientation
|
// First calculate error quaternion between current and target orientation
|
||||||
QuaternionOperations::multiply(currentQuat, targetQuat, errorQuat);
|
QuaternionOperations::multiply(currentQuat, targetQuat, errorQuat);
|
||||||
// Last calculate add rotation from reference quaternion
|
// Last calculate add rotation from reference quaternion
|
||||||
@ -424,26 +424,17 @@ void Guidance::comparePtg(double currentQuat[4], double currentSatRotRate[3], do
|
|||||||
// Calculate error angle
|
// Calculate error angle
|
||||||
errorAngle = QuaternionOperations::getAngle(errorQuat, true);
|
errorAngle = QuaternionOperations::getAngle(errorQuat, true);
|
||||||
|
|
||||||
// Only give back error satellite rotational rate if orientation has already been aquired
|
// Calculate error satellite rotational rate
|
||||||
if (errorAngle < 2. / 180. * M_PI) {
|
|
||||||
// First combine the target and reference satellite rotational rates
|
// First combine the target and reference satellite rotational rates
|
||||||
double combinedRefSatRotRate[3] = {0, 0, 0};
|
double combinedRefSatRotRate[3] = {0, 0, 0};
|
||||||
VectorOperations<double>::add(targetSatRotRate, refSatRotRate, combinedRefSatRotRate, 3);
|
VectorOperations<double>::add(targetSatRotRate, refSatRotRate, combinedRefSatRotRate, 3);
|
||||||
// Then substract the combined required satellite rotational rates from the actual rate
|
// Then subtract the combined required satellite rotational rates from the actual rate
|
||||||
VectorOperations<double>::subtract(currentSatRotRate, combinedRefSatRotRate, errorSatRotRate,
|
VectorOperations<double>::subtract(currentSatRotRate, combinedRefSatRotRate, errorSatRotRate, 3);
|
||||||
3);
|
|
||||||
} else {
|
|
||||||
// If orientation has not been aquired yet set satellite rotational rate to zero
|
|
||||||
errorSatRotRate = 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
// target flag in matlab, importance, does look like it only gives feedback if pointing control is
|
|
||||||
// under 150 arcsec ??
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void Guidance::comparePtg(double currentQuat[4], double currentSatRotRate[3], double targetQuat[4],
|
void Guidance::comparePtg(double currentQuat[4], double currentSatRotRate[3], double targetQuat[4],
|
||||||
double targetSatRotRate[3], double errorQuat[4],
|
double targetSatRotRate[3], double errorQuat[4],
|
||||||
double errorSatRotRate[3], double errorAngle) {
|
double errorSatRotRate[3], double &errorAngle) {
|
||||||
// First calculate error quaternion between current and target orientation
|
// First calculate error quaternion between current and target orientation
|
||||||
QuaternionOperations::multiply(currentQuat, targetQuat, errorQuat);
|
QuaternionOperations::multiply(currentQuat, targetQuat, errorQuat);
|
||||||
// Keep scalar part of quaternion positive
|
// Keep scalar part of quaternion positive
|
||||||
@ -453,17 +444,8 @@ void Guidance::comparePtg(double currentQuat[4], double currentSatRotRate[3], do
|
|||||||
// Calculate error angle
|
// Calculate error angle
|
||||||
errorAngle = QuaternionOperations::getAngle(errorQuat, true);
|
errorAngle = QuaternionOperations::getAngle(errorQuat, true);
|
||||||
|
|
||||||
// Only give back error satellite rotational rate if orientation has already been aquired
|
// Calculate error satellite rotational rate
|
||||||
if (errorAngle < 2. / 180. * M_PI) {
|
|
||||||
// Then substract the combined required satellite rotational rates from the actual rate
|
|
||||||
VectorOperations<double>::subtract(currentSatRotRate, targetSatRotRate, errorSatRotRate, 3);
|
VectorOperations<double>::subtract(currentSatRotRate, targetSatRotRate, errorSatRotRate, 3);
|
||||||
} else {
|
|
||||||
// If orientation has not been aquired yet set satellite rotational rate to zero
|
|
||||||
errorSatRotRate = 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
// target flag in matlab, importance, does look like it only gives feedback if pointing control is
|
|
||||||
// under 150 arcsec ??
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void Guidance::targetRotationRate(int8_t timeElapsedMax, timeval now, double quatInertialTarget[4],
|
void Guidance::targetRotationRate(int8_t timeElapsedMax, timeval now, double quatInertialTarget[4],
|
||||||
@ -471,20 +453,25 @@ void Guidance::targetRotationRate(int8_t timeElapsedMax, timeval now, double qua
|
|||||||
//-------------------------------------------------------------------------------------
|
//-------------------------------------------------------------------------------------
|
||||||
// Calculation of target rotation rate
|
// Calculation of target rotation rate
|
||||||
//-------------------------------------------------------------------------------------
|
//-------------------------------------------------------------------------------------
|
||||||
double timeElapsed = now.tv_sec + now.tv_usec * pow(10, -6) -
|
double timeElapsed = now.tv_sec + now.tv_usec * 1e-6 -
|
||||||
(timeSavedQuaternion.tv_sec +
|
(timeSavedQuaternion.tv_sec + timeSavedQuaternion.tv_usec * 1e-6);
|
||||||
timeSavedQuaternion.tv_usec * pow((double)timeSavedQuaternion.tv_usec, -6));
|
if (VectorOperations<double>::norm(savedQuaternion, 4) == 0) {
|
||||||
|
std::memcpy(savedQuaternion, quatInertialTarget, sizeof(savedQuaternion));
|
||||||
|
}
|
||||||
if (timeElapsed < timeElapsedMax) {
|
if (timeElapsed < timeElapsedMax) {
|
||||||
|
double q[4] = {0, 0, 0, 0}, qS[4] = {0, 0, 0, 0};
|
||||||
|
QuaternionOperations::inverse(quatInertialTarget, q);
|
||||||
|
QuaternionOperations::inverse(savedQuaternion, qS);
|
||||||
double qDiff[4] = {0, 0, 0, 0};
|
double qDiff[4] = {0, 0, 0, 0};
|
||||||
VectorOperations<double>::subtract(quatInertialTarget, savedQuaternion, qDiff, 4);
|
VectorOperations<double>::subtract(q, qS, qDiff, 4);
|
||||||
VectorOperations<double>::mulScalar(qDiff, 1 / timeElapsed, qDiff, 4);
|
VectorOperations<double>::mulScalar(qDiff, 1 / timeElapsed, qDiff, 4);
|
||||||
|
|
||||||
double tgtQuatVec[3] = {quatInertialTarget[0], quatInertialTarget[1], quatInertialTarget[2]},
|
double tgtQuatVec[3] = {q[0], q[1], q[2]};
|
||||||
qDiffVec[3] = {qDiff[0], qDiff[1], qDiff[2]};
|
double qDiffVec[3] = {qDiff[0], qDiff[1], qDiff[2]};
|
||||||
double sum1[3] = {0, 0, 0}, sum2[3] = {0, 0, 0}, sum3[3] = {0, 0, 0}, sum[3] = {0, 0, 0};
|
double sum1[3] = {0, 0, 0}, sum2[3] = {0, 0, 0}, sum3[3] = {0, 0, 0}, sum[3] = {0, 0, 0};
|
||||||
VectorOperations<double>::cross(quatInertialTarget, qDiff, sum1);
|
VectorOperations<double>::cross(tgtQuatVec, qDiffVec, sum1);
|
||||||
VectorOperations<double>::mulScalar(tgtQuatVec, qDiff[3], sum2, 3);
|
VectorOperations<double>::mulScalar(tgtQuatVec, qDiff[3], sum2, 3);
|
||||||
VectorOperations<double>::mulScalar(qDiffVec, quatInertialTarget[3], sum3, 3);
|
VectorOperations<double>::mulScalar(qDiffVec, q[3], sum3, 3);
|
||||||
VectorOperations<double>::add(sum1, sum2, sum, 3);
|
VectorOperations<double>::add(sum1, sum2, sum, 3);
|
||||||
VectorOperations<double>::subtract(sum, sum3, sum, 3);
|
VectorOperations<double>::subtract(sum, sum3, sum, 3);
|
||||||
double omegaRefNew[3] = {0, 0, 0};
|
double omegaRefNew[3] = {0, 0, 0};
|
||||||
@ -531,10 +518,6 @@ ReturnValue_t Guidance::getDistributionMatrixRw(ACS::SensorValues *sensorValues,
|
|||||||
std::memcpy(rwPseudoInv, acsParameters->rwMatrices.without4, 12 * sizeof(double));
|
std::memcpy(rwPseudoInv, acsParameters->rwMatrices.without4, 12 * sizeof(double));
|
||||||
return returnvalue::OK;
|
return returnvalue::OK;
|
||||||
} else {
|
} else {
|
||||||
// @note: This one takes the normal pseudoInverse of all four raction wheels valid.
|
|
||||||
// Does not make sense, but is implemented that way in MATLAB ?!
|
|
||||||
// Thought: It does not really play a role, because in case there are more then one
|
|
||||||
// reaction wheel invalid the pointing control is destined to fail.
|
|
||||||
return returnvalue::FAILED;
|
return returnvalue::FAILED;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -15,7 +15,7 @@ class Guidance {
|
|||||||
void getTargetParamsSafe(double sunTargetSafe[3]);
|
void getTargetParamsSafe(double sunTargetSafe[3]);
|
||||||
ReturnValue_t solarArrayDeploymentComplete();
|
ReturnValue_t solarArrayDeploymentComplete();
|
||||||
|
|
||||||
// Function to get the target quaternion and refence rotation rate from gps position and
|
// Function to get the target quaternion and reference rotation rate from gps position and
|
||||||
// position of the ground station
|
// position of the ground station
|
||||||
void targetQuatPtgSingleAxis(timeval now, double posSatE[3], double velSatE[3], double sunDirI[3],
|
void targetQuatPtgSingleAxis(timeval now, double posSatE[3], double velSatE[3], double sunDirI[3],
|
||||||
double refDirB[3], double quatBI[4], double targetQuat[4],
|
double refDirB[3], double quatBI[4], double targetQuat[4],
|
||||||
@ -25,9 +25,10 @@ class Guidance {
|
|||||||
void targetQuatPtgGs(timeval now, double posSatE[3], double sunDirI[3], double quatIX[4],
|
void targetQuatPtgGs(timeval now, double posSatE[3], double sunDirI[3], double quatIX[4],
|
||||||
double targetSatRotRate[3]);
|
double targetSatRotRate[3]);
|
||||||
|
|
||||||
// Function to get the target quaternion and refence rotation rate for sun pointing after ground
|
// Function to get the target quaternion and reference rotation rate for sun pointing after ground
|
||||||
// station
|
// station
|
||||||
void targetQuatPtgSun(double sunDirI[3], double targetQuat[4], double refSatRate[3]);
|
void targetQuatPtgSun(timeval now, double sunDirI[3], double targetQuat[4],
|
||||||
|
double targetSatRotRate[3]);
|
||||||
|
|
||||||
// Function to get the target quaternion and refence rotation rate from gps position for Nadir
|
// Function to get the target quaternion and refence rotation rate from gps position for Nadir
|
||||||
// pointing
|
// pointing
|
||||||
@ -42,10 +43,10 @@ class Guidance {
|
|||||||
// rate. Lastly gives back the error angle of the error quaternion.
|
// rate. Lastly gives back the error angle of the error quaternion.
|
||||||
void comparePtg(double currentQuat[4], double currentSatRotRate[3], double targetQuat[4],
|
void comparePtg(double currentQuat[4], double currentSatRotRate[3], double targetQuat[4],
|
||||||
double targetSatRotRate[3], double refQuat[4], double refSatRotRate[3],
|
double targetSatRotRate[3], double refQuat[4], double refSatRotRate[3],
|
||||||
double errorQuat[4], double errorSatRotRate[3], double errorAngle);
|
double errorQuat[4], double errorSatRotRate[3], double &errorAngle);
|
||||||
void comparePtg(double currentQuat[4], double currentSatRotRate[3], double targetQuat[4],
|
void comparePtg(double currentQuat[4], double currentSatRotRate[3], double targetQuat[4],
|
||||||
double targetSatRotRate[3], double errorQuat[4], double errorSatRotRate[3],
|
double targetSatRotRate[3], double errorQuat[4], double errorSatRotRate[3],
|
||||||
double errorAngle);
|
double &errorAngle);
|
||||||
|
|
||||||
void targetRotationRate(int8_t timeElapsedMax, timeval now, double quatInertialTarget[4],
|
void targetRotationRate(int8_t timeElapsedMax, timeval now, double quatInertialTarget[4],
|
||||||
double *targetSatRotRate);
|
double *targetSatRotRate);
|
||||||
|
@ -19,9 +19,7 @@ ReturnValue_t Navigation::useMekf(ACS::SensorValues *sensorValues,
|
|||||||
acsctrl::MekfData *mekfData, AcsParameters *acsParameters) {
|
acsctrl::MekfData *mekfData, AcsParameters *acsParameters) {
|
||||||
double quatIB[4] = {sensorValues->strSet.caliQx.value, sensorValues->strSet.caliQy.value,
|
double quatIB[4] = {sensorValues->strSet.caliQx.value, sensorValues->strSet.caliQy.value,
|
||||||
sensorValues->strSet.caliQz.value, sensorValues->strSet.caliQw.value};
|
sensorValues->strSet.caliQz.value, sensorValues->strSet.caliQw.value};
|
||||||
bool quatIBValid = sensorValues->strSet.caliQx.isValid() &&
|
bool quatIBValid = sensorValues->strSet.isTrustWorthy.value;
|
||||||
sensorValues->strSet.caliQy.isValid() &&
|
|
||||||
sensorValues->strSet.caliQz.isValid() && sensorValues->strSet.caliQw.isValid();
|
|
||||||
|
|
||||||
if (mekfStatus == MultiplicativeKalmanFilter::MEKF_UNINITIALIZED) {
|
if (mekfStatus == MultiplicativeKalmanFilter::MEKF_UNINITIALIZED) {
|
||||||
mekfStatus = multiplicativeKalmanFilter.init(
|
mekfStatus = multiplicativeKalmanFilter.init(
|
||||||
|
@ -573,7 +573,7 @@ void SensorProcessing::processGps(const double gpsLatitude, const double gpsLong
|
|||||||
|
|
||||||
// Altitude FDIR
|
// Altitude FDIR
|
||||||
if (gpsAltitude > gpsParameters->maximumFdirAltitude ||
|
if (gpsAltitude > gpsParameters->maximumFdirAltitude ||
|
||||||
gpsAltitude < gpsParameters->maximumFdirAltitude) {
|
gpsAltitude < gpsParameters->minimumFdirAltitude) {
|
||||||
altitude = gpsParameters->fdirAltitude;
|
altitude = gpsParameters->fdirAltitude;
|
||||||
} else {
|
} else {
|
||||||
altitude = gpsAltitude;
|
altitude = gpsAltitude;
|
||||||
|
@ -7,8 +7,10 @@ Detumble::Detumble() {}
|
|||||||
|
|
||||||
Detumble::~Detumble() {}
|
Detumble::~Detumble() {}
|
||||||
|
|
||||||
uint8_t Detumble::detumbleStrategy(const bool magFieldValid, const bool satRotRateValid,
|
acs::SafeModeStrategy Detumble::detumbleStrategy(const bool magFieldValid,
|
||||||
const bool magFieldRateValid, const bool useFullDetumbleLaw) {
|
const bool satRotRateValid,
|
||||||
|
const bool magFieldRateValid,
|
||||||
|
const bool useFullDetumbleLaw) {
|
||||||
if (not magFieldValid) {
|
if (not magFieldValid) {
|
||||||
return acs::SafeModeStrategy::SAFECTRL_NO_MAG_FIELD_FOR_CONTROL;
|
return acs::SafeModeStrategy::SAFECTRL_NO_MAG_FIELD_FOR_CONTROL;
|
||||||
} else if (satRotRateValid and useFullDetumbleLaw) {
|
} else if (satRotRateValid and useFullDetumbleLaw) {
|
||||||
|
@ -11,8 +11,9 @@ class Detumble {
|
|||||||
Detumble();
|
Detumble();
|
||||||
virtual ~Detumble();
|
virtual ~Detumble();
|
||||||
|
|
||||||
uint8_t detumbleStrategy(const bool magFieldValid, const bool satRotRateValid,
|
acs::SafeModeStrategy detumbleStrategy(const bool magFieldValid, const bool satRotRateValid,
|
||||||
const bool magFieldRateValid, const bool useFullDetumbleLaw);
|
const bool magFieldRateValid,
|
||||||
|
const bool useFullDetumbleLaw);
|
||||||
|
|
||||||
void bDotLawFull(const double *satRotRateB, const double *magFieldB, double *magMomB,
|
void bDotLawFull(const double *satRotRateB, const double *magFieldB, double *magMomB,
|
||||||
double gain);
|
double gain);
|
||||||
|
@ -5,9 +5,6 @@
|
|||||||
#include <fsfw/globalfunctions/math/QuaternionOperations.h>
|
#include <fsfw/globalfunctions/math/QuaternionOperations.h>
|
||||||
#include <fsfw/globalfunctions/math/VectorOperations.h>
|
#include <fsfw/globalfunctions/math/VectorOperations.h>
|
||||||
#include <fsfw/globalfunctions/sign.h>
|
#include <fsfw/globalfunctions/sign.h>
|
||||||
#include <math.h>
|
|
||||||
|
|
||||||
#include "../util/MathOperations.h"
|
|
||||||
|
|
||||||
PtgCtrl::PtgCtrl(AcsParameters *acsParameters_) { acsParameters = acsParameters_; }
|
PtgCtrl::PtgCtrl(AcsParameters *acsParameters_) { acsParameters = acsParameters_; }
|
||||||
|
|
||||||
@ -32,12 +29,13 @@ void PtgCtrl::ptgLaw(AcsParameters::PointingLawParameters *pointingLawParameters
|
|||||||
double qErrorLaw[3] = {0, 0, 0};
|
double qErrorLaw[3] = {0, 0, 0};
|
||||||
|
|
||||||
for (int i = 0; i < 3; i++) {
|
for (int i = 0; i < 3; i++) {
|
||||||
if (abs(qError[i]) < qErrorMin) {
|
if (std::abs(qError[i]) < qErrorMin) {
|
||||||
qErrorLaw[i] = qErrorMin;
|
qErrorLaw[i] = qErrorMin;
|
||||||
} else {
|
} else {
|
||||||
qErrorLaw[i] = abs(qError[i]);
|
qErrorLaw[i] = std::abs(qError[i]);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
double qErrorLawNorm = VectorOperations<double>::norm(qErrorLaw, 3);
|
double qErrorLawNorm = VectorOperations<double>::norm(qErrorLaw, 3);
|
||||||
|
|
||||||
double gain1 = cInt * omMax / qErrorLawNorm;
|
double gain1 = cInt * omMax / qErrorLawNorm;
|
||||||
@ -73,7 +71,7 @@ void PtgCtrl::ptgLaw(AcsParameters::PointingLawParameters *pointingLawParameters
|
|||||||
double pErrorSign[3] = {0, 0, 0};
|
double pErrorSign[3] = {0, 0, 0};
|
||||||
|
|
||||||
for (int i = 0; i < 3; i++) {
|
for (int i = 0; i < 3; i++) {
|
||||||
if (abs(pError[i]) > 1) {
|
if (std::abs(pError[i]) > 1) {
|
||||||
pErrorSign[i] = sign(pError[i]);
|
pErrorSign[i] = sign(pError[i]);
|
||||||
} else {
|
} else {
|
||||||
pErrorSign[i] = pError[i];
|
pErrorSign[i] = pError[i];
|
||||||
@ -98,61 +96,92 @@ void PtgCtrl::ptgLaw(AcsParameters::PointingLawParameters *pointingLawParameters
|
|||||||
VectorOperations<double>::mulScalar(torqueRws, -1, torqueRws, 4);
|
VectorOperations<double>::mulScalar(torqueRws, -1, torqueRws, 4);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void PtgCtrl::ptgNullspace(AcsParameters::PointingLawParameters *pointingLawParameters,
|
||||||
|
const int32_t speedRw0, const int32_t speedRw1, const int32_t speedRw2,
|
||||||
|
const int32_t speedRw3, double *rwTrqNs) {
|
||||||
|
// concentrate RW speeds as vector and convert to double
|
||||||
|
double speedRws[4] = {static_cast<double>(speedRw0), static_cast<double>(speedRw1),
|
||||||
|
static_cast<double>(speedRw2), static_cast<double>(speedRw3)};
|
||||||
|
VectorOperations<double>::mulScalar(speedRws, 1e-1, speedRws, 4);
|
||||||
|
VectorOperations<double>::mulScalar(speedRws, RPM_TO_RAD_PER_SEC, speedRws, 4);
|
||||||
|
|
||||||
|
// calculate RPM offset utilizing the nullspace
|
||||||
|
double rpmOffset[4] = {0, 0, 0, 0};
|
||||||
|
double rpmOffsetSpeed = pointingLawParameters->nullspaceSpeed / 10 * RPM_TO_RAD_PER_SEC;
|
||||||
|
VectorOperations<double>::mulScalar(acsParameters->rwMatrices.nullspaceVector, rpmOffsetSpeed,
|
||||||
|
rpmOffset, 4);
|
||||||
|
|
||||||
|
// calculate resulting angular momentum
|
||||||
|
double rwAngMomentum[4] = {0, 0, 0, 0}, diffRwSpeed[4] = {0, 0, 0, 0};
|
||||||
|
VectorOperations<double>::subtract(speedRws, rpmOffset, diffRwSpeed, 4);
|
||||||
|
VectorOperations<double>::mulScalar(diffRwSpeed, acsParameters->rwHandlingParameters.inertiaWheel,
|
||||||
|
rwAngMomentum, 4);
|
||||||
|
|
||||||
|
// calculate resulting torque
|
||||||
|
double nullspaceMatrix[4][4] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}, {0, 0, 0}};
|
||||||
|
MatrixOperations<double>::multiply(acsParameters->rwMatrices.nullspaceVector,
|
||||||
|
acsParameters->rwMatrices.nullspaceVector, *nullspaceMatrix, 4,
|
||||||
|
1, 4);
|
||||||
|
MatrixOperations<double>::multiply(*nullspaceMatrix, rwAngMomentum, rwTrqNs, 4, 4, 1);
|
||||||
|
VectorOperations<double>::mulScalar(rwTrqNs, -1 * pointingLawParameters->gainNullspace, rwTrqNs,
|
||||||
|
4);
|
||||||
|
}
|
||||||
|
|
||||||
void PtgCtrl::ptgDesaturation(AcsParameters::PointingLawParameters *pointingLawParameters,
|
void PtgCtrl::ptgDesaturation(AcsParameters::PointingLawParameters *pointingLawParameters,
|
||||||
double *magFieldEst, bool magFieldEstValid, double *satRate,
|
const double *magFieldB, const bool magFieldBValid,
|
||||||
int32_t *speedRw0, int32_t *speedRw1, int32_t *speedRw2,
|
const double *satRate, const int32_t speedRw0, const int32_t speedRw1,
|
||||||
int32_t *speedRw3, double *mgtDpDes) {
|
const int32_t speedRw2, const int32_t speedRw3, double *mgtDpDes) {
|
||||||
if (!(magFieldEstValid) || !(pointingLawParameters->desatOn)) {
|
if (not magFieldBValid or not pointingLawParameters->desatOn) {
|
||||||
mgtDpDes[0] = 0;
|
|
||||||
mgtDpDes[1] = 0;
|
|
||||||
mgtDpDes[2] = 0;
|
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
// calculating momentum of satellite and momentum of reaction wheels
|
// concentrate RW speeds as vector and convert to double
|
||||||
double speedRws[4] = {(double)*speedRw0, (double)*speedRw1, (double)*speedRw2, (double)*speedRw3};
|
double speedRws[4] = {static_cast<double>(speedRw0), static_cast<double>(speedRw1),
|
||||||
double momentumRwU[4] = {0, 0, 0, 0}, momentumRw[3] = {0, 0, 0};
|
static_cast<double>(speedRw2), static_cast<double>(speedRw3)};
|
||||||
VectorOperations<double>::mulScalar(speedRws, acsParameters->rwHandlingParameters.inertiaWheel,
|
|
||||||
momentumRwU, 4);
|
|
||||||
MatrixOperations<double>::multiply(*(acsParameters->rwMatrices.alignmentMatrix), momentumRwU,
|
|
||||||
momentumRw, 3, 4, 1);
|
|
||||||
double momentumSat[3] = {0, 0, 0}, momentumTotal[3] = {0, 0, 0};
|
|
||||||
MatrixOperations<double>::multiply(*(acsParameters->inertiaEIVE.inertiaMatrixDeployed), satRate,
|
|
||||||
momentumSat, 3, 3, 1);
|
|
||||||
VectorOperations<double>::add(momentumSat, momentumRw, momentumTotal, 3);
|
|
||||||
// calculating momentum error
|
|
||||||
double deltaMomentum[3] = {0, 0, 0};
|
|
||||||
VectorOperations<double>::subtract(momentumTotal, pointingLawParameters->desatMomentumRef,
|
|
||||||
deltaMomentum, 3);
|
|
||||||
// resulting magnetic dipole command
|
|
||||||
double crossMomentumMagField[3] = {0, 0, 0};
|
|
||||||
VectorOperations<double>::cross(deltaMomentum, magFieldEst, crossMomentumMagField);
|
|
||||||
double normMag = VectorOperations<double>::norm(magFieldEst, 3), factor = 0;
|
|
||||||
factor = (pointingLawParameters->deSatGainFactor) / normMag;
|
|
||||||
VectorOperations<double>::mulScalar(crossMomentumMagField, factor, mgtDpDes, 3);
|
|
||||||
}
|
|
||||||
|
|
||||||
void PtgCtrl::ptgNullspace(AcsParameters::PointingLawParameters *pointingLawParameters,
|
// convert magFieldB from uT to T
|
||||||
const int32_t *speedRw0, const int32_t *speedRw1,
|
double magFieldBT[3] = {0, 0, 0};
|
||||||
const int32_t *speedRw2, const int32_t *speedRw3, double *rwTrqNs) {
|
VectorOperations<double>::mulScalar(magFieldB, 1e-6, magFieldBT, 3);
|
||||||
double speedRws[4] = {(double)*speedRw0, (double)*speedRw1, (double)*speedRw2, (double)*speedRw3};
|
|
||||||
double wheelMomentum[4] = {0, 0, 0, 0};
|
// calculate angular momentum of the satellite
|
||||||
double rpmOffset[4] = {1, 1, 1, -1}, factor = 350 * 2 * Math::PI / 60;
|
double angMomentumSat[3] = {0, 0, 0};
|
||||||
// conversion to [rad/s] for further calculations
|
MatrixOperations<double>::multiply(*(acsParameters->inertiaEIVE.inertiaMatrixDeployed), satRate,
|
||||||
VectorOperations<double>::mulScalar(rpmOffset, factor, rpmOffset, 4);
|
angMomentumSat, 3, 3, 1);
|
||||||
VectorOperations<double>::mulScalar(speedRws, 2 * Math::PI / 60, speedRws, 4);
|
|
||||||
double diffRwSpeed[4] = {0, 0, 0, 0};
|
// calculate angular momentum of the reaction wheels with respect to the nullspace RW speed
|
||||||
VectorOperations<double>::subtract(speedRws, rpmOffset, diffRwSpeed, 4);
|
// relocate RW speed zero to nullspace RW speed
|
||||||
VectorOperations<double>::mulScalar(diffRwSpeed, acsParameters->rwHandlingParameters.inertiaWheel,
|
double refSpeedRws[4] = {0, 0, 0, 0};
|
||||||
wheelMomentum, 4);
|
VectorOperations<double>::mulScalar(acsParameters->rwMatrices.nullspaceVector,
|
||||||
double gainNs = pointingLawParameters->gainNullspace;
|
pointingLawParameters->nullspaceSpeed, refSpeedRws, 4);
|
||||||
double nullSpaceMatrix[4][4] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}, {0, 0, 0}};
|
VectorOperations<double>::subtract(speedRws, refSpeedRws, speedRws, 4);
|
||||||
MathOperations<double>::vecTransposeVecMatrix(acsParameters->rwMatrices.nullspace,
|
// convert speed from 10 RPM to 1 RPM
|
||||||
acsParameters->rwMatrices.nullspace,
|
VectorOperations<double>::mulScalar(speedRws, 1e-1, speedRws, 4);
|
||||||
*nullSpaceMatrix, 4);
|
// convert to rad/s
|
||||||
MatrixOperations<double>::multiply(*nullSpaceMatrix, wheelMomentum, rwTrqNs, 4, 4, 1);
|
VectorOperations<double>::mulScalar(speedRws, RPM_TO_RAD_PER_SEC, speedRws, 4);
|
||||||
VectorOperations<double>::mulScalar(rwTrqNs, gainNs, rwTrqNs, 4);
|
// calculate angular momentum of each RW
|
||||||
VectorOperations<double>::mulScalar(rwTrqNs, -1, rwTrqNs, 4);
|
double angMomentumRwU[4] = {0, 0, 0, 0};
|
||||||
|
VectorOperations<double>::mulScalar(speedRws, acsParameters->rwHandlingParameters.inertiaWheel,
|
||||||
|
angMomentumRwU, 4);
|
||||||
|
// convert RW angular momentum to body RF
|
||||||
|
double angMomentumRw[3] = {0, 0, 0};
|
||||||
|
MatrixOperations<double>::multiply(*(acsParameters->rwMatrices.alignmentMatrix), angMomentumRwU,
|
||||||
|
angMomentumRw, 3, 4, 1);
|
||||||
|
|
||||||
|
// calculate total angular momentum
|
||||||
|
double angMomentumTotal[3] = {0, 0, 0};
|
||||||
|
VectorOperations<double>::add(angMomentumSat, angMomentumRw, angMomentumTotal, 3);
|
||||||
|
|
||||||
|
// calculating momentum error
|
||||||
|
double deltaAngMomentum[3] = {0, 0, 0};
|
||||||
|
VectorOperations<double>::subtract(angMomentumTotal, pointingLawParameters->desatMomentumRef,
|
||||||
|
deltaAngMomentum, 3);
|
||||||
|
|
||||||
|
// resulting magnetic dipole command
|
||||||
|
double crossAngMomentumMagField[3] = {0, 0, 0};
|
||||||
|
VectorOperations<double>::cross(deltaAngMomentum, magFieldBT, crossAngMomentumMagField);
|
||||||
|
double factor =
|
||||||
|
pointingLawParameters->deSatGainFactor / VectorOperations<double>::norm(magFieldBT, 3);
|
||||||
|
VectorOperations<double>::mulScalar(crossAngMomentumMagField, factor, mgtDpDes, 3);
|
||||||
}
|
}
|
||||||
|
|
||||||
void PtgCtrl::rwAntistiction(ACS::SensorValues *sensorValues, int32_t *rwCmdSpeeds) {
|
void PtgCtrl::rwAntistiction(ACS::SensorValues *sensorValues, int32_t *rwCmdSpeeds) {
|
||||||
@ -169,15 +198,9 @@ void PtgCtrl::rwAntistiction(ACS::SensorValues *sensorValues, int32_t *rwCmdSpee
|
|||||||
if (rwCmdSpeeds[i] != 0) {
|
if (rwCmdSpeeds[i] != 0) {
|
||||||
if (rwCmdSpeeds[i] > -acsParameters->rwHandlingParameters.stictionSpeed &&
|
if (rwCmdSpeeds[i] > -acsParameters->rwHandlingParameters.stictionSpeed &&
|
||||||
rwCmdSpeeds[i] < acsParameters->rwHandlingParameters.stictionSpeed) {
|
rwCmdSpeeds[i] < acsParameters->rwHandlingParameters.stictionSpeed) {
|
||||||
if (currRwSpeed[i] == 0) {
|
if (rwCmdSpeeds[i] > currRwSpeed[i]) {
|
||||||
if (rwCmdSpeeds[i] > 0) {
|
|
||||||
rwCmdSpeeds[i] = acsParameters->rwHandlingParameters.stictionSpeed;
|
rwCmdSpeeds[i] = acsParameters->rwHandlingParameters.stictionSpeed;
|
||||||
} else if (rwCmdSpeeds[i] < 0) {
|
} else if (rwCmdSpeeds[i] < currRwSpeed[i]) {
|
||||||
rwCmdSpeeds[i] = -acsParameters->rwHandlingParameters.stictionSpeed;
|
|
||||||
}
|
|
||||||
} else if (currRwSpeed[i] < -acsParameters->rwHandlingParameters.stictionSpeed) {
|
|
||||||
rwCmdSpeeds[i] = acsParameters->rwHandlingParameters.stictionSpeed;
|
|
||||||
} else if (currRwSpeed[i] > acsParameters->rwHandlingParameters.stictionSpeed) {
|
|
||||||
rwCmdSpeeds[i] = -acsParameters->rwHandlingParameters.stictionSpeed;
|
rwCmdSpeeds[i] = -acsParameters->rwHandlingParameters.stictionSpeed;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -1,13 +1,10 @@
|
|||||||
#ifndef PTGCTRL_H_
|
#ifndef PTGCTRL_H_
|
||||||
#define PTGCTRL_H_
|
#define PTGCTRL_H_
|
||||||
|
|
||||||
|
#include <math.h>
|
||||||
|
#include <mission/controller/acs/AcsParameters.h>
|
||||||
|
#include <mission/controller/acs/SensorValues.h>
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
#include <string.h>
|
|
||||||
#include <time.h>
|
|
||||||
|
|
||||||
#include "../AcsParameters.h"
|
|
||||||
#include "../SensorValues.h"
|
|
||||||
#include "eive/resultClassIds.h"
|
|
||||||
|
|
||||||
class PtgCtrl {
|
class PtgCtrl {
|
||||||
/*
|
/*
|
||||||
@ -29,14 +26,14 @@ class PtgCtrl {
|
|||||||
void ptgLaw(AcsParameters::PointingLawParameters *pointingLawParameters, const double *qError,
|
void ptgLaw(AcsParameters::PointingLawParameters *pointingLawParameters, const double *qError,
|
||||||
const double *deltaRate, const double *rwPseudoInv, double *torqueRws);
|
const double *deltaRate, const double *rwPseudoInv, double *torqueRws);
|
||||||
|
|
||||||
void ptgDesaturation(AcsParameters::PointingLawParameters *pointingLawParameters,
|
|
||||||
double *magFieldEst, bool magFieldEstValid, double *satRate,
|
|
||||||
int32_t *speedRw0, int32_t *speedRw1, int32_t *speedRw2, int32_t *speedRw3,
|
|
||||||
double *mgtDpDes);
|
|
||||||
|
|
||||||
void ptgNullspace(AcsParameters::PointingLawParameters *pointingLawParameters,
|
void ptgNullspace(AcsParameters::PointingLawParameters *pointingLawParameters,
|
||||||
const int32_t *speedRw0, const int32_t *speedRw1, const int32_t *speedRw2,
|
const int32_t speedRw0, const int32_t speedRw1, const int32_t speedRw2,
|
||||||
const int32_t *speedRw3, double *rwTrqNs);
|
const int32_t speedRw3, double *rwTrqNs);
|
||||||
|
|
||||||
|
void ptgDesaturation(AcsParameters::PointingLawParameters *pointingLawParameters,
|
||||||
|
const double *magFieldB, const bool magFieldBValid, const double *satRate,
|
||||||
|
const int32_t speedRw0, const int32_t speedRw1, const int32_t speedRw2,
|
||||||
|
const int32_t speedRw3, double *mgtDpDes);
|
||||||
|
|
||||||
/* @brief: Commands the stiction torque in case wheel speed is to low
|
/* @brief: Commands the stiction torque in case wheel speed is to low
|
||||||
* torqueCommand modified torque after antistiction
|
* torqueCommand modified torque after antistiction
|
||||||
@ -45,6 +42,7 @@ class PtgCtrl {
|
|||||||
|
|
||||||
private:
|
private:
|
||||||
const AcsParameters *acsParameters;
|
const AcsParameters *acsParameters;
|
||||||
|
static constexpr double RPM_TO_RAD_PER_SEC = (2 * M_PI) / 60;
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* ACS_CONTROL_PTGCTRL_H_ */
|
#endif /* ACS_CONTROL_PTGCTRL_H_ */
|
||||||
|
@ -9,9 +9,10 @@ SafeCtrl::SafeCtrl(AcsParameters *acsParameters_) { acsParameters = acsParameter
|
|||||||
|
|
||||||
SafeCtrl::~SafeCtrl() {}
|
SafeCtrl::~SafeCtrl() {}
|
||||||
|
|
||||||
uint8_t SafeCtrl::safeCtrlStrategy(const bool magFieldValid, const bool mekfValid,
|
acs::SafeModeStrategy SafeCtrl::safeCtrlStrategy(const bool magFieldValid, const bool mekfValid,
|
||||||
const bool satRotRateValid, const bool sunDirValid,
|
const bool satRotRateValid, const bool sunDirValid,
|
||||||
const uint8_t mekfEnabled, const uint8_t dampingEnabled) {
|
const uint8_t mekfEnabled,
|
||||||
|
const uint8_t dampingEnabled) {
|
||||||
if (not magFieldValid) {
|
if (not magFieldValid) {
|
||||||
return acs::SafeModeStrategy::SAFECTRL_NO_MAG_FIELD_FOR_CONTROL;
|
return acs::SafeModeStrategy::SAFECTRL_NO_MAG_FIELD_FOR_CONTROL;
|
||||||
} else if (mekfEnabled and mekfValid) {
|
} else if (mekfEnabled and mekfValid) {
|
||||||
|
@ -12,7 +12,7 @@ class SafeCtrl {
|
|||||||
SafeCtrl(AcsParameters *acsParameters_);
|
SafeCtrl(AcsParameters *acsParameters_);
|
||||||
virtual ~SafeCtrl();
|
virtual ~SafeCtrl();
|
||||||
|
|
||||||
uint8_t safeCtrlStrategy(const bool magFieldValid, const bool mekfValid,
|
acs::SafeModeStrategy safeCtrlStrategy(const bool magFieldValid, const bool mekfValid,
|
||||||
const bool satRotRateValid, const bool sunDirValid,
|
const bool satRotRateValid, const bool sunDirValid,
|
||||||
const uint8_t mekfEnabled, const uint8_t dampingEnabled);
|
const uint8_t mekfEnabled, const uint8_t dampingEnabled);
|
||||||
|
|
||||||
|
@ -49,6 +49,7 @@
|
|||||||
#include "mission/system/acs/acsModeTree.h"
|
#include "mission/system/acs/acsModeTree.h"
|
||||||
#include "mission/system/tcs/tcsModeTree.h"
|
#include "mission/system/tcs/tcsModeTree.h"
|
||||||
#include "mission/tcs/defs.h"
|
#include "mission/tcs/defs.h"
|
||||||
|
#include "mission/tmtc/Service15TmStorage.h"
|
||||||
#include "mission/tmtc/tmFilters.h"
|
#include "mission/tmtc/tmFilters.h"
|
||||||
#include "objects/systemObjectList.h"
|
#include "objects/systemObjectList.h"
|
||||||
#include "tmtc/pusIds.h"
|
#include "tmtc/pusIds.h"
|
||||||
@ -58,15 +59,13 @@ using persTmStore::PersistentTmStores;
|
|||||||
#if OBSW_ADD_TCPIP_SERVERS == 1
|
#if OBSW_ADD_TCPIP_SERVERS == 1
|
||||||
#if OBSW_ADD_TMTC_UDP_SERVER == 1
|
#if OBSW_ADD_TMTC_UDP_SERVER == 1
|
||||||
// UDP server includes
|
// UDP server includes
|
||||||
#include "devices/gpioIds.h"
|
#include <fsfw/osal/common/UdpTcPollingTask.h>
|
||||||
#include "fsfw/osal/common/UdpTcPollingTask.h"
|
#include <fsfw/osal/common/UdpTmTcBridge.h>
|
||||||
#include "fsfw/osal/common/UdpTmTcBridge.h"
|
|
||||||
#endif
|
#endif
|
||||||
#if OBSW_ADD_TMTC_TCP_SERVER == 1
|
#if OBSW_ADD_TMTC_TCP_SERVER == 1
|
||||||
// TCP server includes
|
// TCP server includes
|
||||||
#include "fsfw/osal/common/TcpTmTcBridge.h"
|
#include <fsfw/osal/common/TcpTmTcBridge.h>
|
||||||
#include "fsfw/osal/common/TcpTmTcServer.h"
|
#include <fsfw/osal/common/TcpTmTcServer.h>
|
||||||
#include "mission/tmtc/Service15TmStorage.h"
|
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@ -234,7 +233,8 @@ void ObjectFactory::produceGenericObjects(HealthTableIF** healthTable_, PusTmFun
|
|||||||
|
|
||||||
// PUS service stack
|
// PUS service stack
|
||||||
new Service1TelecommandVerification(objects::PUS_SERVICE_1_VERIFICATION, config::EIVE_PUS_APID,
|
new Service1TelecommandVerification(objects::PUS_SERVICE_1_VERIFICATION, config::EIVE_PUS_APID,
|
||||||
pus::PUS_SERVICE_1, objects::PUS_TM_FUNNEL, 40);
|
pus::PUS_SERVICE_1, objects::PUS_TM_FUNNEL,
|
||||||
|
config::VERIFICATION_SERVICE_QUEUE_DEPTH);
|
||||||
new Service2DeviceAccess(objects::PUS_SERVICE_2_DEVICE_ACCESS, config::EIVE_PUS_APID,
|
new Service2DeviceAccess(objects::PUS_SERVICE_2_DEVICE_ACCESS, config::EIVE_PUS_APID,
|
||||||
pus::PUS_SERVICE_2, 3, 10);
|
pus::PUS_SERVICE_2, 3, 10);
|
||||||
new Service3Housekeeping(objects::PUS_SERVICE_3_HOUSEKEEPING, config::EIVE_PUS_APID,
|
new Service3Housekeeping(objects::PUS_SERVICE_3_HOUSEKEEPING, config::EIVE_PUS_APID,
|
||||||
@ -243,7 +243,7 @@ void ObjectFactory::produceGenericObjects(HealthTableIF** healthTable_, PusTmFun
|
|||||||
PsbParams(objects::PUS_SERVICE_5_EVENT_REPORTING, config::EIVE_PUS_APID, pus::PUS_SERVICE_5),
|
PsbParams(objects::PUS_SERVICE_5_EVENT_REPORTING, config::EIVE_PUS_APID, pus::PUS_SERVICE_5),
|
||||||
80, 160);
|
80, 160);
|
||||||
new Service8FunctionManagement(objects::PUS_SERVICE_8_FUNCTION_MGMT, config::EIVE_PUS_APID,
|
new Service8FunctionManagement(objects::PUS_SERVICE_8_FUNCTION_MGMT, config::EIVE_PUS_APID,
|
||||||
pus::PUS_SERVICE_8, 16, 60);
|
pus::PUS_SERVICE_8, config::ACTION_SERVICE_QUEUE_DEPTH, 16, 60);
|
||||||
new Service9TimeManagement(
|
new Service9TimeManagement(
|
||||||
PsbParams(objects::PUS_SERVICE_9_TIME_MGMT, config::EIVE_PUS_APID, pus::PUS_SERVICE_9));
|
PsbParams(objects::PUS_SERVICE_9_TIME_MGMT, config::EIVE_PUS_APID, pus::PUS_SERVICE_9));
|
||||||
|
|
||||||
|
@ -595,8 +595,8 @@ ReturnValue_t GomspaceDeviceHandler::parsePduHkTable(PDU::PduCoreHk& coreHk, PDU
|
|||||||
for (uint8_t idx = 0; idx < PDU::CHANNELS_LEN; idx++) {
|
for (uint8_t idx = 0; idx < PDU::CHANNELS_LEN; idx++) {
|
||||||
coreHk.voltages[idx] = as<uint16_t>(packet + 0x12 + (idx * 2));
|
coreHk.voltages[idx] = as<uint16_t>(packet + 0x12 + (idx * 2));
|
||||||
}
|
}
|
||||||
auxHk.vcc.value = as<int16_t>(packet + 0x24);
|
coreHk.vcc.value = as<int16_t>(packet + 0x24);
|
||||||
meggert marked this conversation as resolved
meggert
commented
is the MIB prepared for this? is the MIB prepared for this?
muellerr
commented
v2.0.0-dev is being prepared for this v2.0.0-dev is being prepared for this
|
|||||||
auxHk.vbat.value = as<int16_t>(packet + 0x26);
|
coreHk.vbat.value = as<int16_t>(packet + 0x26);
|
||||||
coreHk.temperature = as<int16_t>(packet + 0x28) * 0.1;
|
coreHk.temperature = as<int16_t>(packet + 0x28) * 0.1;
|
||||||
|
|
||||||
for (uint8_t idx = 0; idx < 3; idx++) {
|
for (uint8_t idx = 0; idx < 3; idx++) {
|
||||||
|
@ -404,6 +404,11 @@ class PduCoreHk : public StaticLocalDataSet<9> {
|
|||||||
/** Battery mode: 1 = Critical, 2 = Safe, 3 = Normal, 4 = Full */
|
/** Battery mode: 1 = Critical, 2 = Safe, 3 = Normal, 4 = Full */
|
||||||
lp_var_t<uint8_t> battMode = lp_var_t<uint8_t>(sid.objectId, pool::PDU_BATT_MODE, this);
|
lp_var_t<uint8_t> battMode = lp_var_t<uint8_t>(sid.objectId, pool::PDU_BATT_MODE, this);
|
||||||
lp_var_t<float> temperature = lp_var_t<float>(sid.objectId, pool::PDU_TEMPERATURE, this);
|
lp_var_t<float> temperature = lp_var_t<float>(sid.objectId, pool::PDU_TEMPERATURE, this);
|
||||||
|
|
||||||
|
/** Measured VCC */
|
||||||
|
lp_var_t<int16_t> vcc = lp_var_t<int16_t>(sid.objectId, pool::PDU_VCC, this);
|
||||||
|
/** Measured VBAT */
|
||||||
|
lp_var_t<int16_t> vbat = lp_var_t<int16_t>(sid.objectId, pool::PDU_VBAT, this);
|
||||||
};
|
};
|
||||||
|
|
||||||
class PduConfig : public StaticLocalDataSet<32> {
|
class PduConfig : public StaticLocalDataSet<32> {
|
||||||
@ -451,11 +456,6 @@ class PduAuxHk : public StaticLocalDataSet<36> {
|
|||||||
|
|
||||||
PduAuxHk(object_id_t objectId, uint32_t setId) : StaticLocalDataSet(sid_t(objectId, setId)) {}
|
PduAuxHk(object_id_t objectId, uint32_t setId) : StaticLocalDataSet(sid_t(objectId, setId)) {}
|
||||||
|
|
||||||
/** Measured VCC */
|
|
||||||
lp_var_t<int16_t> vcc = lp_var_t<int16_t>(sid.objectId, pool::PDU_VCC, this);
|
|
||||||
/** Measured VBAT */
|
|
||||||
lp_var_t<int16_t> vbat = lp_var_t<int16_t>(sid.objectId, pool::PDU_VBAT, this);
|
|
||||||
|
|
||||||
/** Output converter enable status */
|
/** Output converter enable status */
|
||||||
lp_vec_t<uint8_t, 3> converterEnable =
|
lp_vec_t<uint8_t, 3> converterEnable =
|
||||||
lp_vec_t<uint8_t, 3>(sid.objectId, pool::PDU_CONV_EN, this);
|
lp_vec_t<uint8_t, 3>(sid.objectId, pool::PDU_CONV_EN, this);
|
||||||
|
@ -268,6 +268,8 @@ void HeaterHandler::handleSwitchOnCommand(heater::Switch heaterIdx) {
|
|||||||
triggerEvent(GPIO_PULL_HIGH_FAILED, result);
|
triggerEvent(GPIO_PULL_HIGH_FAILED, result);
|
||||||
} else {
|
} else {
|
||||||
triggerEvent(HEATER_WENT_ON, heaterIdx, 0);
|
triggerEvent(HEATER_WENT_ON, heaterIdx, 0);
|
||||||
|
EventManagerIF::triggerEvent(helper.heaters[heaterIdx].first->getObjectId(), MODE_INFO,
|
||||||
|
MODE_ON, 0);
|
||||||
{
|
{
|
||||||
MutexGuard mg(handlerLock, LOCK_TYPE, LOCK_TIMEOUT, LOCK_CTX);
|
MutexGuard mg(handlerLock, LOCK_TYPE, LOCK_TIMEOUT, LOCK_CTX);
|
||||||
heater.switchState = ON;
|
heater.switchState = ON;
|
||||||
@ -324,6 +326,8 @@ void HeaterHandler::handleSwitchOffCommand(heater::Switch heaterIdx) {
|
|||||||
heater.switchState = OFF;
|
heater.switchState = OFF;
|
||||||
}
|
}
|
||||||
triggerEvent(HEATER_WENT_OFF, heaterIdx, 0);
|
triggerEvent(HEATER_WENT_OFF, heaterIdx, 0);
|
||||||
|
EventManagerIF::triggerEvent(helper.heaters[heaterIdx].first->getObjectId(), MODE_INFO,
|
||||||
|
MODE_OFF, 0);
|
||||||
// When all switches are off, also main line switch will be turned off
|
// When all switches are off, also main line switch will be turned off
|
||||||
if (allSwitchesOff()) {
|
if (allSwitchesOff()) {
|
||||||
mainLineSwitcher->sendSwitchCommand(mainLineSwitch, PowerSwitchIF::SWITCH_OFF);
|
mainLineSwitcher->sendSwitchCommand(mainLineSwitch, PowerSwitchIF::SWITCH_OFF);
|
||||||
|
@ -29,7 +29,7 @@ static const uint8_t MAX_REPLY_LENGTH = GET_TEMP_REPLY_SIZE;
|
|||||||
|
|
||||||
enum Tmp1075PoolIds : lp_id_t { TEMPERATURE_C_TMP1075 };
|
enum Tmp1075PoolIds : lp_id_t { TEMPERATURE_C_TMP1075 };
|
||||||
|
|
||||||
class Tmp1075Dataset : public StaticLocalDataSet<sizeof(float)> {
|
class Tmp1075Dataset : public StaticLocalDataSet<2> {
|
||||||
public:
|
public:
|
||||||
Tmp1075Dataset(HasLocalDataPoolIF* owner) : StaticLocalDataSet(owner, TMP1075_DATA_SET_ID) {}
|
Tmp1075Dataset(HasLocalDataPoolIF* owner) : StaticLocalDataSet(owner, TMP1075_DATA_SET_ID) {}
|
||||||
|
|
||||||
|
@ -256,6 +256,7 @@ ReturnValue_t PersistentTmStore::getNextDumpPacket(PusTmReader& reader, bool& fi
|
|||||||
if (state == State::IDLE or dumpParams.pendingPacketDump) {
|
if (state == State::IDLE or dumpParams.pendingPacketDump) {
|
||||||
return returnvalue::FAILED;
|
return returnvalue::FAILED;
|
||||||
}
|
}
|
||||||
|
fileHasSwapped = false;
|
||||||
reader.setReadOnlyData(fileBuf.data() + dumpParams.currentSize,
|
reader.setReadOnlyData(fileBuf.data() + dumpParams.currentSize,
|
||||||
fileBuf.size() - dumpParams.currentSize);
|
fileBuf.size() - dumpParams.currentSize);
|
||||||
// CRC check to fully ensure this is a valid TM
|
// CRC check to fully ensure this is a valid TM
|
||||||
@ -270,7 +271,6 @@ ReturnValue_t PersistentTmStore::getNextDumpPacket(PusTmReader& reader, bool& fi
|
|||||||
fileHasSwapped = true;
|
fileHasSwapped = true;
|
||||||
return loadNextDumpFile();
|
return loadNextDumpFile();
|
||||||
}
|
}
|
||||||
fileHasSwapped = false;
|
|
||||||
dumpParams.pendingPacketDump = true;
|
dumpParams.pendingPacketDump = true;
|
||||||
return returnvalue::OK;
|
return returnvalue::OK;
|
||||||
}
|
}
|
||||||
|
2
tmtc
2
tmtc
@ -1 +1 @@
|
|||||||
Subproject commit 5fbd19bb6cca0790373a809d78f2307adca9d0c8
|
Subproject commit 522f273c99845f9c50aaf135b1c6f52676b975dd
|
Loading…
Reference in New Issue
Block a user
lol