we really need to get rid of this overcomplicated crap
EIVE/eive-obsw/pipeline/head There was a failure building this commit Details

This commit is contained in:
Robin Müller 2024-04-11 13:12:42 +02:00
parent d60f4dd3e3
commit 13e752d9f8
Signed by: muellerr
GPG Key ID: A649FB78196E3849
13 changed files with 545 additions and 15 deletions

View File

@ -32,6 +32,7 @@ enum commonClassIds : uint8_t {
NVM_PARAM_BASE, // NVMB
FILE_SYSTEM_HELPER, // FSHLP
PLOC_MPSOC_HELPER, // PLMPHLP
PLOC_MPSOC_COM, // PLMPCOM
SA_DEPL_HANDLER, // SADPL
MPSOC_RETURN_VALUES_IF, // MPSOCRTVIF
SUPV_RETURN_VALUES_IF, // SPVRTVIF

2
fsfw

@ -1 +1 @@
Subproject commit 8b21dd276de72b46b41bc7080d6646180bfa0662
Subproject commit f307a86d9a972d29ee82234a415bf60a7ce4b6bc

View File

@ -2,6 +2,9 @@ target_sources(
${OBSW_NAME}
PUBLIC PlocMemoryDumper.cpp
PlocMpsocHandler.cpp
MpsocCommunication.cpp
SerialCommunicationHelper.cpp
FreshMpsocHandler.cpp
FreshSupvHandler.cpp
PlocMpsocSpecialComHelper.cpp
plocMpsocHelpers.cpp

View File

@ -0,0 +1,111 @@
#include "FreshMpsocHandler.h"
#include "fsfw/devicehandlers/FreshDeviceHandlerBase.h"
#include "fsfw/ipc/QueueFactory.h"
#include "fsfw/returnvalues/returnvalue.h"
#include "linux/payload/MpsocCommunication.h"
FreshMpsocHandler::FreshMpsocHandler(DhbConfig cfg, MpsocCommunication& comInterface,
PlocMpsocSpecialComHelper* plocMPSoCHelper,
Gpio uartIsolatorSwitch, object_id_t supervisorHandler)
: FreshDeviceHandlerBase(cfg), comInterface(comInterface) {
eventQueue = QueueFactory::instance()->createMessageQueue(10);
}
void FreshMpsocHandler::performDeviceOperation(uint8_t opCode) {
if (not transitionActive and mode == MODE_OFF) {
// Nothing to do for now.
return;
}
}
ReturnValue_t FreshMpsocHandler::handleCommandMessage(CommandMessage* message) {
return FreshDeviceHandlerBase::handleCommandMessage(message);
}
ReturnValue_t FreshMpsocHandler::initialize() {
ReturnValue_t result = FreshDeviceHandlerBase::initialize();
if (result != returnvalue::OK) {
return result;
}
EventManagerIF* manager = ObjectManager::instance()->get<EventManagerIF>(objects::EVENT_MANAGER);
if (manager == nullptr) {
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::error << "PlocMPSoCHandler::initialize: Invalid event manager" << std::endl;
#endif
return ObjectManagerIF::CHILD_INIT_FAILED;
;
}
result = manager->registerListener(eventQueue->getId());
if (result != returnvalue::OK) {
return result;
}
result = manager->subscribeToEvent(
eventQueue->getId(), event::getEventId(PlocMpsocSpecialComHelper::MPSOC_FLASH_WRITE_FAILED));
if (result != returnvalue::OK) {
return ObjectManagerIF::CHILD_INIT_FAILED;
}
result = manager->subscribeToEvent(
eventQueue->getId(),
event::getEventId(PlocMpsocSpecialComHelper::MPSOC_FLASH_WRITE_SUCCESSFUL));
if (result != returnvalue::OK) {
return ObjectManagerIF::CHILD_INIT_FAILED;
}
result = manager->subscribeToEvent(
eventQueue->getId(),
event::getEventId(PlocMpsocSpecialComHelper::MPSOC_FLASH_READ_SUCCESSFUL));
if (result != returnvalue::OK) {
return ObjectManagerIF::CHILD_INIT_FAILED;
}
result = manager->subscribeToEvent(
eventQueue->getId(), event::getEventId(PlocMpsocSpecialComHelper::MPSOC_FLASH_READ_FAILED));
if (result != returnvalue::OK) {
return ObjectManagerIF::CHILD_INIT_FAILED;
}
result = specialComHelper->setComIF(communicationInterface);
if (result != returnvalue::OK) {
return ObjectManagerIF::CHILD_INIT_FAILED;
}
specialComHelper->setComCookie(comCookie);
specialComHelper->setSequenceCount(&sequenceCount);
result = commandActionHelper.initialize();
if (result != returnvalue::OK) {
return ObjectManagerIF::CHILD_INIT_FAILED;
}
return result;
}
// HK manager abstract functions.
LocalPoolDataSetBase* FreshMpsocHandler::getDataSetHandle(sid_t sid) {}
ReturnValue_t FreshMpsocHandler::initializeLocalDataPool(localpool::DataPool& localDataPoolMap,
LocalDataPoolManager& poolManager) {
return returnvalue::OK;
}
// Mode abstract functions
ReturnValue_t FreshMpsocHandler::checkModeCommand(Mode_t mode, Submode_t submode,
uint32_t* msToReachTheMode) {
return returnvalue::OK;
}
// Action override. Forward to user.
ReturnValue_t FreshMpsocHandler::executeAction(ActionId_t actionId, MessageQueueId_t commandedBy,
const uint8_t* data, size_t size) {
return returnvalue::OK;
}
/**
* @overload
* @param submode
*/
void FreshMpsocHandler::startTransition(Mode_t newMode, Submode_t submode) {}
ReturnValue_t FreshMpsocHandler::performDeviceOperationPreQueueHandling(uint8_t opCode) {
return returnvalue::OK;
}
void FreshMpsocHandler::handleTransitionToOn() {}
void FreshMpsocHandler::handleTransitionToOff() {}

View File

@ -0,0 +1,54 @@
#include "fsfw/devicehandlers/FreshDeviceHandlerBase.h"
#include "fsfw/objectmanager/SystemObjectIF.h"
#include "fsfw_hal/linux/gpio/Gpio.h"
#include "linux/payload/MpsocCommunication.h"
#include "linux/payload/PlocMpsocSpecialComHelper.h"
class FreshMpsocHandler : public FreshDeviceHandlerBase {
public:
FreshMpsocHandler(DhbConfig cfg, MpsocCommunication& comInterface,
PlocMpsocSpecialComHelper* plocMPSoCHelper, Gpio uartIsolatorSwitch,
object_id_t supervisorHandler);
/**
* Periodic helper executed function, implemented by child class.
*/
void performDeviceOperation(uint8_t opCode) override;
/**
* Implemented by child class. Handle all command messages which are
* not health, mode, action or housekeeping messages.
* @param message
* @return
*/
ReturnValue_t handleCommandMessage(CommandMessage* message) override;
ReturnValue_t initialize() override;
private:
// HK manager abstract functions.
LocalPoolDataSetBase* getDataSetHandle(sid_t sid) override;
ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap,
LocalDataPoolManager& poolManager) override;
// Mode abstract functions
ReturnValue_t checkModeCommand(Mode_t mode, Submode_t submode,
uint32_t* msToReachTheMode) override;
// Action override. Forward to user.
ReturnValue_t executeAction(ActionId_t actionId, MessageQueueId_t commandedBy,
const uint8_t* data, size_t size) override;
/**
* @overload
* @param submode
*/
void startTransition(Mode_t newMode, Submode_t submode) override;
ReturnValue_t performDeviceOperationPreQueueHandling(uint8_t opCode) override;
void handleTransitionToOn();
void handleTransitionToOff();
bool transitionActive = false;
MpsocCommunication comInterface;
MessageQueueIF* eventQueue = nullptr;
};

View File

@ -0,0 +1,61 @@
#include "MpsocCommunication.h"
#include "fsfw/globalfunctions/CRC.h"
#include "fsfw/returnvalues/returnvalue.h"
#include "fsfw/tmtcpacket/ccsds/SpacePacketReader.h"
#include "fsfw/tmtcpacket/ccsds/header.h"
#include "unistd.h"
MpsocCommunication::MpsocCommunication(object_id_t objectId, SerialConfig cfg)
: SystemObject(objectId), readRingBuf(4096, true), helper(cfg) {}
ReturnValue_t MpsocCommunication::initialize() { return helper.initialize(); }
ReturnValue_t MpsocCommunication::send(const uint8_t* data, size_t dataLen) {
return helper.send(data, dataLen);
}
ReturnValue_t MpsocCommunication::parseAndRetrieveNextPacket() {
// We do not have a data link layer, so this whole thing is a mess in any case..
// But basically, we try to parse space packets from the internal ring buffer and trasnfer
// them to the higher level device handler. The CRC check is performed here as well, with
// few other ways to detect if we even have a valid packet.
size_t availableReadData = readRingBuf.getAvailableReadData();
// Minimum valid size for a space packet header.
if (availableReadData < ccsds::HEADER_LEN + 1) {
return returnvalue::OK;
}
readRingBuf.readData(readBuf, availableReadData);
spReader.setReadOnlyData(readBuf, availableReadData);
auto res = spReader.checkSize();
if (res != returnvalue::OK) {
return res;
}
// The packet might be garbage, with no way to recover without a data link layer.
if (spReader.getFullPacketLen() > 4096) {
readRingBuf.clear();
// TODO: Maybe we should also clear the serial input buffer in Linux?
return FAULTY_PACKET_SIZE;
}
if (availableReadData < spReader.getFullPacketLen()) {
// Might be split packet where the rest still has to be read.
return returnvalue::OK;
}
if (CRC::crc16ccitt(readBuf, availableReadData) != 0) {
// Possibly invalid packet. We can not even trust the detected packet length.
// Just clear the whole read buffer as well.
readRingBuf.clear();
}
readRingBuf.deleteData(spReader.getFullPacketLen());
return PACKET_RECEIVED;
}
ReturnValue_t MpsocCommunication::readSerialInterface() {
int bytesRead = read(helper.rawFd(), readBuf, sizeof(readBuf));
if (bytesRead < 0) {
return returnvalue::FAILED;
}
return readRingBuf.writeData(readBuf, bytesRead);
}
const SpacePacketReader& MpsocCommunication::getSpReader() const { return spReader; }

View File

@ -0,0 +1,38 @@
#pragma once
#include <fsfw/objectmanager/SystemObject.h>
#include "eive/resultClassIds.h"
#include "fsfw/container/SimpleRingBuffer.h"
#include "fsfw/returnvalues/returnvalue.h"
#include "fsfw/tmtcpacket/ccsds/SpacePacketReader.h"
#include "linux/payload/SerialCommunicationHelper.h"
class MpsocCommunication : public SystemObject {
public:
static const uint8_t CLASS_ID = CLASS_ID::PLOC_MPSOC_COM;
static constexpr ReturnValue_t PACKET_RECEIVED = returnvalue::makeCode(CLASS_ID, 0);
static constexpr ReturnValue_t FAULTY_PACKET_SIZE = returnvalue::makeCode(CLASS_ID, 1);
MpsocCommunication(object_id_t objectId, SerialCookie cfg);
ReturnValue_t initialize() override;
ReturnValue_t send(const uint8_t* data, size_t dataLen);
// Should be called periodically to transfer the received data from the MPSoC from the Linux
// buffer to the internal ring buffer for further processing.
ReturnValue_t readSerialInterface();
// Parses the internal ring buffer for packets and checks whether a packet was received.
ReturnValue_t parseAndRetrieveNextPacket();
// Can be used to read the parse packet, if one was received.
const SpacePacketReader& getSpReader() const;
private:
SpacePacketReader spReader;
uint8_t readBuf[4096];
SimpleRingBuffer readRingBuf;
SerialCommunicationHelper helper;
};

View File

@ -17,7 +17,7 @@
#include "fsfw_hal/linux/gpio/Gpio.h"
#include "fsfw_hal/linux/serial/SerialComIF.h"
static constexpr bool DEBUG_MPSOC_COMMUNICATION = false;
static constexpr bool DEBUG_MPSOC_COMMUNICATION = true;
/**
* @brief This is the device handler for the MPSoC of the payload computer.
@ -186,7 +186,7 @@ class PlocMpsocHandler : public DeviceHandlerBase, public CommandsActionsIF {
};
TmMemReadReport tmMemReadReport;
Countdown cmdCountdown = Countdown(10000);
Countdown cmdCountdown = Countdown(15000);
struct TelemetryBuffer {
uint16_t length = 0;

View File

@ -6,6 +6,8 @@
#include <filesystem>
#include <fstream>
#include "linux/payload/MpsocCommunication.h"
#ifdef XIPHOS_Q7S
#include "bsp_q7s/fs/FilesystemHelper.h"
#endif
@ -23,8 +25,7 @@ PlocMpsocSpecialComHelper::PlocMpsocSpecialComHelper(object_id_t objectId)
PlocMpsocSpecialComHelper::~PlocMpsocSpecialComHelper() {}
ReturnValue_t PlocMpsocSpecialComHelper::initialize() {
#ifdef XIPHOS_Q7S
sdcMan = SdCardManager::instance();
#ifdef XIPHOS_Q7S sdcMan = SdCardManager::instance();
if (sdcMan == nullptr) {
sif::warning << "PlocMPSoCHelper::initialize: Invalid SD Card Manager" << std::endl;
return returnvalue::FAILED;
@ -72,17 +73,11 @@ ReturnValue_t PlocMpsocSpecialComHelper::performOperation(uint8_t operationCode)
}
}
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;
}
ReturnValue_t PlocMpsocSpecialComHelper::setComIF(MpsocCommunication& communication) {
comInterface = communication;
return returnvalue::OK;
}
void PlocMpsocSpecialComHelper::setComCookie(CookieIF* comCookie_) { comCookie = comCookie_; }
void PlocMpsocSpecialComHelper::setSequenceCount(SourceSequenceCounter* sequenceCount_) {
sequenceCount = sequenceCount_;
}

View File

@ -14,6 +14,7 @@
#include "fsfw/tasks/ExecutableObjectIF.h"
#include "fsfw/tmtcservices/SourceSequenceCounter.h"
#include "fsfw_hal/linux/serial/SerialComIF.h"
#include "linux/payload/MpsocCommunication.h"
#ifdef XIPHOS_Q7S
#include "bsp_q7s/fs/SdCardManager.h"
#endif
@ -169,9 +170,10 @@ class PlocMpsocSpecialComHelper : public SystemObject, public ExecutableObjectIF
* Communication interface of MPSoC responsible for low level access. Must be set by the
* MPSoC Handler.
*/
SerialComIF* uartComIF = nullptr;
// SerialComIF* uartComIF = nullptr;
// Communication cookie. Must be set by the MPSoC Handler
CookieIF* comCookie = nullptr;
// CookieIF* comCookie = nullptr;
MpsocCommunication& comInterface;
// Sequence count, must be set by Ploc MPSoC Handler
SourceSequenceCounter* sequenceCount = nullptr;
ploc::SpTmReader spReader;

View File

@ -0,0 +1,126 @@
#include "SerialCommunicationHelper.h"
#include <errno.h>
#include <fcntl.h>
#include <termios.h>
#include <unistd.h>
#include <cstring>
#include "fsfw/returnvalues/returnvalue.h"
#include "fsfw_hal/linux/serial/helper.h"
SerialCommunicationHelper::SerialCommunicationHelper(SerialConfig cfg) : cfg(cfg) {}
ReturnValue_t SerialCommunicationHelper::initialize() {
fd = configureUartPort();
if (fd < 0) {
return returnvalue::FAILED;
}
return returnvalue::OK;
}
int SerialCommunicationHelper::rawFd() const { return fd; }
ReturnValue_t SerialCommunicationHelper::send(const uint8_t* data, size_t dataLen) {
if (write(fd, data, dataLen) != static_cast<int>(dataLen)) {
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::error << "UartComIF::sendMessage: Failed to send data with error code " << errno
<< ": Error description: " << strerror(errno) << std::endl;
#endif
return returnvalue::FAILED;
}
return returnvalue::OK;
}
int SerialCommunicationHelper::configureUartPort() {
struct termios options = {};
int flags = O_RDWR;
if (cfg.getUartMode() == UartModes::CANONICAL) {
// In non-canonical mode, don't specify O_NONBLOCK because these properties will be
// controlled by the VTIME and VMIN parameters and O_NONBLOCK would override this
flags |= O_NONBLOCK;
}
int fd = open(cfg.getDeviceFile().c_str(), flags);
if (fd < 0) {
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::warning << "UartComIF::configureUartPort: Failed to open uart "
<< cfg.getDeviceFile().c_str()
<< "with error code " << errno << strerror(errno) << std::endl;
#endif
return fd;
}
/* Read in existing settings */
if (tcgetattr(fd, &options) != 0) {
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::warning << "UartComIF::configureUartPort: Error " << errno
<< "from tcgetattr: " << strerror(errno) << std::endl;
#endif
return fd;
}
serial::setParity(options, cfg.getParity());
serial::setStopbits(options, cfg.getStopBits());
serial::setBitsPerWord(options, cfg.getBitsPerWord());
setFixedOptions(&options);
serial::setMode(options, cfg.getUartMode());
tcflush(fd, TCIFLUSH);
/* Sets uart to non-blocking mode. Read returns immediately when there are no data available */
options.c_cc[VTIME] = 0;
options.c_cc[VMIN] = 0;
serial::setBaudrate(options, cfg.getBaudrate());
/* Save option settings */
if (tcsetattr(fd, TCSANOW, &options) != 0) {
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::warning << "UartComIF::configureUartPort: Failed to set options with error " << errno
<< ": " << strerror(errno);
#endif
return fd;
}
return fd;
}
void SerialCommunicationHelper::setFixedOptions(struct termios* options) {
/* Disable RTS/CTS hardware flow control */
options->c_cflag &= ~CRTSCTS;
/* Turn on READ & ignore ctrl lines (CLOCAL = 1) */
options->c_cflag |= CREAD | CLOCAL;
/* Disable echo */
options->c_lflag &= ~ECHO;
/* Disable erasure */
options->c_lflag &= ~ECHOE;
/* Disable new-line echo */
options->c_lflag &= ~ECHONL;
/* Disable interpretation of INTR, QUIT and SUSP */
options->c_lflag &= ~ISIG;
/* Turn off s/w flow ctrl */
options->c_iflag &= ~(IXON | IXOFF | IXANY);
/* Disable any special handling of received bytes */
options->c_iflag &= ~(IGNBRK | BRKINT | PARMRK | ISTRIP | INLCR | IGNCR | ICRNL);
/* Prevent special interpretation of output bytes (e.g. newline chars) */
options->c_oflag &= ~OPOST;
/* Prevent conversion of newline to carriage return/line feed */
options->c_oflag &= ~ONLCR;
}
ReturnValue_t SerialCommunicationHelper::flushUartRxBuffer() {
serial::flushRxBuf(fd);
return returnvalue::OK;
}
ReturnValue_t SerialCommunicationHelper::flushUartTxBuffer() {
serial::flushTxBuf(fd);
return returnvalue::OK;
}
ReturnValue_t SerialCommunicationHelper::flushUartTxAndRxBuf() {
serial::flushTxRxBuf(fd);
return returnvalue::OK;
}

View File

@ -0,0 +1,69 @@
#pragma once
#include <fsfw/devicehandlers/DeviceCommunicationIF.h>
#include <fsfw/objectmanager/SystemObject.h>
#include <fsfw_hal/linux/serial/SerialCookie.h>
#include <fsfw_hal/linux/serial/helper.h>
#include "SerialConfig.h"
#include "fsfw/returnvalues/returnvalue.h"
/**
* @brief This is the communication interface to access serial ports on linux based operating
* systems.
*
* @details The implementation follows the instructions from https://blog.mbedded.ninja/programming/
* operating-systems/linux/linux-serial-ports-using-c-cpp/#disabling-canonical-mode
*
* @author J. Meier
*/
class SerialCommunicationHelper {
public:
SerialCommunicationHelper(SerialCookie serialCfg);
ReturnValue_t send(const uint8_t* data, size_t dataLen);
int rawFd() const;
ReturnValue_t initialize();
/**
* @brief This function discards all data received but not read in the UART buffer.
*/
ReturnValue_t flushUartRxBuffer();
/**
* @brief This function discards all data in the transmit buffer of the UART driver.
*/
ReturnValue_t flushUartTxBuffer();
/**
* @brief This function discards both data in the transmit and receive buffer of the UART.
*/
ReturnValue_t flushUartTxAndRxBuf();
private:
SerialCookie cfg;
int fd = 0;
/**
* @brief This function opens and configures a uart device by using the information stored
* in the uart cookie.
* @param uartCookie Pointer to uart cookie with information about the uart. Contains the
* uart device file, baudrate, parity, stopbits etc.
* @return The file descriptor of the configured uart.
*/
int configureUartPort();
void setStopBitOptions(struct termios* options);
/**
* @brief This function sets options which are not configurable by the uartCookie.
*/
void setFixedOptions(struct termios* options);
/**
* @brief With this function the datasize settings are added to the termios options struct.
*/
void setDatasizeOptions(struct termios* options);
};

View File

@ -0,0 +1,70 @@
#pragma once
#include <fsfw/devicehandlers/CookieIF.h>
#include <fsfw/objectmanager/SystemObjectIF.h>
#include <fsfw_hal/linux/serial/helper.h>
#include <string>
/**
* @brief Cookie for the UartComIF. There are many options available to configure the UART driver.
* The constructor only requests for common options like the baudrate. Other options can
* be set by member functions.
*
* @author J. Meier
*/
class SerialConfig : public CookieIF {
public:
/**
* @brief Constructor for the uart cookie.
* @param deviceFile The device file specifying the uart to use, e.g. "/dev/ttyPS1"
* @param uartMode Specify the UART mode. The canonical mode should be used if the
* messages are separated by a delimited character like '\n'. See the
* termios documentation for more information
* @param baudrate The baudrate to use for input and output.
* @param maxReplyLen The maximum size an object using this cookie expects
* @details
* Default configuration: No parity
* 8 databits (number of bits transfered with one uart frame)
* One stop bit
*/
SerialConfig(std::string deviceFile, UartBaudRate baudrate, size_t maxReplyLen,
UartModes uartMode = UartModes::NON_CANONICAL);
virtual ~SerialConfig();
UartBaudRate getBaudrate() const { return baudrate; }
size_t getMaxReplyLen() const { return maxReplyLen; }
std::string getDeviceFile() const { return deviceFile; }
Parity getParity() const { return parity; }
BitsPerWord getBitsPerWord() const { return bitsPerWord; }
StopBits getStopBits() const { return stopBits; }
UartModes getUartMode() const { return uartMode; }
/**
* Functions two enable parity checking.
*/
void setParityOdd() { parity = Parity::ODD; }
void setParityEven() { parity = Parity::EVEN; }
/**
* Function two set number of bits per UART frame.
*/
void setBitsPerWord(BitsPerWord bitsPerWord_) { bitsPerWord = bitsPerWord_; }
/**
* Function to specify the number of stopbits.
*/
void setTwoStopBits() { stopBits = StopBits::TWO_STOP_BITS; }
void setOneStopBit() { stopBits = StopBits::ONE_STOP_BIT; }
private:
const object_id_t handlerId;
std::string deviceFile;
const UartModes uartMode;
UartBaudRate baudrate;
size_t maxReplyLen = 0;
Parity parity = Parity::NONE;
BitsPerWord bitsPerWord = BitsPerWord::BITS_8;
StopBits stopBits = StopBits::ONE_STOP_BIT;
};