From 2fd33bed7fcd880ca3915e5f3cfa444a482e2b70 Mon Sep 17 00:00:00 2001 From: "Jakob.Meier" Date: Wed, 17 Feb 2021 15:54:48 +0100 Subject: [PATCH 01/79] syrlinks handler wip --- libcsp/src/drivers/can/can_socketcan.c | 6 + linux/csp/CspComIF.cpp | 2 +- linux/csp/CspComIF.h | 2 +- mission/devices/PDU1Handler.cpp | 2 +- .../devices/SolarArrayDeploymentHandler.cpp | 7 +- mission/devices/SolarArrayDeploymentHandler.h | 3 +- mission/devices/SyrlinksHkHandler.cpp | 145 ++++++++++++++++++ mission/devices/SyrlinksHkHandler.h | 65 ++++++++ 8 files changed, 223 insertions(+), 9 deletions(-) create mode 100644 mission/devices/SyrlinksHkHandler.cpp create mode 100644 mission/devices/SyrlinksHkHandler.h diff --git a/libcsp/src/drivers/can/can_socketcan.c b/libcsp/src/drivers/can/can_socketcan.c index 94c6bdde..d6d6b9e1 100644 --- a/libcsp/src/drivers/can/can_socketcan.c +++ b/libcsp/src/drivers/can/can_socketcan.c @@ -95,6 +95,12 @@ static void * socketcan_rx_thread(void * parameters) /* Strip flags */ frame.can_id &= CAN_EFF_MASK; + printf("socketcan_rx_thread: CAN bytes received: "); + /* Print received data */ + for (int i = 0; i < 8; i++) { + printf("%x, ", frame.data[i]); + } + /* Call RX callbacsp_can_rx_frameck */ csp_can_rx(&socketcan[0].interface, frame.can_id, frame.data, frame.can_dlc, NULL); } diff --git a/linux/csp/CspComIF.cpp b/linux/csp/CspComIF.cpp index bfe7e7e9..1798b152 100644 --- a/linux/csp/CspComIF.cpp +++ b/linux/csp/CspComIF.cpp @@ -28,7 +28,7 @@ ReturnValue_t CspComIF::initializeInterface(CookieIF *cookie) { int buf_count = 10; int buf_size = 300; /* Init CSP and CSP buffer system */ - if (csp_init(cspClientAddress) != CSP_ERR_NONE + if (csp_init(cspOwnAddress) != CSP_ERR_NONE || csp_buffer_init(buf_count, buf_size) != CSP_ERR_NONE) { sif::error << "Failed to init CSP\r\n" << std::endl; return HasReturnvaluesIF::RETURN_FAILED; diff --git a/linux/csp/CspComIF.h b/linux/csp/CspComIF.h index 78f5158f..4855fbf8 100644 --- a/linux/csp/CspComIF.h +++ b/linux/csp/CspComIF.h @@ -65,7 +65,7 @@ private: uint16_t replySize = 0; /* This is the CSP address of the OBC. */ - node_t cspClientAddress = 1; + node_t cspOwnAddress = 1; /* Interface struct for csp protocol stack */ csp_iface_t csp_if; diff --git a/mission/devices/PDU1Handler.cpp b/mission/devices/PDU1Handler.cpp index 92281f49..559ce94d 100644 --- a/mission/devices/PDU1Handler.cpp +++ b/mission/devices/PDU1Handler.cpp @@ -20,7 +20,7 @@ ReturnValue_t PDU1Handler::buildNormalDeviceCommand( void PDU1Handler::letChildHandleHkReply(DeviceCommandId_t id, const uint8_t *packet) { parseHkTableReply(packet); -// handleDeviceTM(&pdu1HkTableDataset, id, true); + handleDeviceTM(&pdu1HkTableDataset, id, true); #if OBSW_VERBOSE_LEVEL >= 1 && PDU1_DEBUG == 1 pdu1HkTableDataset.read(); diff --git a/mission/devices/SolarArrayDeploymentHandler.cpp b/mission/devices/SolarArrayDeploymentHandler.cpp index 9c0ebed4..45521800 100644 --- a/mission/devices/SolarArrayDeploymentHandler.cpp +++ b/mission/devices/SolarArrayDeploymentHandler.cpp @@ -84,14 +84,13 @@ void SolarArrayDeploymentHandler::handleStateMachine() { break; case WAIT_FOR_MAIN_SWITCH_OFF: if (mainLineSwitcher->getSwitchState(mainLineSwitch) == PowerSwitchIF::SWITCH_OFF) { - stateMachine = FINISHED_DEPLOYMENT; + stateMachine = WAIT_ON_DELOYMENT_COMMAND; } else if (mainSwitchCountdown.hasTimedOut()) { triggerEvent(MAIN_SWITCH_OFF_TIMEOUT); - stateMachine = FINISHED_DEPLOYMENT; sif::error << "SolarArrayDeploymentHandler::handleStateMachine: Failed to switch main" << " switch off" << std::endl; + stateMachine = WAIT_ON_DELOYMENT_COMMAND; } - case FINISHED_DEPLOYMENT: break; default: sif::debug << "SolarArrayDeploymentHandler::handleStateMachine: Invalid state" << std::endl; @@ -143,7 +142,6 @@ void SolarArrayDeploymentHandler::switchDeploymentTransistors() { void SolarArrayDeploymentHandler::handleDeploymentFinish() { ReturnValue_t result = RETURN_OK; if (deploymentCountdown.hasTimedOut()) { - stateMachine = FINISHED_DEPLOYMENT; actionHelper.finish(rememberCommanderId, DEPLOY_SOLAR_ARRAYS, RETURN_OK); result = gpioInterface->pullLow(deplSA1); if (result != RETURN_OK) { @@ -157,6 +155,7 @@ void SolarArrayDeploymentHandler::handleDeploymentFinish() { } mainLineSwitcher->sendSwitchCommand(mainLineSwitch, PowerSwitchIF::SWITCH_OFF); mainSwitchCountdown.setTimeout(mainLineSwitcher->getSwitchDelayMs()); + stateMachine = WAIT_FOR_MAIN_SWITCH_OFF; } } diff --git a/mission/devices/SolarArrayDeploymentHandler.h b/mission/devices/SolarArrayDeploymentHandler.h index c45c2ba7..279ae5da 100644 --- a/mission/devices/SolarArrayDeploymentHandler.h +++ b/mission/devices/SolarArrayDeploymentHandler.h @@ -76,8 +76,7 @@ private: WAIT_ON_8V_SWITCH, SWITCH_DEPL_GPIOS, WAIT_ON_DEPLOYMENT_FINISH, - WAIT_FOR_MAIN_SWITCH_OFF, - FINISHED_DEPLOYMENT + WAIT_FOR_MAIN_SWITCH_OFF }; StateMachine stateMachine = WAIT_ON_DELOYMENT_COMMAND; diff --git a/mission/devices/SyrlinksHkHandler.cpp b/mission/devices/SyrlinksHkHandler.cpp new file mode 100644 index 00000000..68c202cd --- /dev/null +++ b/mission/devices/SyrlinksHkHandler.cpp @@ -0,0 +1,145 @@ +#include +#include +#include + +SyrlinksHkHandler::SyrlinksHkHandler(object_id_t objectId, object_id_t comIF, + CookieIF * comCookie) : + DeviceHandlerBase(objectId, comIF, comCookie), dataset( + this) { + if (comCookie == NULL) { + sif::error << "SyrlinksHkHandler: Invalid com cookie" << std::endl; + } +} + +SyrlinksHkHandler::~SyrlinksHkHandler() { +} + + +void SyrlinksHkHandler::doStartUp(){ + if(mode == _MODE_START_UP){ + setMode(MODE_ON); + } +} + +void SyrlinksHkHandler::doShutDown(){ + +} + +ReturnValue_t SyrlinksHkHandler::buildNormalDeviceCommand( + DeviceCommandId_t * id) { + + if(communicationStep == CommunicationStep::START_ADC_CONVERSION) { + *id = TMP1075::START_ADC_CONVERSION; + communicationStep = CommunicationStep::GET_TEMPERATURE; + return buildCommandFromCommand(*id, NULL, 0); + } + else { + *id = TMP1075::GET_TEMP; + communicationStep = CommunicationStep::START_ADC_CONVERSION; + return buildCommandFromCommand(*id, NULL, 0); + } + return HasReturnvaluesIF::RETURN_OK; +} + +ReturnValue_t SyrlinksHkHandler::buildTransitionDeviceCommand( + DeviceCommandId_t * id){ + return HasReturnvaluesIF::RETURN_OK; +} + +ReturnValue_t SyrlinksHkHandler::buildCommandFromCommand( + DeviceCommandId_t deviceCommand, const uint8_t * commandData, + size_t commandDataLen) { + switch(deviceCommand) { + case(TMP1075::START_ADC_CONVERSION): { + std::memset(cmdBuffer, 0, sizeof(cmdBuffer)); + prepareAdcConversionCommand(); + rawPacket = cmdBuffer; + rawPacketLen = TMP1075::CFGR_CMD_SIZE; + return RETURN_OK; + } + case(TMP1075::GET_TEMP): { + std::memset(cmdBuffer, 0, sizeof(cmdBuffer)); + prepareGetTempCommand(); + rawPacket = cmdBuffer; + rawPacketLen = TMP1075::POINTER_REG_SIZE; + rememberCommandId = TMP1075::GET_TEMP; + return RETURN_OK; + } + default: + return DeviceHandlerIF::COMMAND_NOT_IMPLEMENTED; + } + return HasReturnvaluesIF::RETURN_FAILED; +} + +void SyrlinksHkHandler::fillCommandAndReplyMap(){ + this->insertInCommandMap(TMP1075::START_ADC_CONVERSION); + this->insertInCommandAndReplyMap(TMP1075::GET_TEMP, 1, &dataset, + TMP1075::GET_TEMP_REPLY_SIZE); +} + +ReturnValue_t SyrlinksHkHandler::scanForReply(const uint8_t *start, + size_t remainingSize, DeviceCommandId_t *foundId, size_t *foundLen) { + switch(rememberCommandId) { + case(TMP1075::GET_TEMP): + *foundId = TMP1075::GET_TEMP; + *foundLen = TMP1075::GET_TEMP_REPLY_SIZE; + rememberCommandId = TMP1075::NONE; + break; + default: + return IGNORE_REPLY_DATA; + } + return HasReturnvaluesIF::RETURN_OK; +} + +ReturnValue_t SyrlinksHkHandler::interpretDeviceReply(DeviceCommandId_t id, + const uint8_t *packet) { + switch (id) { + case TMP1075::GET_TEMP: { + int16_t tempValueRaw = 0; + tempValueRaw = packet[0] << 4 | packet[1] >> 4; + float tempValue = ((static_cast(tempValueRaw)) * 0.0625); +#if OBSW_VERBOSE_LEVEL >= 1 + sif::info << "Tmp1075 with object id: 0x" << std::hex << getObjectId() + << ": Temperature: " << tempValue<< " °C" + << std::endl; +#endif + ReturnValue_t result = dataset.read(); + if(result == HasReturnvaluesIF::RETURN_OK) { + dataset.temperatureCelcius = tempValue; + dataset.commit(); + } + break; + } + + default: { + return DeviceHandlerIF::UNKNOWN_DEVICE_REPLY; + } + + } + return HasReturnvaluesIF::RETURN_OK; +} + +void SyrlinksHkHandler::setNormalDatapoolEntriesInvalid(){ + +} + +void SyrlinksHkHandler::prepareAdcConversionCommand(){ + cmdBuffer[0] = TMP1075::CFGR_ADDR; + cmdBuffer[1] = TMP1075::ONE_SHOT_MODE >> 8; + cmdBuffer[2] = TMP1075::ONE_SHOT_MODE & 0xFF; +} + +void SyrlinksHkHandler::prepareGetTempCommand(){ + cmdBuffer[0] = TMP1075::TEMP_REG_ADDR; +} + +uint32_t SyrlinksHkHandler::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo){ + return 500; +} + +ReturnValue_t SyrlinksHkHandler::initializeLocalDataPool(localpool::DataPool& localDataPoolMap, + LocalDataPoolManager& poolManager) { + localDataPoolMap.emplace(TMP1075::TEMPERATURE_C_TMP1075_1, new PoolEntry( { 0.0 })); + return HasReturnvaluesIF::RETURN_OK; +} + diff --git a/mission/devices/SyrlinksHkHandler.h b/mission/devices/SyrlinksHkHandler.h new file mode 100644 index 00000000..d2d80efa --- /dev/null +++ b/mission/devices/SyrlinksHkHandler.h @@ -0,0 +1,65 @@ +#ifndef MISSION_DEVICES_SYRLINKSHKHANDLER_H_ +#define MISSION_DEVICES_SYRLINKSHKHANDLER_H_ + +#include +#include + +/** + * @brief This is the device handler for the syrlinks transceiver. It handles the command + * transmission and reading of housekeeping data via the housekeeping interface. The + * transmission of telemetry and the reception of telecommands is handled by an additional + * class. + * + * @author J. Meier + */ +class SyrlinksHkHandler: public DeviceHandlerBase { +public: + + SyrlinksHkHandler(object_id_t objectId, object_id_t comIF, + CookieIF * comCookie); + virtual ~SyrlinksHkHandler(); + +protected: + void doStartUp() override; + void doShutDown() override; + ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t * id) override; + ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t * id) override; + void fillCommandAndReplyMap() override; + ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, + const uint8_t * commandData,size_t commandDataLen) override; + ReturnValue_t scanForReply(const uint8_t *start, size_t remainingSize, + DeviceCommandId_t *foundId, size_t *foundLen) override; + ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, + const uint8_t *packet) override; + void setNormalDatapoolEntriesInvalid() override; + uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override; + ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap, + LocalDataPoolManager& poolManager) override; + +private: + + /** + * @brief Function fills cmdBuffer with command to start the adc + * conversion for a new temperature value. + */ + void prepareAdcConversionCommand(); + + void prepareGetTempCommand(); + + enum class CommunicationStep { + START_ADC_CONVERSION, + GET_TEMPERATURE + }; + + TMP1075::Tmp1075Dataset dataset; + + static const uint8_t MAX_CMD_LEN = 3; + + uint8_t rememberRequestedSize = 0; + uint8_t rememberCommandId = TMP1075::NONE; + uint8_t cmdBuffer[MAX_CMD_LEN]; + CommunicationStep communicationStep = + CommunicationStep::START_ADC_CONVERSION; +}; + +#endif /* MISSION_DEVICES_SYRLINKSHKHANDLER_H_ */ From 89d0427437dabe4c5f7b14ecdc1dcb6c8d5f65c0 Mon Sep 17 00:00:00 2001 From: "Jakob.Meier" Date: Thu, 18 Feb 2021 16:16:38 +0100 Subject: [PATCH 02/79] syrlinks handler wip --- mission/devices/CMakeLists.txt | 1 + mission/devices/SyrlinksHkHandler.cpp | 54 ++++++++++--------- mission/devices/SyrlinksHkHandler.h | 25 ++++++++- .../devicedefinitions/SyrlinksDefinitions.h | 15 ++++++ 4 files changed, 68 insertions(+), 27 deletions(-) create mode 100644 mission/devices/devicedefinitions/SyrlinksDefinitions.h diff --git a/mission/devices/CMakeLists.txt b/mission/devices/CMakeLists.txt index 4f45a7e6..a5093a8c 100644 --- a/mission/devices/CMakeLists.txt +++ b/mission/devices/CMakeLists.txt @@ -12,6 +12,7 @@ target_sources(${TARGET_NAME} PUBLIC ACUHandler.cpp HeaterHandler.cpp SolarArrayDeploymentHandler.cpp + SyrlinksHkHandler.cpp ) diff --git a/mission/devices/SyrlinksHkHandler.cpp b/mission/devices/SyrlinksHkHandler.cpp index 68c202cd..cedb015f 100644 --- a/mission/devices/SyrlinksHkHandler.cpp +++ b/mission/devices/SyrlinksHkHandler.cpp @@ -1,5 +1,4 @@ #include -#include #include SyrlinksHkHandler::SyrlinksHkHandler(object_id_t objectId, object_id_t comIF, @@ -27,18 +26,8 @@ void SyrlinksHkHandler::doShutDown(){ ReturnValue_t SyrlinksHkHandler::buildNormalDeviceCommand( DeviceCommandId_t * id) { - - if(communicationStep == CommunicationStep::START_ADC_CONVERSION) { - *id = TMP1075::START_ADC_CONVERSION; - communicationStep = CommunicationStep::GET_TEMPERATURE; - return buildCommandFromCommand(*id, NULL, 0); - } - else { - *id = TMP1075::GET_TEMP; - communicationStep = CommunicationStep::START_ADC_CONVERSION; - return buildCommandFromCommand(*id, NULL, 0); - } - return HasReturnvaluesIF::RETURN_OK; + *id = READ_RX_STATUS_REGISTERS; + return buildCommandFromCommand(*id, NULL, 0); } ReturnValue_t SyrlinksHkHandler::buildTransitionDeviceCommand( @@ -50,19 +39,29 @@ ReturnValue_t SyrlinksHkHandler::buildCommandFromCommand( DeviceCommandId_t deviceCommand, const uint8_t * commandData, size_t commandDataLen) { switch(deviceCommand) { - case(TMP1075::START_ADC_CONVERSION): { - std::memset(cmdBuffer, 0, sizeof(cmdBuffer)); - prepareAdcConversionCommand(); - rawPacket = cmdBuffer; - rawPacketLen = TMP1075::CFGR_CMD_SIZE; + case(RESET_UNIT): { + resetCommand.copy(rawPacket, resetCommand.size(), 0); + rawPacketLen = resetCommand.size(); return RETURN_OK; } - case(TMP1075::GET_TEMP): { - std::memset(cmdBuffer, 0, sizeof(cmdBuffer)); - prepareGetTempCommand(); - rawPacket = cmdBuffer; - rawPacketLen = TMP1075::POINTER_REG_SIZE; - rememberCommandId = TMP1075::GET_TEMP; + case(SET_TX_MODE_STANDBY): { + setTxModeStandby.copy(rawPacket, setTxModeStandby.size(), 0); + rawPacketLen = setTxModeStandby.size(); + return RETURN_OK; + } + case(SET_TX_MODE_MODULATION): { + setTxModeModulation.copy(rawPacket, setTxModeModulation.size(), 0); + rawPacketLen = setTxModeModulation.size(); + return RETURN_OK; + } + case(SET_TX_MODE_CW): { + setTxModeCw.copy(rawPacket, setTxModeCw.size(), 0); + rawPacketLen = setTxModeCw.size(); + return RETURN_OK; + } + case(READ_RX_STATUS_REGISTERS): { + readRxStatusRegCommand.copy(rawPacket, readRxStatusRegCommand.size(), 0); + rawPacketLen = readRxStatusRegCommand.size(); return RETURN_OK; } default: @@ -72,8 +71,11 @@ ReturnValue_t SyrlinksHkHandler::buildCommandFromCommand( } void SyrlinksHkHandler::fillCommandAndReplyMap(){ - this->insertInCommandMap(TMP1075::START_ADC_CONVERSION); - this->insertInCommandAndReplyMap(TMP1075::GET_TEMP, 1, &dataset, + this->insertInCommandAndReplyMap(RESET_UNIT); + this->insertInCommandAndReplyMap(SET_TX_MODE_STANDBY); + this->insertInCommandAndReplyMap(SET_TX_MODE_MODULATION); + this->insertInCommandAndReplyMap(SET_TX_MODE_CW); + this->insertInCommandAndReplyMap(READ_RX_STATUS_REGISTERS, 1, &rxStatusRegiserSet, TMP1075::GET_TEMP_REPLY_SIZE); } diff --git a/mission/devices/SyrlinksHkHandler.h b/mission/devices/SyrlinksHkHandler.h index d2d80efa..1a30ff4a 100644 --- a/mission/devices/SyrlinksHkHandler.h +++ b/mission/devices/SyrlinksHkHandler.h @@ -2,7 +2,7 @@ #define MISSION_DEVICES_SYRLINKSHKHANDLER_H_ #include -#include +#include /** * @brief This is the device handler for the syrlinks transceiver. It handles the command @@ -38,6 +38,29 @@ protected: private: + static const DeviceCommandId_t RESET_UNIT = 0x01; + /** Reads out all status registers */ + static const DeviceCommandId_t READ_RX_STATUS_REGISTERS = 0x02; + /** Sets Tx mode to standby */ + static const DeviceCommandId_t SET_TX_MODE_STANDBY = 0x03; + /** Starts transmission mode. Only reached when clock signal is applying to the data tx input */ + static const DeviceCommandId_t SET_TX_MODE_MODULATION = 0x04; + /** Sends out a single carrier wave for testing purpose */ + static const DeviceCommandId_t SET_TX_MODE_CW = 0x05; + + /** Size of a simple transmission success response */ + static const uint8_t REQUEST_STATUS_REPLY_SIZE = 11; + /** Size of reply to an rx status registers request */ + static const uint8_t RX_STATUS_REGISTERS_REPLY_SIZE = 39; + + std::string resetCommand = ""; + std::string readRxStatusRegCommand = ""; + std::string setTxModeStandby = ""; + /** W - write, 04 - 4 bytes in data field, 01 - value, 40 register to write value */ + std::string setTxModeModulation = ""; + std::string setTxModeCw = ""; + + /** * @brief Function fills cmdBuffer with command to start the adc * conversion for a new temperature value. diff --git a/mission/devices/devicedefinitions/SyrlinksDefinitions.h b/mission/devices/devicedefinitions/SyrlinksDefinitions.h new file mode 100644 index 00000000..47e802c5 --- /dev/null +++ b/mission/devices/devicedefinitions/SyrlinksDefinitions.h @@ -0,0 +1,15 @@ +/* + * SyrlinksDefinitions.h + * + * Created on: 18.02.2021 + * Author: jakob + */ + +#ifndef MISSION_DEVICES_DEVICEDEFINITIONS_SYRLINKSDEFINITIONS_H_ +#define MISSION_DEVICES_DEVICEDEFINITIONS_SYRLINKSDEFINITIONS_H_ + + + + + +#endif /* MISSION_DEVICES_DEVICEDEFINITIONS_SYRLINKSDEFINITIONS_H_ */ From a5ef1d58532b8e6f4d4791b54f9a606275bb5bdb Mon Sep 17 00:00:00 2001 From: "Jakob.Meier" Date: Fri, 19 Feb 2021 11:02:27 +0100 Subject: [PATCH 03/79] syrlinks handler wip --- mission/devices/SyrlinksHkHandler.cpp | 95 ++++++++++--------- mission/devices/SyrlinksHkHandler.h | 32 +------ .../devicedefinitions/SyrlinksDefinitions.h | 53 +++++++++++ 3 files changed, 103 insertions(+), 77 deletions(-) diff --git a/mission/devices/SyrlinksHkHandler.cpp b/mission/devices/SyrlinksHkHandler.cpp index cedb015f..8c1feff9 100644 --- a/mission/devices/SyrlinksHkHandler.cpp +++ b/mission/devices/SyrlinksHkHandler.cpp @@ -1,13 +1,11 @@ #include #include -SyrlinksHkHandler::SyrlinksHkHandler(object_id_t objectId, object_id_t comIF, - CookieIF * comCookie) : - DeviceHandlerBase(objectId, comIF, comCookie), dataset( - this) { - if (comCookie == NULL) { - sif::error << "SyrlinksHkHandler: Invalid com cookie" << std::endl; - } +SyrlinksHkHandler::SyrlinksHkHandler(object_id_t objectId, object_id_t comIF, CookieIF * comCookie) : + DeviceHandlerBase(objectId, comIF, comCookie), rxStatusRegistersSet(this) { + if (comCookie == NULL) { + sif::error << "SyrlinksHkHandler: Invalid com cookie" << std::endl; + } } SyrlinksHkHandler::~SyrlinksHkHandler() { @@ -39,29 +37,34 @@ ReturnValue_t SyrlinksHkHandler::buildCommandFromCommand( DeviceCommandId_t deviceCommand, const uint8_t * commandData, size_t commandDataLen) { switch(deviceCommand) { - case(RESET_UNIT): { + case(SYRLINKS::RESET_UNIT): { resetCommand.copy(rawPacket, resetCommand.size(), 0); rawPacketLen = resetCommand.size(); + rememberCommandId = SYRLINKS::RESET_UNIT; return RETURN_OK; } - case(SET_TX_MODE_STANDBY): { + case(SYRLINKS::SET_TX_MODE_STANDBY): { setTxModeStandby.copy(rawPacket, setTxModeStandby.size(), 0); rawPacketLen = setTxModeStandby.size(); + rememberCommandId = SYRLINKS::SET_TX_MODE_STANDBY; return RETURN_OK; } - case(SET_TX_MODE_MODULATION): { + case(SYRLINKS::SET_TX_MODE_MODULATION): { setTxModeModulation.copy(rawPacket, setTxModeModulation.size(), 0); rawPacketLen = setTxModeModulation.size(); + rememberCommandId = SYRLINKS::SET_TX_MODE_MODULATION; return RETURN_OK; } - case(SET_TX_MODE_CW): { + case(SYRLINKS::SET_TX_MODE_CW): { setTxModeCw.copy(rawPacket, setTxModeCw.size(), 0); rawPacketLen = setTxModeCw.size(); + rememberCommandId = SYRLINKS::SET_TX_MODE_CW; return RETURN_OK; } - case(READ_RX_STATUS_REGISTERS): { + case(SYRLINKS::READ_RX_STATUS_REGISTERS): { readRxStatusRegCommand.copy(rawPacket, readRxStatusRegCommand.size(), 0); rawPacketLen = readRxStatusRegCommand.size(); + rememberCommandId = SYRLINKS::READ_RX_STATUS_REGISTERS; return RETURN_OK; } default: @@ -70,23 +73,43 @@ ReturnValue_t SyrlinksHkHandler::buildCommandFromCommand( return HasReturnvaluesIF::RETURN_FAILED; } -void SyrlinksHkHandler::fillCommandAndReplyMap(){ - this->insertInCommandAndReplyMap(RESET_UNIT); - this->insertInCommandAndReplyMap(SET_TX_MODE_STANDBY); - this->insertInCommandAndReplyMap(SET_TX_MODE_MODULATION); - this->insertInCommandAndReplyMap(SET_TX_MODE_CW); - this->insertInCommandAndReplyMap(READ_RX_STATUS_REGISTERS, 1, &rxStatusRegiserSet, - TMP1075::GET_TEMP_REPLY_SIZE); +void SyrlinksHkHandler::fillCommandAndReplyMap() { + this->insertInCommandAndReplyMap(SYRLINKS::RESET_UNIT); + this->insertInCommandAndReplyMap(SYRLINKS::SET_TX_MODE_STANDBY); + this->insertInCommandAndReplyMap(SYRLINKS::SET_TX_MODE_MODULATION); + this->insertInCommandAndReplyMap(SYRLINKS::SET_TX_MODE_CW); + this->insertInCommandAndReplyMap(SYRLINKS::READ_RX_STATUS_REGISTERS, 1, &rxStatusRegistersSet, + SYRLINKS::RX_STATUS_REGISTERS_REPLY_SIZE); } ReturnValue_t SyrlinksHkHandler::scanForReply(const uint8_t *start, size_t remainingSize, DeviceCommandId_t *foundId, size_t *foundLen) { switch(rememberCommandId) { - case(TMP1075::GET_TEMP): - *foundId = TMP1075::GET_TEMP; - *foundLen = TMP1075::GET_TEMP_REPLY_SIZE; - rememberCommandId = TMP1075::NONE; + case(SYRLINKS::RESET_UNIT): + *foundId = SYRLINKS::RESET_UNIT; + *foundLen = SYRLINKS::REQUEST_STATUS_REPLY_SIZE; + rememberCommandId = SYRLINKS::NONE; break; + case(SYRLINKS::SET_TX_MODE_STANDBY): + *foundId = SYRLINKS::SET_TX_MODE_STANDBY; + *foundLen = SYRLINKS::REQUEST_STATUS_REPLY_SIZE; + rememberCommandId = SYRLINKS::NONE; + break; + case(SYRLINKS::SET_TX_MODE_MODULATION): + *foundId = SYRLINKS::SET_TX_MODE_MODULATION; + *foundLen = SYRLINKS::REQUEST_STATUS_REPLY_SIZE; + rememberCommandId = SYRLINKS::NONE; + break; + case(SYRLINKS::SET_TX_MODE_CW): + *foundId = SYRLINKS::SET_TX_MODE_CW; + *foundLen = SYRLINKS::REQUEST_STATUS_REPLY_SIZE; + rememberCommandId = SYRLINKS::NONE; + break; + case(SYRLINKS::READ_RX_STATUS_REGISTERS): + *foundId = SYRLINKS::READ_RX_STATUS_REGISTERS; + *foundLen = SYRLINKS::REQUEST_STATUS_REPLY_SIZE; + rememberCommandId = SYRLINKS::NONE; + break; default: return IGNORE_REPLY_DATA; } @@ -96,20 +119,8 @@ ReturnValue_t SyrlinksHkHandler::scanForReply(const uint8_t *start, ReturnValue_t SyrlinksHkHandler::interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) { switch (id) { - case TMP1075::GET_TEMP: { - int16_t tempValueRaw = 0; - tempValueRaw = packet[0] << 4 | packet[1] >> 4; - float tempValue = ((static_cast(tempValueRaw)) * 0.0625); -#if OBSW_VERBOSE_LEVEL >= 1 - sif::info << "Tmp1075 with object id: 0x" << std::hex << getObjectId() - << ": Temperature: " << tempValue<< " °C" - << std::endl; -#endif - ReturnValue_t result = dataset.read(); - if(result == HasReturnvaluesIF::RETURN_OK) { - dataset.temperatureCelcius = tempValue; - dataset.commit(); - } + case (SYRLINKS::RESET_UNIT): { + break; } @@ -125,16 +136,6 @@ void SyrlinksHkHandler::setNormalDatapoolEntriesInvalid(){ } -void SyrlinksHkHandler::prepareAdcConversionCommand(){ - cmdBuffer[0] = TMP1075::CFGR_ADDR; - cmdBuffer[1] = TMP1075::ONE_SHOT_MODE >> 8; - cmdBuffer[2] = TMP1075::ONE_SHOT_MODE & 0xFF; -} - -void SyrlinksHkHandler::prepareGetTempCommand(){ - cmdBuffer[0] = TMP1075::TEMP_REG_ADDR; -} - uint32_t SyrlinksHkHandler::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo){ return 500; } diff --git a/mission/devices/SyrlinksHkHandler.h b/mission/devices/SyrlinksHkHandler.h index 1a30ff4a..55beec65 100644 --- a/mission/devices/SyrlinksHkHandler.h +++ b/mission/devices/SyrlinksHkHandler.h @@ -2,6 +2,7 @@ #define MISSION_DEVICES_SYRLINKSHKHANDLER_H_ #include +#include #include /** @@ -38,21 +39,6 @@ protected: private: - static const DeviceCommandId_t RESET_UNIT = 0x01; - /** Reads out all status registers */ - static const DeviceCommandId_t READ_RX_STATUS_REGISTERS = 0x02; - /** Sets Tx mode to standby */ - static const DeviceCommandId_t SET_TX_MODE_STANDBY = 0x03; - /** Starts transmission mode. Only reached when clock signal is applying to the data tx input */ - static const DeviceCommandId_t SET_TX_MODE_MODULATION = 0x04; - /** Sends out a single carrier wave for testing purpose */ - static const DeviceCommandId_t SET_TX_MODE_CW = 0x05; - - /** Size of a simple transmission success response */ - static const uint8_t REQUEST_STATUS_REPLY_SIZE = 11; - /** Size of reply to an rx status registers request */ - static const uint8_t RX_STATUS_REGISTERS_REPLY_SIZE = 39; - std::string resetCommand = ""; std::string readRxStatusRegCommand = ""; std::string setTxModeStandby = ""; @@ -60,21 +46,7 @@ private: std::string setTxModeModulation = ""; std::string setTxModeCw = ""; - - /** - * @brief Function fills cmdBuffer with command to start the adc - * conversion for a new temperature value. - */ - void prepareAdcConversionCommand(); - - void prepareGetTempCommand(); - - enum class CommunicationStep { - START_ADC_CONVERSION, - GET_TEMPERATURE - }; - - TMP1075::Tmp1075Dataset dataset; + SYRLINKS::RxStatusRegistersDataset rxStatusRegistersSet; static const uint8_t MAX_CMD_LEN = 3; diff --git a/mission/devices/devicedefinitions/SyrlinksDefinitions.h b/mission/devices/devicedefinitions/SyrlinksDefinitions.h index 47e802c5..3e50238b 100644 --- a/mission/devices/devicedefinitions/SyrlinksDefinitions.h +++ b/mission/devices/devicedefinitions/SyrlinksDefinitions.h @@ -9,7 +9,60 @@ #define MISSION_DEVICES_DEVICEDEFINITIONS_SYRLINKSDEFINITIONS_H_ +namespace SYRLINKS { + static const DeviceCommandId_t NONE = 0x0; + static const DeviceCommandId_t RESET_UNIT = 0x01; + /** Reads out all status registers */ + static const DeviceCommandId_t READ_RX_STATUS_REGISTERS = 0x02; + /** Sets Tx mode to standby */ + static const DeviceCommandId_t SET_TX_MODE_STANDBY = 0x03; + /** Starts transmission mode. Only reached when clock signal is applying to the data tx input */ + static const DeviceCommandId_t SET_TX_MODE_MODULATION = 0x04; + /** Sends out a single carrier wave for testing purpose */ + static const DeviceCommandId_t SET_TX_MODE_CW = 0x05; + + /** Size of a simple transmission success response */ + static const uint8_t REQUEST_STATUS_REPLY_SIZE = 11; + /** Size of reply to an rx status registers request */ + static const uint8_t RX_STATUS_REGISTERS_REPLY_SIZE = 39; + + static const uint8_t RX_STATUS_REGISTERS_SET_ID = READ_RX_STATUS_REGISTERS; + +class RxStatusRegistersDataset: public StaticLocalDataSet { +public: + + RxStatusRegistersDataset(HasLocalDataPoolIF* owner) : + StaticLocalDataSet(owner, RX_STATUS_REGISTERS_SET_ID) { + } + + RxStatusRegistersDataset(object_id_t objectId) : + StaticLocalDataSet(sid_t(objectId, RX_STATUS_REGISTERS_SET_ID)) { + } + + lp_var_t fpgaVersion = lp_var_t(sid.objectId, FPGA_VERSION, this); + lp_var_t fpgaBuild = lp_var_t(sid.objectId, FPGA_BUILD, this); + lp_var_t hardwareId = lp_var_t(sid.objectId, HARDWARE_ID, this); + lp_var_t fpgaType = lp_var_t(sid.objectId, FPGA_TYPE, this); + lp_var_t lclStatus = lp_var_t(sid.objectId, LCL_STATUS, this); + lp_var_t fpgaOption = lp_var_t(sid.objectId, FPGA_OPTION, this); + lp_var_t rxStatus = lp_var_t(sid.objectId, RX_STATUS, this); + lp_var_t rxSensitivity = lp_var_t(sid.objectId, RX_SENSITIVITY, this); + lp_var_t rxFrequencyShift = lp_var_t(sid.objectId, RX_FREQUENCY_SHIFT, this); + lp_var_t rxIqPower = lp_var_t(sid.objectId, RX_IQ_POWER, this); + lp_var_t rxAgcValue = lp_var_t(sid.objectId, RX_AGC_VALUE, this); + lp_var_t rxDemodEb = lp_var_t(sid.objectId, RX_DEMOD_EB, this); + lp_var_t rxDemodN0 = lp_var_t(sid.objectId, RX_DEMOD_N0, this); + lp_var_t rxDataRate = lp_var_t(sid.objectId, RX_DEMOD_N0, this); + lp_var_t txStatus = lp_var_t(sid.objectId, TX_STATUS, this); + lp_var_t txConvDiff = lp_var_t(sid.objectId, TX_CONV_DIFF, this); + lp_var_t txConvFilter = lp_var_t(sid.objectId, TX_CONV_FILTER, this); + lp_var_t txWaveform = lp_var_t(sid.objectId, TX_WAVEFORM, this); + lp_var_t txPcmIndex = lp_var_t(sid.objectId, TX_PCM_INDEX, this); + lp_var_t txAgcValue = lp_var_t(sid.objectId, TX_AGC_VALUE, this); +}; + +} #endif /* MISSION_DEVICES_DEVICEDEFINITIONS_SYRLINKSDEFINITIONS_H_ */ From e250f41c0939390885e8c0d711426f4fd49a6e2c Mon Sep 17 00:00:00 2001 From: "Jakob.Meier" Date: Fri, 19 Feb 2021 12:10:02 +0100 Subject: [PATCH 04/79] included crc for syrlinks --- mission/devices/crc/crc_ccitt_Syrlinks.cpp | 58 ++++++++++++++++++++++ mission/devices/crc/crc_ccitt_Syrlinks.h | 23 +++++++++ 2 files changed, 81 insertions(+) create mode 100644 mission/devices/crc/crc_ccitt_Syrlinks.cpp create mode 100644 mission/devices/crc/crc_ccitt_Syrlinks.h diff --git a/mission/devices/crc/crc_ccitt_Syrlinks.cpp b/mission/devices/crc/crc_ccitt_Syrlinks.cpp new file mode 100644 index 00000000..cb1e867d --- /dev/null +++ b/mission/devices/crc/crc_ccitt_Syrlinks.cpp @@ -0,0 +1,58 @@ +#include "crc_ccitt_Syrlinks.h" +#include +#include + +static const uint16_t crc_table[256] = { + 0x0000, 0x1021, 0x2042, 0x3063, 0x4084, 0x50a5, 0x60c6, 0x70e7, + 0x8108, 0x9129, 0xa14a, 0xb16b, 0xc18c, 0xd1ad, 0xe1ce, 0xf1ef, + 0x1231, 0x0210, 0x3273, 0x2252, 0x52b5, 0x4294, 0x72f7, 0x62d6, + 0x9339, 0x8318, 0xb37b, 0xa35a, 0xd3bd, 0xc39c, 0xf3ff, 0xe3de, + 0x2462, 0x3443, 0x0420, 0x1401, 0x64e6, 0x74c7, 0x44a4, 0x5485, + 0xa56a, 0xb54b, 0x8528, 0x9509, 0xe5ee, 0xf5cf, 0xc5ac, 0xd58d, + 0x3653, 0x2672, 0x1611, 0x0630, 0x76d7, 0x66f6, 0x5695, 0x46b4, + 0xb75b, 0xa77a, 0x9719, 0x8738, 0xf7df, 0xe7fe, 0xd79d, 0xc7bc, + 0x48c4, 0x58e5, 0x6886, 0x78a7, 0x0840, 0x1861, 0x2802, 0x3823, + 0xc9cc, 0xd9ed, 0xe98e, 0xf9af, 0x8948, 0x9969, 0xa90a, 0xb92b, + 0x5af5, 0x4ad4, 0x7ab7, 0x6a96, 0x1a71, 0x0a50, 0x3a33, 0x2a12, + 0xdbfd, 0xcbdc, 0xfbbf, 0xeb9e, 0x9b79, 0x8b58, 0xbb3b, 0xab1a, + 0x6ca6, 0x7c87, 0x4ce4, 0x5cc5, 0x2c22, 0x3c03, 0x0c60, 0x1c41, + 0xedae, 0xfd8f, 0xcdec, 0xddcd, 0xad2a, 0xbd0b, 0x8d68, 0x9d49, + 0x7e97, 0x6eb6, 0x5ed5, 0x4ef4, 0x3e13, 0x2e32, 0x1e51, 0x0e70, + 0xff9f, 0xefbe, 0xdfdd, 0xcffc, 0xbf1b, 0xaf3a, 0x9f59, 0x8f78, + 0x9188, 0x81a9, 0xb1ca, 0xa1eb, 0xd10c, 0xc12d, 0xf14e, 0xe16f, + 0x1080, 0x00a1, 0x30c2, 0x20e3, 0x5004, 0x4025, 0x7046, 0x6067, + 0x83b9, 0x9398, 0xa3fb, 0xb3da, 0xc33d, 0xd31c, 0xe37f, 0xf35e, + 0x02b1, 0x1290, 0x22f3, 0x32d2, 0x4235, 0x5214, 0x6277, 0x7256, + 0xb5ea, 0xa5cb, 0x95a8, 0x8589, 0xf56e, 0xe54f, 0xd52c, 0xc50d, + 0x34e2, 0x24c3, 0x14a0, 0x0481, 0x7466, 0x6447, 0x5424, 0x4405, + 0xa7db, 0xb7fa, 0x8799, 0x97b8, 0xe75f, 0xf77e, 0xc71d, 0xd73c, + 0x26d3, 0x36f2, 0x0691, 0x16b0, 0x6657, 0x7676, 0x4615, 0x5634, + 0xd94c, 0xc96d, 0xf90e, 0xe92f, 0x99c8, 0x89e9, 0xb98a, 0xa9ab, + 0x5844, 0x4865, 0x7806, 0x6827, 0x18c0, 0x08e1, 0x3882, 0x28a3, + 0xcb7d, 0xdb5c, 0xeb3f, 0xfb1e, 0x8bf9, 0x9bd8, 0xabbb, 0xbb9a, + 0x4a75, 0x5a54, 0x6a37, 0x7a16, 0x0af1, 0x1ad0, 0x2ab3, 0x3a92, + 0xfd2e, 0xed0f, 0xdd6c, 0xcd4d, 0xbdaa, 0xad8b, 0x9de8, 0x8dc9, + 0x7c26, 0x6c07, 0x5c64, 0x4c45, 0x3ca2, 0x2c83, 0x1ce0, 0x0cc1, + 0xef1f, 0xff3e, 0xcf5d, 0xdf7c, 0xaf9b, 0xbfba, 0x8fd9, 0x9ff8, + 0x6e17, 0x7e36, 0x4e55, 0x5e74, 0x2e93, 0x3eb2, 0x0ed1, 0x1ef0 +}; + + +// CRC implementation +uint16_t Calculate_CRC_Syrlinks(uint8_t const input[], uint32_t length) +{ + uint16_t crc = 0x0000; + uint8_t *data = (uint8_t *)input; + unsigned int tbl_idx; + + while (length--) { + tbl_idx = ((crc >> 8) ^ *data) & 0xff; + crc = (crc_table[tbl_idx] ^ (crc << 8)) & 0xffff; + + data++; + } + return crc & 0xffff; + +} /* Calculate_CRC() */ + + diff --git a/mission/devices/crc/crc_ccitt_Syrlinks.h b/mission/devices/crc/crc_ccitt_Syrlinks.h new file mode 100644 index 00000000..8b952ee8 --- /dev/null +++ b/mission/devices/crc/crc_ccitt_Syrlinks.h @@ -0,0 +1,23 @@ +#ifndef CRC_CCITT_Syrlinks_H_ +#define CRC_CCITT_Syrlinks_H_ + +#include + +/** + * @brief With this function the CRC16-CCITT over a data packet can be calculated. + * + * @param input Pointer to data over which the crc shall be calculated. + * @param length Size of data packet. + * + * @return The 16-bit wide crc calculated over the data packet. + * + * @details Wide: 16 bits + * Generator polynomial: 0x1021 + * Bit order: MSB + * Initial value: 0 + * @author Bucher, J. Meier + */ +uint16_t Calculate_CRC_Syrlinks(uint8_t const input[], uint32_t length); + + +#endif /* CRC_H_ */ From b4d74b4a4ffe6ea6aafa8c67a99bd5dc0f7bb2e9 Mon Sep 17 00:00:00 2001 From: "Jakob.Meier" Date: Fri, 19 Feb 2021 15:41:50 +0100 Subject: [PATCH 05/79] save before removing approach with rememberCommandId --- fsfwconfig/returnvalues/classIds.h | 3 +- mission/devices/SyrlinksHkHandler.cpp | 164 +++++++++++++++--- mission/devices/SyrlinksHkHandler.h | 56 +++++- .../devicedefinitions/SyrlinksDefinitions.h | 3 + 4 files changed, 203 insertions(+), 23 deletions(-) diff --git a/fsfwconfig/returnvalues/classIds.h b/fsfwconfig/returnvalues/classIds.h index 419a24ef..c5e4d27a 100644 --- a/fsfwconfig/returnvalues/classIds.h +++ b/fsfwconfig/returnvalues/classIds.h @@ -16,7 +16,8 @@ enum { LINUX_LIBGPIO_IF, PCDU_HANDLER, HEATER_HANDLER, - SA_DEPL_HANDLER + SA_DEPL_HANDLER, + SYRLINKS_HANDLER, }; } diff --git a/mission/devices/SyrlinksHkHandler.cpp b/mission/devices/SyrlinksHkHandler.cpp index 8c1feff9..a13c0286 100644 --- a/mission/devices/SyrlinksHkHandler.cpp +++ b/mission/devices/SyrlinksHkHandler.cpp @@ -1,5 +1,6 @@ #include #include +#include SyrlinksHkHandler::SyrlinksHkHandler(object_id_t objectId, object_id_t comIF, CookieIF * comCookie) : DeviceHandlerBase(objectId, comIF, comCookie), rxStatusRegistersSet(this) { @@ -84,46 +85,95 @@ void SyrlinksHkHandler::fillCommandAndReplyMap() { ReturnValue_t SyrlinksHkHandler::scanForReply(const uint8_t *start, size_t remainingSize, DeviceCommandId_t *foundId, size_t *foundLen) { + + ReturnValue_t result = RETURN_OK; + switch(rememberCommandId) { case(SYRLINKS::RESET_UNIT): - *foundId = SYRLINKS::RESET_UNIT; - *foundLen = SYRLINKS::REQUEST_STATUS_REPLY_SIZE; - rememberCommandId = SYRLINKS::NONE; + if (remainingSize != SYRLINKS::REQUEST_STATUS_REPLY_SIZE) { + result = REPLY_WRONG_SIZE; + break; + } + *foundLen = SYRLINKS::REQUEST_STATUS_REPLY_SIZE; + *foundId = SYRLINKS::RESET_UNIT; + rememberCommandId = SYRLINKS::NONE; break; case(SYRLINKS::SET_TX_MODE_STANDBY): - *foundId = SYRLINKS::SET_TX_MODE_STANDBY; - *foundLen = SYRLINKS::REQUEST_STATUS_REPLY_SIZE; - rememberCommandId = SYRLINKS::NONE; + if (remainingSize != SYRLINKS::REQUEST_STATUS_REPLY_SIZE) { + result = REPLY_WRONG_SIZE; + } + *foundLen = SYRLINKS::REQUEST_STATUS_REPLY_SIZE; + rememberCommandId = SYRLINKS::NONE; + *foundId = SYRLINKS::SET_TX_MODE_STANDBY; break; case(SYRLINKS::SET_TX_MODE_MODULATION): - *foundId = SYRLINKS::SET_TX_MODE_MODULATION; - *foundLen = SYRLINKS::REQUEST_STATUS_REPLY_SIZE; - rememberCommandId = SYRLINKS::NONE; + if (remainingSize != SYRLINKS::REQUEST_STATUS_REPLY_SIZE) { + result = REPLY_WRONG_SIZE; + } + *foundLen = SYRLINKS::REQUEST_STATUS_REPLY_SIZE; + *foundId = SYRLINKS::SET_TX_MODE_MODULATION; + rememberCommandId = SYRLINKS::NONE; break; case(SYRLINKS::SET_TX_MODE_CW): - *foundId = SYRLINKS::SET_TX_MODE_CW; - *foundLen = SYRLINKS::REQUEST_STATUS_REPLY_SIZE; - rememberCommandId = SYRLINKS::NONE; + if (remainingSize != SYRLINKS::REQUEST_STATUS_REPLY_SIZE) { + result = REPLY_WRONG_SIZE; + } + *foundLen = SYRLINKS::REQUEST_STATUS_REPLY_SIZE; + *foundId = SYRLINKS::SET_TX_MODE_CW; + rememberCommandId = SYRLINKS::NONE; break; case(SYRLINKS::READ_RX_STATUS_REGISTERS): - *foundId = SYRLINKS::READ_RX_STATUS_REGISTERS; - *foundLen = SYRLINKS::REQUEST_STATUS_REPLY_SIZE; - rememberCommandId = SYRLINKS::NONE; + if (remainingSize != SYRLINKS::RX_STATUS_REGISTERS_REPLY_SIZE) { + result = REPLY_WRONG_SIZE; + } + *foundLen = SYRLINKS::RX_STATUS_REGISTERS_REPLY_SIZE; + *foundId = SYRLINKS::READ_RX_STATUS_REGISTERS; + rememberCommandId = SYRLINKS::NONE; break; default: - return IGNORE_REPLY_DATA; + result = IGNORE_REPLY_DATA; + break; } - return HasReturnvaluesIF::RETURN_OK; + + if (result == REPLY_WRONG_SIZE) { + sif::debug << "SyrlinksHkHandler::scanForReply: Received reply with invalid length" + << std::endl; + return result; + } + + return result; } ReturnValue_t SyrlinksHkHandler::interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) { - switch (id) { - case (SYRLINKS::RESET_UNIT): { - break; - } + ReturnValue_t result; + switch (id) { + case (SYRLINKS::RESET_UNIT): + case (SYRLINKS::SET_TX_MODE_STANDBY): + case (SYRLINKS::SET_TX_MODE_MODULATION): + case (SYRLINKS::SET_TX_MODE_CW): + result = verifyTansmissionStatusReply(packet); + if (result != RETURN_OK) { + sif::debug << "SyrlinksHkHandler::interpretDeviceReply: Status reply has invalid crc" + << std::endl; + return CRC_FAILURE; + } + result = parseReplyStatus(static_cast(packet + SYRLINKS::MESSAGE_HEADER_SIZE)); + if (result != RETURN_OK) { + return result; + } + break; + case(SYRLINKS::READ_RX_STATUS_REGISTERS): + result = verifyReadRxStatusRegistersReply(packet); + if (result != RETURN_OK) { + sif::debug << "SyrlinksHkHandler::interpretDeviceReply: Read rx status registers reply " + << "has invalid crc" << std::endl; + return CRC_FAILURE; + } + + break; default: { return DeviceHandlerIF::UNKNOWN_DEVICE_REPLY; } @@ -132,6 +182,78 @@ ReturnValue_t SyrlinksHkHandler::interpretDeviceReply(DeviceCommandId_t id, return HasReturnvaluesIF::RETURN_OK; } + +ReturnValue_t SyrlinksHkHandler::verifyTansmissionStatusReply() { + int result = 0; + uint16_t crc = CRC::crc16ccitt(packet, + SYRLINKS::REQUEST_STATUS_REPLY_SIZE - SYRLINKS::SIZE_CRC_AND_TERMINATION, + CRC_INITIAL_VALUE); + std::string recalculatedCrc = convertIntToHexString(crc); + const char* replyCrc = packet + SYRLINKS::REQUEST_STATUS_REPLY_SIZE + - SYRLINKS::SIZE_CRC_AND_TERMINATION; + size_t startPosition = 0; + result = recalculatedCrc.compare(startPosition, SYRLINKS_CRC_FIELD_SIZE, replyCrc); + if (result != 0) { + return RETURN_FAILED; + } + return RETURN_OK; +} + +std::string SyrlinksHkHandler::convertIntToHexString(uint16_t intValue) { + std::stringstream stream; + stream << std::hex << intValue; + return stream.str(); +} + +ReturnValue_t SyrlinksHkHandler::parseReplyStatus(char* status) { + switch (*status) { + case '0': + return RETURN_OK; + case '1': + sif::debug << "SyrlinksHkHandler::parseReplyStatus: Uart faming or parity error" + << std::endl; + return UART_FRAMIN_OR_PARITY_ERROR_ACK; + case '2': + sif::debug << "SyrlinksHkHandler::parseReplyStatus: Bad character detected" << std::endl; + return BAD_CHARACTER_ACK; + case '3': + sif::debug << "SyrlinksHkHandler::parseReplyStatus: Bad parameter value (unexpected value " + << "detected" << std::endl; + return BAD_PARAMETER_VALUE_ACK; + case '4': + sif::debug << "SyrlinksHkHandler::parseReplyStatus: Bad end of frame" << std::endl; + return BAD_END_OF_FRAME_ACK; + case '5': + sif::debug << "SyrlinksHkHandler::parseReplyStatus: Unknown command id or attempt to access" + << " a protected register" << std::endl; + return UNKNOWN_COMMAND_ID_ACK; + case '6': + sif::debug << "SyrlinksHkHandler::parseReplyStatus: Bad CRC" << std::endl; + return BAD_CRC_ACK; + default: + sif::debug << "SyrlinksHkHandler::parseReplyStatus: Status reply holds invalid status " + << "id" << std::endl; + return RETURN_FAILED; + } +} + +ReturnValue_t SyrlinksHkHandler::verifyReadRxStatusRegistersReply(uint8_t* packet) { + int result = 0; + /* Calculate crc of received packet */ + uint16_t crc = CRC::crc16ccitt(packet, + SYRLINKS::RX_STATUS_REGISTERS_REPLY_SIZE - SYRLINKS::SIZE_CRC_AND_TERMINATION, + CRC_INITIAL_VALUE); + std::string recalculatedCrc = convertIntToHexString(crc); + const char* replyCrc = packet + SYRLINKS::RX_STATUS_REGISTERS_REPLY_SIZE + - SYRLINKS::SIZE_CRC_AND_TERMINATION; + size_t startPosition = 0; + result = recalculatedCrc.compare(startPosition, SYRLINKS_CRC_FIELD_SIZE, replyCrc); + if (result != 0) { + return RETURN_FAILED; + } + return RETURN_OK; +} + void SyrlinksHkHandler::setNormalDatapoolEntriesInvalid(){ } diff --git a/mission/devices/SyrlinksHkHandler.h b/mission/devices/SyrlinksHkHandler.h index 55beec65..aefc99f9 100644 --- a/mission/devices/SyrlinksHkHandler.h +++ b/mission/devices/SyrlinksHkHandler.h @@ -39,6 +39,19 @@ protected: private: + static const uint8_t INTERFACE_ID = CLASS_ID::SYRLINKS_HANDLER; + + static const ReturnValue_t CRC_FAILURE = MAKE_RETURN_CODE(0xA0); + static const ReturnValue_t UART_FRAMIN_OR_PARITY_ERROR_ACK = MAKE_RETURN_CODE(0xA1); + static const ReturnValue_t BAD_CHARACTER_ACK = MAKE_RETURN_CODE(0xA2); + static const ReturnValue_t BAD_PARAMETER_VALUE_ACK = MAKE_RETURN_CODE(0xA3); + static const ReturnValue_t BAD_END_OF_FRAME_ACK = MAKE_RETURN_CODE(0xA4); + static const ReturnValue_t UNKNOWN_COMMAND_ID_ACK = MAKE_RETURN_CODE(0xA5); + static const ReturnValue_t BAD_CRC_ACK = MAKE_RETURN_CODE(0xA6); + static const ReturnValue_t REPLY_WRONG_SIZE = MAKE_RETURN_CODE(0xA7); + + static const uint8_t CRC_INITIAL_VALUE = 0x0; + std::string resetCommand = ""; std::string readRxStatusRegCommand = ""; std::string setTxModeStandby = ""; @@ -51,10 +64,51 @@ private: static const uint8_t MAX_CMD_LEN = 3; uint8_t rememberRequestedSize = 0; - uint8_t rememberCommandId = TMP1075::NONE; + uint8_t rememberCommandId = SYRLINKS::NONE; uint8_t cmdBuffer[MAX_CMD_LEN]; CommunicationStep communicationStep = CommunicationStep::START_ADC_CONVERSION; + + + /** + * @brief This function verifies the checksum of a status reply packet of the syrlinks. + * + * @param packet Pointer to the received status reply. + * + * @return RETURN_OK if successful, otherwise RETURN_FAILURE. + * + * @details A status reply only contains one byte of payload data giving information about + * the transmission status. + */ + ReturnValue_t verifyTansmissionStatusReply(const uint8_t* packet); + + /** + * @brief This function converts an uint16_t into its hexadecimal string representation. + * + * @param The value to convert. + * + * @return An std::string object containing the hex representation of intValue. + */ + std::string SyrlinksHkHandler::convertIntToHexString(uint16_t intValue); + + /** + * @brief This function parses the status reply + * @param status Pointer to the status information. + * + * @details Some commands reply with a status message giving information about the preceding + * command transmission and/or execution was successful. + */ + ReturnValue_t parseReplyStatus(char* status); + + /** + * @brief Function verifies the received reply from the syrlinks by recalculating and + * comparing the crc. + * + * @param packet Pointer to the received reply. + * + * @return RETURN_OK if successful, otherwise RETURN_FAILED. + */ + ReturnValue_t verifyReadRxStatusRegistersReply(uint8_t* packet) }; #endif /* MISSION_DEVICES_SYRLINKSHKHANDLER_H_ */ diff --git a/mission/devices/devicedefinitions/SyrlinksDefinitions.h b/mission/devices/devicedefinitions/SyrlinksDefinitions.h index 3e50238b..2cd159af 100644 --- a/mission/devices/devicedefinitions/SyrlinksDefinitions.h +++ b/mission/devices/devicedefinitions/SyrlinksDefinitions.h @@ -24,6 +24,9 @@ namespace SYRLINKS { /** Size of a simple transmission success response */ static const uint8_t REQUEST_STATUS_REPLY_SIZE = 11; + static const uint8_t SIZE_CRC_AND_TERMINATION = 5; + /** The size of the header with the message identifier and the payload size field */ + static const uint8_t MESSAGE_HEADER_SIZE = 5; /** Size of reply to an rx status registers request */ static const uint8_t RX_STATUS_REGISTERS_REPLY_SIZE = 39; From 7710fda755971c939132bd4b935682b19e50ab1e Mon Sep 17 00:00:00 2001 From: "Jakob.Meier" Date: Mon, 22 Feb 2021 09:24:42 +0100 Subject: [PATCH 06/79] syrlinks handler ready for testing --- CMakeLists.txt | 2 +- bsp_q7s/ObjectFactory.cpp | 13 + fsfwconfig/objects/systemObjectList.h | 4 +- .../PollingSequenceFactory.cpp | 4 + libcsp/src/drivers/can/can_socketcan.c | 6 - linux/CMakeLists.txt | 1 + linux/i2c/I2cComIF.cpp | 7 +- linux/i2c/I2cCookie.h | 3 +- linux/uart/CMakeLists.txt | 8 + linux/uart/UartComIF.cpp | 368 ++++++++++++++++++ linux/uart/UartComIF.h | 94 +++++ linux/uart/UartCookie.cpp | 63 +++ linux/uart/UartCookie.h | 81 ++++ mission/devices/SyrlinksHkHandler.cpp | 217 ++++++----- mission/devices/SyrlinksHkHandler.h | 58 +-- mission/devices/crc/crc_ccitt_Syrlinks.cpp | 58 --- mission/devices/crc/crc_ccitt_Syrlinks.h | 23 -- .../devicedefinitions/SyrlinksDefinitions.h | 79 ++-- 18 files changed, 842 insertions(+), 247 deletions(-) create mode 100644 linux/uart/CMakeLists.txt create mode 100644 linux/uart/UartComIF.cpp create mode 100644 linux/uart/UartComIF.h create mode 100644 linux/uart/UartCookie.cpp create mode 100644 linux/uart/UartCookie.h delete mode 100644 mission/devices/crc/crc_ccitt_Syrlinks.cpp delete mode 100644 mission/devices/crc/crc_ccitt_Syrlinks.h diff --git a/CMakeLists.txt b/CMakeLists.txt index 22e45134..5107b573 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -47,7 +47,7 @@ set(TEST_PATH test/testtasks) set(LINUX_PATH linux) set(FSFW_WARNING_SHADOW_LOCAL_GCC OFF) -set(ADD_LINUX_FILES FALSE) +set(ADD_LINUX_FILES TRUE) # Analyse different OS and architecture/target options, determine BSP_PATH, # display information about compiler etc. diff --git a/bsp_q7s/ObjectFactory.cpp b/bsp_q7s/ObjectFactory.cpp index aae12b34..a97118f9 100644 --- a/bsp_q7s/ObjectFactory.cpp +++ b/bsp_q7s/ObjectFactory.cpp @@ -23,8 +23,10 @@ #include #include #include +#include #include #include +#include #include #include @@ -33,6 +35,8 @@ #include #include #include +#include +#include #if TEST_LIBGPIOD == 1 #include "LibgpiodTest.h" @@ -75,6 +79,7 @@ void ObjectFactory::produce(){ /* Communication interfaces */ new CspComIF(objects::CSP_COM_IF); new I2cComIF(objects::I2C_COM_IF); + new UartComIF(objects::UART_COM_IF); #if TE0720 == 0 CspCookie* p60DockCspCookie = new CspCookie(P60Dock::MAX_REPLY_LENGTH, @@ -168,6 +173,14 @@ void ObjectFactory::produce(){ new SolarArrayDeploymentHandler(objects::SOLAR_ARRAY_DEPL_HANDLER, objects::GPIO_IF, solarArrayDeplCookie, objects::PCDU_HANDLER, pcduSwitches::DEPLOYMENT_MECHANISM, gpioIds::DEPLSA1, gpioIds::DEPLSA2, 1000); + + UartCookie* syrlinksUartCookie = new UartCookie( + std::string("/dev/ttyPS1"), 38400, SYRLINKS::MAX_REPLY_SIZE); + syrlinksUartCookie->setParityEven(); + + SyrlinksHkHandler* syrlinksHkHandler = new SyrlinksHkHandler(objects::SYRLINKS_HK_HANDLER, objects::UART_COM_IF, syrlinksUartCookie); + syrlinksHkHandler->setModeNormal(); + #endif new TmTcUnixUdpBridge(objects::UDP_BRIDGE, diff --git a/fsfwconfig/objects/systemObjectList.h b/fsfwconfig/objects/systemObjectList.h index 153b3155..f05a5f6a 100644 --- a/fsfwconfig/objects/systemObjectList.h +++ b/fsfwconfig/objects/systemObjectList.h @@ -30,6 +30,7 @@ namespace objects { ARDUINO_COM_IF = 0x49000001, CSP_COM_IF = 0x49000002, I2C_COM_IF = 0x49000003, + UART_COM_IF = 0x49000004, /* 0x47 ('G') for Gpio Interfaces */ GPIO_IF = 0x47000001, @@ -41,10 +42,11 @@ namespace objects { ACU_HANDLER = 0x44000004, TMP1075_HANDLER_1 = 0x44000005, TMP1075_HANDLER_2 = 0x44000006, - /* Custom device handler */ PCDU_HANDLER = 0x44000007, + /* Custom device handler */ SOLAR_ARRAY_DEPL_HANDLER = 0x44000008, + SYRLINKS_HK_HANDLER = 0x44000009, /* 0x54 ('T') for thermal objects */ HEATER_HANDLER = 0x54000003, diff --git a/fsfwconfig/pollingsequence/PollingSequenceFactory.cpp b/fsfwconfig/pollingsequence/PollingSequenceFactory.cpp index d6f922dd..f098800f 100644 --- a/fsfwconfig/pollingsequence/PollingSequenceFactory.cpp +++ b/fsfwconfig/pollingsequence/PollingSequenceFactory.cpp @@ -20,15 +20,19 @@ ReturnValue_t pst::pollingSequenceInitDefault(FixedTimeslotTaskIF *thisSequence) thisSequence->addSlot(objects::TMP1075_HANDLER_1, length * 0.2, DeviceHandlerIF::SEND_WRITE); thisSequence->addSlot(objects::TMP1075_HANDLER_2, length * 0.2, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::SYRLINKS_HK_HANDLER, length * 0.2, DeviceHandlerIF::SEND_WRITE); thisSequence->addSlot(objects::TMP1075_HANDLER_1, length * 0.4, DeviceHandlerIF::GET_WRITE); thisSequence->addSlot(objects::TMP1075_HANDLER_2, length * 0.4, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::SYRLINKS_HK_HANDLER, length * 0.4, DeviceHandlerIF::GET_WRITE); thisSequence->addSlot(objects::TMP1075_HANDLER_1, length * 0.6, DeviceHandlerIF::SEND_READ); thisSequence->addSlot(objects::TMP1075_HANDLER_2, length * 0.6, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::SYRLINKS_HK_HANDLER, length * 0.6, DeviceHandlerIF::SEND_READ); thisSequence->addSlot(objects::TMP1075_HANDLER_1, length * 0.8, DeviceHandlerIF::GET_READ); thisSequence->addSlot(objects::TMP1075_HANDLER_2, length * 0.8, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::SYRLINKS_HK_HANDLER, length * 0.8, DeviceHandlerIF::GET_READ); if (thisSequence->checkSequence() == HasReturnvaluesIF::RETURN_OK) { return HasReturnvaluesIF::RETURN_OK; diff --git a/libcsp/src/drivers/can/can_socketcan.c b/libcsp/src/drivers/can/can_socketcan.c index d6d6b9e1..94c6bdde 100644 --- a/libcsp/src/drivers/can/can_socketcan.c +++ b/libcsp/src/drivers/can/can_socketcan.c @@ -95,12 +95,6 @@ static void * socketcan_rx_thread(void * parameters) /* Strip flags */ frame.can_id &= CAN_EFF_MASK; - printf("socketcan_rx_thread: CAN bytes received: "); - /* Print received data */ - for (int i = 0; i < 8; i++) { - printf("%x, ", frame.data[i]); - } - /* Call RX callbacsp_can_rx_frameck */ csp_can_rx(&socketcan[0].interface, frame.can_id, frame.data, frame.can_dlc, NULL); } diff --git a/linux/CMakeLists.txt b/linux/CMakeLists.txt index 9a25fdff..da75446a 100644 --- a/linux/CMakeLists.txt +++ b/linux/CMakeLists.txt @@ -2,4 +2,5 @@ add_subdirectory(gpio) add_subdirectory(i2c) add_subdirectory(csp) add_subdirectory(spi) +add_subdirectory(uart) diff --git a/linux/i2c/I2cComIF.cpp b/linux/i2c/I2cComIF.cpp index 2f1d710a..5b11f231 100644 --- a/linux/i2c/I2cComIF.cpp +++ b/linux/i2c/I2cComIF.cpp @@ -40,7 +40,7 @@ ReturnValue_t I2cComIF::initializeInterface(CookieIF * cookie) { sif::error << "I2cComIF::initializeInterface: Failed to insert " << "device with address " << i2cAddress << "to I2C device " << "map" << std::endl; - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_FAILED; } } else { @@ -48,11 +48,6 @@ ReturnValue_t I2cComIF::initializeInterface(CookieIF * cookie) { << "already in use" << std::endl; } - i2cDeviceMapIter = i2cDeviceMap.find(i2cAddress); - if(i2cDeviceMapIter == i2cDeviceMap.end()) { - sif::error << "Failure" << std::endl; - } - return HasReturnvaluesIF::RETURN_OK; } diff --git a/linux/i2c/I2cCookie.h b/linux/i2c/I2cCookie.h index f03d6290..483ed19c 100644 --- a/linux/i2c/I2cCookie.h +++ b/linux/i2c/I2cCookie.h @@ -15,8 +15,9 @@ public: /** * @brief Constructor for the I2C cookie. * @param i2cAddress_ The i2c address of the target device. - * @param maxReplyLen The maximum expected length of a reply from the + * @param maxReplyLen_ The maximum expected length of a reply from the * target device. + * @param devicFile_ The device file specifying the i2c interface to use. E.g. "/dev/i2c-0". */ I2cCookie(address_t i2cAddress_, size_t maxReplyLen_, std::string deviceFile_); diff --git a/linux/uart/CMakeLists.txt b/linux/uart/CMakeLists.txt new file mode 100644 index 00000000..7b503d02 --- /dev/null +++ b/linux/uart/CMakeLists.txt @@ -0,0 +1,8 @@ +target_sources(${TARGET_NAME} PUBLIC + UartComIF.cpp + UartCookie.cpp +) + + + + diff --git a/linux/uart/UartComIF.cpp b/linux/uart/UartComIF.cpp new file mode 100644 index 00000000..79470a45 --- /dev/null +++ b/linux/uart/UartComIF.cpp @@ -0,0 +1,368 @@ +#include "UartComIF.h" + +#include +#include + +#include +#include +#include +#include + +UartComIF::UartComIF(object_id_t objectId): SystemObject(objectId){ +} + +UartComIF::~UartComIF() {} + +ReturnValue_t UartComIF::initializeInterface(CookieIF * cookie) { + + std::string deviceFile; + UartDeviceMapIter uartDeviceMapIter; + + if(cookie == nullptr) { + return NULLPOINTER; + } + + UartCookie* uartCookie = dynamic_cast(cookie); + if (uartCookie == nullptr) { + sif::error << "UartComIF::initializeInterface: Invalid UART Cookie!" << std::endl; + return NULLPOINTER; + } + + deviceFile = uartCookie->getDeviceFile(); + + uartDeviceMapIter = uartDeviceMap.find(deviceFile); + if(uartDeviceMapIter == uartDeviceMap.end()) { + int fileDescriptor = configureUartPort(uartCookie); + if (fileDescriptor < 0) { + return RETURN_FAILED; + } + size_t maxReplyLen = uartCookie->getMaxReplyLen(); + UartElements_t uartElements = {fileDescriptor, std::vector(maxReplyLen), 0}; + std::pair status = uartDeviceMap.emplace(deviceFile, uartElements); + if (status.second == false) { + sif::debug << "UartComIF::initializeInterface: Failed to insert device " << deviceFile + << "to Uart device map" << std::endl; + return RETURN_FAILED; + } + } + else { + sif::debug << "UartComIF::initializeInterface: Uart device " << deviceFile << "already in " + << "use" << std::endl; + return RETURN_FAILED; + } + + return RETURN_OK; +} + +int UartComIF::configureUartPort(UartCookie* uartCookie) { + + struct termios options; + + std::string deviceFile = uartCookie->getDeviceFile(); + int fd = open(deviceFile.c_str(), O_RDWR); + + if (fd < 0) { + sif::debug << "UartComIF::configureUartPort: Failed to open uart " << deviceFile << "with" + << " error code " << errno << strerror(errno) << std::endl; + return fd; + } + + /* Read in existing settings */ + if(tcgetattr(fd, &options) != 0) { + sif::debug << "UartComIF::configureUartPort: Error " << errno << "from tcgetattr: " + << strerror(errno) << std::endl; + return fd; + } + + setParityOptions(&options, uartCookie); + setStopBitOptions(&options, uartCookie); + setDatasizeOptions(&options, uartCookie); + setFixedOptions(&options); + + /* 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; + + configureBaudrate(&options, uartCookie); + + /* Save option settings */ + if (tcsetattr(fd, TCSANOW, &options) != 0) { + sif::debug << "UartComIF::configureUartPort: Failed to set options with error " << errno + << ": " << strerror(errno); + return fd; + } + return fd; +} + +void UartComIF::setParityOptions(struct termios* options, UartCookie* uartCookie) { + /* Clear parity bit */ + options->c_cflag &= ~PARENB; + switch (uartCookie->getParity()) { + case Parity::EVEN: + options->c_cflag |= PARENB; + options->c_cflag &= ~PARODD; + break; + case Parity::ODD: + options->c_cflag |= PARENB; + options->c_cflag |= PARODD; + break; + default: + break; + } +} + +void UartComIF::setStopBitOptions(struct termios* options, UartCookie* uartCookie) { + /* Clear stop field. Sets stop bit to one bit */ + options->c_cflag &= ~CSTOPB; + switch (uartCookie->getStopBits()) { + case StopBits::TWO_STOP_BITS: + options->c_cflag |= CSTOPB; + break; + default: + break; + } +} + +void UartComIF::setDatasizeOptions(struct termios* options, UartCookie* uartCookie) { + /* Clear size bits */ + options->c_cflag &= ~CSIZE; + switch (uartCookie->getBitsPerWord()) { + case 5: + options->c_cflag |= CS5; + break; + case 6: + options->c_cflag |= CS6; + break; + case 7: + options->c_cflag |= CS7; + break; + case 8: + options->c_cflag |= CS8; + break; + default: + sif::debug << "UartComIF::setDatasizeOptions: Invalid size specified" << std::endl; + break; + } +} + +void UartComIF::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 canonical mode */ + options->c_lflag &= ~ICANON; + /* 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; +} + +void UartComIF::configureBaudrate(struct termios* options, UartCookie* uartCookie) { + switch (uartCookie->getBaudrate()) { + case 50: + cfsetispeed(options, B50); + cfsetospeed(options, B50); + break; + case 75: + cfsetispeed(options, B75); + cfsetospeed(options, B75); + break; + case 110: + cfsetispeed(options, B110); + cfsetospeed(options, B110); + break; + case 134: + cfsetispeed(options, B134); + cfsetospeed(options, B134); + break; + case 150: + cfsetispeed(options, B150); + cfsetospeed(options, B150); + break; + case 200: + cfsetispeed(options, B200); + cfsetospeed(options, B200); + break; + case 300: + cfsetispeed(options, B300); + cfsetospeed(options, B300); + break; + case 600: + cfsetispeed(options, B600); + cfsetospeed(options, B600); + break; + case 1200: + cfsetispeed(options, B1200); + cfsetospeed(options, B1200); + break; + case 1800: + cfsetispeed(options, B1800); + cfsetospeed(options, B1800); + break; + case 2400: + cfsetispeed(options, B2400); + cfsetospeed(options, B2400); + break; + case 4800: + cfsetispeed(options, B4800); + cfsetospeed(options, B4800); + break; + case 9600: + cfsetispeed(options, B9600); + cfsetospeed(options, B9600); + break; + case 19200: + cfsetispeed(options, B19200); + cfsetospeed(options, B19200); + break; + case 38400: + cfsetispeed(options, B38400); + cfsetospeed(options, B38400); + break; + case 57600: + cfsetispeed(options, B57600); + cfsetospeed(options, B57600); + break; + case 115200: + cfsetispeed(options, B115200); + cfsetospeed(options, B115200); + break; + case 230400: + cfsetispeed(options, B230400); + cfsetospeed(options, B230400); + break; + case 460800: + cfsetispeed(options, B460800); + cfsetospeed(options, B460800); + break; + default: + sif::debug << "UartComIF::configureBaudrate: Baudrate not supported" << std::endl; + break; + } +} + +ReturnValue_t UartComIF::sendMessage(CookieIF *cookie, + const uint8_t *sendData, size_t sendLen) { + + int fd; + std::string deviceFile; + UartDeviceMapIter uartDeviceMapIter; + + if(sendData == nullptr) { + sif::debug << "UartComIF::sendMessage: Send Data is nullptr" << std::endl; + return RETURN_FAILED; + } + + if(sendLen == 0) { + return RETURN_OK; + } + + UartCookie* uartCookie = dynamic_cast(cookie); + if(uartCookie == nullptr) { + sif::debug << "UartComIF::sendMessasge: Invalid Uart Cookie!" << std::endl; + return NULLPOINTER; + } + + deviceFile = uartCookie->getDeviceFile(); + uartDeviceMapIter = uartDeviceMap.find(deviceFile); + if (uartDeviceMapIter == uartDeviceMap.end()) { + sif::debug << "UartComIF::sendMessage: Device file " << deviceFile << "not in uart map" + << std::endl; + return RETURN_FAILED; + } + + fd = uartDeviceMapIter->second.fileDescriptor; + + if (write(fd, sendData, sendLen) != (int)sendLen) { + sif::error << "UartComIF::sendMessage: Failed to send data with error code " << errno + << ": Error description: " << strerror(errno) << std::endl; + return RETURN_FAILED; + } + + return RETURN_OK; +} + +ReturnValue_t UartComIF::getSendSuccess(CookieIF *cookie) { + return RETURN_OK; +} + +ReturnValue_t UartComIF::requestReceiveMessage(CookieIF *cookie, + size_t requestLen) { + + int fd; + std::string deviceFile; + UartDeviceMapIter uartDeviceMapIter; + uint8_t* bufferPtr; + + if(requestLen == 0) { + return RETURN_OK; + } + + UartCookie* uartCookie = dynamic_cast(cookie); + if(uartCookie == nullptr) { + sif::debug << "UartComIF::requestReceiveMessage: Invalid Uart Cookie!" << std::endl; + return NULLPOINTER; + } + + deviceFile = uartCookie->getDeviceFile(); + uartDeviceMapIter = uartDeviceMap.find(deviceFile); + if (uartDeviceMapIter == uartDeviceMap.end()) { + sif::debug << "UartComIF::requestReceiveMessage: Device file " << deviceFile + << " not in uart map" << std::endl; + return RETURN_FAILED; + } + + fd = uartDeviceMapIter->second.fileDescriptor; + bufferPtr = uartDeviceMapIter->second.replyBuffer.data(); + int bytesRead = read(fd, bufferPtr, requestLen); + if (bytesRead != static_cast(requestLen)) { + sif::debug << "UartComIF::requestReceiveMessage: Only read " << bytesRead + << " of " << requestLen << " bytes" << std::endl; + return RETURN_FAILED; + } + else { + uartDeviceMapIter->second.replyLen = bytesRead; + } + + return RETURN_OK; +} + +ReturnValue_t UartComIF::readReceivedMessage(CookieIF *cookie, + uint8_t **buffer, size_t* size) { + + std::string deviceFile; + UartDeviceMapIter uartDeviceMapIter; + + UartCookie* uartCookie = dynamic_cast(cookie); + if(uartCookie == nullptr) { + sif::debug << "UartComIF::readReceivedMessage: Invalid uart cookie!" << std::endl; + return NULLPOINTER; + } + + deviceFile = uartCookie->getDeviceFile(); + uartDeviceMapIter = uartDeviceMap.find(deviceFile); + if (uartDeviceMapIter == uartDeviceMap.end()) { + sif::debug << "UartComIF::readReceivedMessage: Device file " << deviceFile + << " not in uart map" << std::endl; + return RETURN_FAILED; + } + + *buffer = uartDeviceMapIter->second.replyBuffer.data(); + *size = uartDeviceMapIter->second.replyLen; + + return RETURN_OK; +} + diff --git a/linux/uart/UartComIF.h b/linux/uart/UartComIF.h new file mode 100644 index 00000000..9dd854da --- /dev/null +++ b/linux/uart/UartComIF.h @@ -0,0 +1,94 @@ +#ifndef BSP_Q7S_COMIF_UARTCOMIF_H_ +#define BSP_Q7S_COMIF_UARTCOMIF_H_ + +#include +#include + +#include +#include + +#include "UartCookie.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 UartComIF: public DeviceCommunicationIF, public SystemObject { +public: + UartComIF(object_id_t objectId); + + virtual ~UartComIF(); + + ReturnValue_t initializeInterface(CookieIF * cookie) override; + ReturnValue_t sendMessage(CookieIF *cookie,const uint8_t *sendData, + size_t sendLen) override; + ReturnValue_t getSendSuccess(CookieIF *cookie) override; + ReturnValue_t requestReceiveMessage(CookieIF *cookie, + size_t requestLen) override; + ReturnValue_t readReceivedMessage(CookieIF *cookie, uint8_t **buffer, + size_t *size) override; + +private: + + using UartDeviceFile_t = std::string; + + typedef struct UartElements { + int fileDescriptor; + std::vector replyBuffer; + /** Number of bytes read will be written to this variable */ + size_t replyLen; + } UartElements_t; + + using UartDeviceMap = std::unordered_map; + using UartDeviceMapIter = UartDeviceMap::iterator; + + /** + * The uart devie map stores informations of initialized uart ports. + */ + UartDeviceMap uartDeviceMap; + + /** + * @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(UartCookie* uartCookie); + + /** + * @brief This function adds the parity settings to the termios options struct. + * + * @param options Pointer to termios options struct which will be modified to enable or disable + * parity checking. + * @param uartCookie Pointer to uart cookie containing the information about the desired + * parity settings. + * + */ + void setParityOptions(struct termios* options, UartCookie* uartCookie); + + void setStopBitOptions(struct termios* options, UartCookie* uartCookie); + + /** + * @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, UartCookie* uartCookie); + + /** + * @brief This functions adds the baudrate specified in the uartCookie to the termios options + * struct. + */ + void configureBaudrate(struct termios* options, UartCookie* uartCookie); +}; + +#endif /* BSP_Q7S_COMIF_UARTCOMIF_H_ */ diff --git a/linux/uart/UartCookie.cpp b/linux/uart/UartCookie.cpp new file mode 100644 index 00000000..b8149388 --- /dev/null +++ b/linux/uart/UartCookie.cpp @@ -0,0 +1,63 @@ +#include "UartCookie.h" + +#include + +UartCookie::UartCookie(std::string deviceFile, uint32_t baudrate, size_t maxReplyLen) : + deviceFile(deviceFile), baudrate(baudrate), maxReplyLen(maxReplyLen) { +} + +UartCookie::~UartCookie() {} + +uint32_t UartCookie::getBaudrate() const { + return baudrate; +} + +size_t UartCookie::getMaxReplyLen() const { + return maxReplyLen; +} + +std::string UartCookie::getDeviceFile() const { + return deviceFile; +} + +void UartCookie::setParityOdd() { + parity = Parity::ODD; +} + +void UartCookie::setParityEven() { + parity = Parity::EVEN; +} + +Parity UartCookie::getParity() const { + return parity; +} + +void UartCookie::setBitsPerWord(uint8_t bitsPerWord_) { + switch(bitsPerWord_) { + case 5: + case 6: + case 7: + case 8: + break; + default: + sif::debug << "UartCookie::setBitsPerWord: Invalid bits per word specified" << std::endl; + return; + } + bitsPerWord = bitsPerWord_; +} + +uint8_t UartCookie::getBitsPerWord() const { + return bitsPerWord; +} + +StopBits UartCookie::getStopBits() const { + return stopBits; +} + +void UartCookie::setTwoStopBits() { + stopBits = StopBits::TWO_STOP_BITS; +} + +void UartCookie::setOneStopBit() { + stopBits = StopBits::ONE_STOP_BIT; +} diff --git a/linux/uart/UartCookie.h b/linux/uart/UartCookie.h new file mode 100644 index 00000000..59004719 --- /dev/null +++ b/linux/uart/UartCookie.h @@ -0,0 +1,81 @@ +#ifndef SAM9G20_COMIF_COOKIES_UART_COOKIE_H_ +#define SAM9G20_COMIF_COOKIES_UART_COOKIE_H_ + +#include +#include + +enum class Parity { + NONE, + EVEN, + ODD +}; + +enum class StopBits { + ONE_STOP_BIT, + TWO_STOP_BITS +}; + +/** + * @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 UartCookie: public CookieIF { +public: + + /** + * @brief Constructor for the uart cookie. + * @param deviceFile The device file specifying the uart to use. E.g. "/dev/ttyPS1". + * @param baudrate The baudrate to use for input and output. Possible Baudrates are: 50, + * 75, 110, 134, 150, 200, 300, 600, 1200, 1800, 2400, 4800, 9600, B19200, + * 38400, 57600, 115200, 230400, 460800 + * @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 + * + * + */ + UartCookie(std::string deviceFile, uint32_t baudrate, size_t maxReplyLen); + + virtual ~UartCookie(); + + uint32_t getBaudrate() const; + size_t getMaxReplyLen() const; + std::string getDeviceFile() const; + Parity getParity() const; + uint8_t getBitsPerWord() const; + StopBits getStopBits() const; + + /** + * Functions two enable parity checking. + */ + void setParityOdd(); + void setParityEven(); + + /** + * Function two set number of bits per UART frame. + */ + void setBitsPerWord(uint8_t bitsPerWord_); + + /** + * Function to specify the number of stopbits. + */ + void setTwoStopBits(); + void setOneStopBit(); + + +private: + + std::string deviceFile; + uint32_t baudrate; + size_t maxReplyLen = 0; + Parity parity = Parity::NONE; + uint8_t bitsPerWord = 8; + StopBits stopBits = StopBits::ONE_STOP_BIT; +}; + +#endif diff --git a/mission/devices/SyrlinksHkHandler.cpp b/mission/devices/SyrlinksHkHandler.cpp index a13c0286..60dc439c 100644 --- a/mission/devices/SyrlinksHkHandler.cpp +++ b/mission/devices/SyrlinksHkHandler.cpp @@ -1,9 +1,10 @@ #include #include #include +#include SyrlinksHkHandler::SyrlinksHkHandler(object_id_t objectId, object_id_t comIF, CookieIF * comCookie) : - DeviceHandlerBase(objectId, comIF, comCookie), rxStatusRegistersSet(this) { + DeviceHandlerBase(objectId, comIF, comCookie), rxDataset(this), txDataset(this) { if (comCookie == NULL) { sif::error << "SyrlinksHkHandler: Invalid com cookie" << std::endl; } @@ -25,7 +26,7 @@ void SyrlinksHkHandler::doShutDown(){ ReturnValue_t SyrlinksHkHandler::buildNormalDeviceCommand( DeviceCommandId_t * id) { - *id = READ_RX_STATUS_REGISTERS; + *id = SYRLINKS::READ_RX_STATUS_REGISTERS; return buildCommandFromCommand(*id, NULL, 0); } @@ -39,33 +40,40 @@ ReturnValue_t SyrlinksHkHandler::buildCommandFromCommand( size_t commandDataLen) { switch(deviceCommand) { case(SYRLINKS::RESET_UNIT): { - resetCommand.copy(rawPacket, resetCommand.size(), 0); + resetCommand.copy(reinterpret_cast(commandBuffer), resetCommand.size(), 0); rawPacketLen = resetCommand.size(); - rememberCommandId = SYRLINKS::RESET_UNIT; + rawPacket = commandBuffer; return RETURN_OK; } case(SYRLINKS::SET_TX_MODE_STANDBY): { - setTxModeStandby.copy(rawPacket, setTxModeStandby.size(), 0); + setTxModeStandby.copy(reinterpret_cast(commandBuffer), setTxModeStandby.size(), 0); rawPacketLen = setTxModeStandby.size(); - rememberCommandId = SYRLINKS::SET_TX_MODE_STANDBY; + rawPacket = commandBuffer; return RETURN_OK; } case(SYRLINKS::SET_TX_MODE_MODULATION): { - setTxModeModulation.copy(rawPacket, setTxModeModulation.size(), 0); + setTxModeModulation.copy(reinterpret_cast(commandBuffer), setTxModeModulation.size(), 0); rawPacketLen = setTxModeModulation.size(); - rememberCommandId = SYRLINKS::SET_TX_MODE_MODULATION; + rawPacket = commandBuffer; return RETURN_OK; } case(SYRLINKS::SET_TX_MODE_CW): { - setTxModeCw.copy(rawPacket, setTxModeCw.size(), 0); + setTxModeCw.copy(reinterpret_cast(commandBuffer), setTxModeCw.size(), 0); rawPacketLen = setTxModeCw.size(); - rememberCommandId = SYRLINKS::SET_TX_MODE_CW; + rawPacket = commandBuffer; return RETURN_OK; } case(SYRLINKS::READ_RX_STATUS_REGISTERS): { - readRxStatusRegCommand.copy(rawPacket, readRxStatusRegCommand.size(), 0); + readRxStatusRegCommand.copy(reinterpret_cast(commandBuffer), readRxStatusRegCommand.size(), 0); rawPacketLen = readRxStatusRegCommand.size(); - rememberCommandId = SYRLINKS::READ_RX_STATUS_REGISTERS; + rawPacket = commandBuffer; + return RETURN_OK; + } + case(SYRLINKS::READ_TX_STATUS): { + readTxStatus.copy(reinterpret_cast(commandBuffer), readTxStatus.size(), 0); + rawPacketLen = readTxStatus.size(); + rememberCommandId = SYRLINKS::READ_TX_STATUS; + rawPacket = commandBuffer; return RETURN_OK; } default: @@ -75,11 +83,17 @@ ReturnValue_t SyrlinksHkHandler::buildCommandFromCommand( } void SyrlinksHkHandler::fillCommandAndReplyMap() { - this->insertInCommandAndReplyMap(SYRLINKS::RESET_UNIT); - this->insertInCommandAndReplyMap(SYRLINKS::SET_TX_MODE_STANDBY); - this->insertInCommandAndReplyMap(SYRLINKS::SET_TX_MODE_MODULATION); - this->insertInCommandAndReplyMap(SYRLINKS::SET_TX_MODE_CW); - this->insertInCommandAndReplyMap(SYRLINKS::READ_RX_STATUS_REGISTERS, 1, &rxStatusRegistersSet, + this->insertInCommandAndReplyMap(SYRLINKS::RESET_UNIT, 1, nullptr, SYRLINKS::ACK_SIZE, false, + true, SYRLINKS::ACK_REPLY); + this->insertInCommandAndReplyMap(SYRLINKS::SET_TX_MODE_STANDBY, 1, nullptr, SYRLINKS::ACK_SIZE, + false, true, SYRLINKS::ACK_REPLY); + this->insertInCommandAndReplyMap(SYRLINKS::SET_TX_MODE_MODULATION, 1, nullptr, + SYRLINKS::ACK_SIZE, false, true, SYRLINKS::ACK_REPLY); + this->insertInCommandAndReplyMap(SYRLINKS::SET_TX_MODE_CW, 1, nullptr, SYRLINKS::ACK_SIZE, + false, true, SYRLINKS::ACK_REPLY); + this->insertInCommandAndReplyMap(SYRLINKS::READ_TX_STATUS, 1, &txDataset, + SYRLINKS::READ_TX_STATUS); + this->insertInCommandAndReplyMap(SYRLINKS::READ_RX_STATUS_REGISTERS, 1, &rxDataset, SYRLINKS::RX_STATUS_REGISTERS_REPLY_SIZE); } @@ -88,59 +102,33 @@ ReturnValue_t SyrlinksHkHandler::scanForReply(const uint8_t *start, ReturnValue_t result = RETURN_OK; - switch(rememberCommandId) { - case(SYRLINKS::RESET_UNIT): - if (remainingSize != SYRLINKS::REQUEST_STATUS_REPLY_SIZE) { - result = REPLY_WRONG_SIZE; - break; - } - *foundLen = SYRLINKS::REQUEST_STATUS_REPLY_SIZE; - *foundId = SYRLINKS::RESET_UNIT; - rememberCommandId = SYRLINKS::NONE; + if(*start != '<') { + sif::error << "SyrlinksHkHandler::scanForReply: Missing start frame character" << std::endl; + return MISSING_START_FRAME_CHARACTER; + } + + switch(*(start + 1)) { + case('A'): + *foundLen = SYRLINKS::ACK_SIZE; + *foundId = SYRLINKS::ACK_REPLY; break; - case(SYRLINKS::SET_TX_MODE_STANDBY): - if (remainingSize != SYRLINKS::REQUEST_STATUS_REPLY_SIZE) { - result = REPLY_WRONG_SIZE; - } - *foundLen = SYRLINKS::REQUEST_STATUS_REPLY_SIZE; - rememberCommandId = SYRLINKS::NONE; - *foundId = SYRLINKS::SET_TX_MODE_STANDBY; - break; - case(SYRLINKS::SET_TX_MODE_MODULATION): - if (remainingSize != SYRLINKS::REQUEST_STATUS_REPLY_SIZE) { - result = REPLY_WRONG_SIZE; - } - *foundLen = SYRLINKS::REQUEST_STATUS_REPLY_SIZE; - *foundId = SYRLINKS::SET_TX_MODE_MODULATION; - rememberCommandId = SYRLINKS::NONE; - break; - case(SYRLINKS::SET_TX_MODE_CW): - if (remainingSize != SYRLINKS::REQUEST_STATUS_REPLY_SIZE) { - result = REPLY_WRONG_SIZE; - } - *foundLen = SYRLINKS::REQUEST_STATUS_REPLY_SIZE; - *foundId = SYRLINKS::SET_TX_MODE_CW; - rememberCommandId = SYRLINKS::NONE; - break; - case(SYRLINKS::READ_RX_STATUS_REGISTERS): - if (remainingSize != SYRLINKS::RX_STATUS_REGISTERS_REPLY_SIZE) { - result = REPLY_WRONG_SIZE; - } + case('E'): *foundLen = SYRLINKS::RX_STATUS_REGISTERS_REPLY_SIZE; *foundId = SYRLINKS::READ_RX_STATUS_REGISTERS; - rememberCommandId = SYRLINKS::NONE; + break; + case('R'): + if (rememberCommandId == SYRLINKS::READ_TX_STATUS) { + *foundLen = SYRLINKS::READ_TX_STATUS_REPLY_SIZE; + *foundId = SYRLINKS::READ_TX_STATUS; + rememberCommandId = SYRLINKS::NONE; + } break; default: + sif::error << "SyrlinksHkHandler::scanForReply: Unknown reply identifier" << std::endl; result = IGNORE_REPLY_DATA; break; } - if (result == REPLY_WRONG_SIZE) { - sif::debug << "SyrlinksHkHandler::scanForReply: Received reply with invalid length" - << std::endl; - return result; - } - return result; } @@ -150,53 +138,44 @@ ReturnValue_t SyrlinksHkHandler::interpretDeviceReply(DeviceCommandId_t id, ReturnValue_t result; switch (id) { - case (SYRLINKS::RESET_UNIT): - case (SYRLINKS::SET_TX_MODE_STANDBY): - case (SYRLINKS::SET_TX_MODE_MODULATION): - case (SYRLINKS::SET_TX_MODE_CW): - result = verifyTansmissionStatusReply(packet); + case (SYRLINKS::ACK_REPLY): + result = verifyReply(packet, SYRLINKS::ACK_SIZE); if (result != RETURN_OK) { - sif::debug << "SyrlinksHkHandler::interpretDeviceReply: Status reply has invalid crc" - << std::endl; + sif::error << "SyrlinksHkHandler::interpretDeviceReply: Acknowledgement reply has " + "invalid crc" << std::endl; return CRC_FAILURE; } - result = parseReplyStatus(static_cast(packet + SYRLINKS::MESSAGE_HEADER_SIZE)); + result = parseReplyStatus(reinterpret_cast(packet + SYRLINKS::MESSAGE_HEADER_SIZE)); if (result != RETURN_OK) { return result; } break; case(SYRLINKS::READ_RX_STATUS_REGISTERS): - result = verifyReadRxStatusRegistersReply(packet); + result = verifyReply(packet, SYRLINKS::RX_STATUS_REGISTERS_REPLY_SIZE); if (result != RETURN_OK) { - sif::debug << "SyrlinksHkHandler::interpretDeviceReply: Read rx status registers reply " + sif::error << "SyrlinksHkHandler::interpretDeviceReply: Read rx status registers reply " << "has invalid crc" << std::endl; return CRC_FAILURE; } - + parseRxStatusRegistersReply(packet); + break; + case(SYRLINKS::READ_TX_STATUS): + result = verifyReply(packet, SYRLINKS::READ_TX_STATUS_REPLY_SIZE); + if (result != RETURN_OK) { + sif::error << "SyrlinksHkHandler::interpretDeviceReply: Read tx status reply " + << "has invalid crc" << std::endl; + return CRC_FAILURE; + } + parseTxStatusReply(packet); break; default: { + sif::debug << "SyrlinksHkHandler::interpretDeviceReply: Unknown device reply id" + << std::endl; return DeviceHandlerIF::UNKNOWN_DEVICE_REPLY; } - } - return HasReturnvaluesIF::RETURN_OK; -} - -ReturnValue_t SyrlinksHkHandler::verifyTansmissionStatusReply() { - int result = 0; - uint16_t crc = CRC::crc16ccitt(packet, - SYRLINKS::REQUEST_STATUS_REPLY_SIZE - SYRLINKS::SIZE_CRC_AND_TERMINATION, - CRC_INITIAL_VALUE); - std::string recalculatedCrc = convertIntToHexString(crc); - const char* replyCrc = packet + SYRLINKS::REQUEST_STATUS_REPLY_SIZE - - SYRLINKS::SIZE_CRC_AND_TERMINATION; - size_t startPosition = 0; - result = recalculatedCrc.compare(startPosition, SYRLINKS_CRC_FIELD_SIZE, replyCrc); - if (result != 0) { - return RETURN_FAILED; - } - return RETURN_OK; + return RETURN_OK; } std::string SyrlinksHkHandler::convertIntToHexString(uint16_t intValue) { @@ -205,7 +184,7 @@ std::string SyrlinksHkHandler::convertIntToHexString(uint16_t intValue) { return stream.str(); } -ReturnValue_t SyrlinksHkHandler::parseReplyStatus(char* status) { +ReturnValue_t SyrlinksHkHandler::parseReplyStatus(const char* status) { switch (*status) { case '0': return RETURN_OK; @@ -231,29 +210,54 @@ ReturnValue_t SyrlinksHkHandler::parseReplyStatus(char* status) { sif::debug << "SyrlinksHkHandler::parseReplyStatus: Bad CRC" << std::endl; return BAD_CRC_ACK; default: - sif::debug << "SyrlinksHkHandler::parseReplyStatus: Status reply holds invalid status " - << "id" << std::endl; + sif::debug << "SyrlinksHkHandler::parseReplyStatus: Status reply contains an invalid " + << "status id" << std::endl; return RETURN_FAILED; } } -ReturnValue_t SyrlinksHkHandler::verifyReadRxStatusRegistersReply(uint8_t* packet) { +ReturnValue_t SyrlinksHkHandler::verifyReply(const uint8_t* packet, uint8_t size) { int result = 0; /* Calculate crc of received packet */ - uint16_t crc = CRC::crc16ccitt(packet, - SYRLINKS::RX_STATUS_REGISTERS_REPLY_SIZE - SYRLINKS::SIZE_CRC_AND_TERMINATION, + uint16_t crc = CRC::crc16ccitt(packet, size - SYRLINKS::SIZE_CRC_AND_TERMINATION, CRC_INITIAL_VALUE); std::string recalculatedCrc = convertIntToHexString(crc); - const char* replyCrc = packet + SYRLINKS::RX_STATUS_REGISTERS_REPLY_SIZE - - SYRLINKS::SIZE_CRC_AND_TERMINATION; + const char* replyCrc = reinterpret_cast(packet) + size - SYRLINKS::SIZE_CRC_AND_TERMINATION; size_t startPosition = 0; - result = recalculatedCrc.compare(startPosition, SYRLINKS_CRC_FIELD_SIZE, replyCrc); + result = recalculatedCrc.compare(startPosition, SYRLINKS::CRC_FIELD_SIZE, replyCrc); if (result != 0) { return RETURN_FAILED; } return RETURN_OK; } +void SyrlinksHkHandler::parseRxStatusRegistersReply(const uint8_t* packet) { + PoolReadHelper readHelper(&rxDataset); + uint16_t offset = SYRLINKS::MESSAGE_HEADER_SIZE; + rxDataset.rxStatus = *(packet + offset); + packet += 1; + rxDataset.rxSensitivity = *(packet + offset) << 16 | *(packet + offset + 1) << 8 | *(packet + offset + 2); + packet += 3; + rxDataset.rxFrequencyShift = *(packet + offset) << 16 | *(packet + offset + 1) << 8 | *(packet + offset + 2); + packet += 3; + rxDataset.rxIqPower = *(packet + offset) << 8 | *(packet + offset + 1); + packet += 2; + rxDataset.rxAgcValue = *(packet + offset + 1) << 8 | *(packet + offset); + packet += 2; + packet += 1; // reserved register + rxDataset.rxDemodEb= *(packet + offset) << 16 | *(packet + offset + 1) << 8 | *(packet + offset + 2); + packet += 3; + rxDataset.rxDemodN0= *(packet + offset) << 16 | *(packet + offset + 1) << 8 | *(packet + offset + 2); + packet += 3; + rxDataset.rxDataRate = *(packet + offset); +} + +void SyrlinksHkHandler::parseTxStatusReply(const uint8_t* packet) { + PoolReadHelper readHelper(&txDataset); + uint16_t offset = SYRLINKS::MESSAGE_HEADER_SIZE; + rxDataset.rxStatus = *(packet + offset); +} + void SyrlinksHkHandler::setNormalDatapoolEntriesInvalid(){ } @@ -264,7 +268,20 @@ uint32_t SyrlinksHkHandler::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) ReturnValue_t SyrlinksHkHandler::initializeLocalDataPool(localpool::DataPool& localDataPoolMap, LocalDataPoolManager& poolManager) { - localDataPoolMap.emplace(TMP1075::TEMPERATURE_C_TMP1075_1, new PoolEntry( { 0.0 })); + + localDataPoolMap.emplace(SYRLINKS::RX_STATUS, new PoolEntry( { 0 })); + localDataPoolMap.emplace(SYRLINKS::RX_SENSITIVITY, new PoolEntry( { 0 })); + localDataPoolMap.emplace(SYRLINKS::RX_FREQUENCY_SHIFT, new PoolEntry( { 0 })); + localDataPoolMap.emplace(SYRLINKS::RX_IQ_POWER, new PoolEntry( { 0 })); + localDataPoolMap.emplace(SYRLINKS::RX_AGC_VALUE, new PoolEntry( { 0 })); + localDataPoolMap.emplace(SYRLINKS::RX_DEMOD_EB, new PoolEntry( { 0 })); + localDataPoolMap.emplace(SYRLINKS::RX_DEMOD_N0, new PoolEntry( { 0 })); + localDataPoolMap.emplace(SYRLINKS::RX_DATA_RATE, new PoolEntry( { 0 })); + return HasReturnvaluesIF::RETURN_OK; } +void SyrlinksHkHandler::setModeNormal() { + mode = MODE_NORMAL; +} + diff --git a/mission/devices/SyrlinksHkHandler.h b/mission/devices/SyrlinksHkHandler.h index aefc99f9..23a48c13 100644 --- a/mission/devices/SyrlinksHkHandler.h +++ b/mission/devices/SyrlinksHkHandler.h @@ -3,7 +3,7 @@ #include #include -#include +#include /** * @brief This is the device handler for the syrlinks transceiver. It handles the command @@ -20,6 +20,11 @@ public: CookieIF * comCookie); virtual ~SyrlinksHkHandler(); + /** + * @brief Sets mode to MODE_NORMAL. Can be used for debugging. + */ + void setModeNormal(); + protected: void doStartUp() override; void doShutDown() override; @@ -49,6 +54,7 @@ private: static const ReturnValue_t UNKNOWN_COMMAND_ID_ACK = MAKE_RETURN_CODE(0xA5); static const ReturnValue_t BAD_CRC_ACK = MAKE_RETURN_CODE(0xA6); static const ReturnValue_t REPLY_WRONG_SIZE = MAKE_RETURN_CODE(0xA7); + static const ReturnValue_t MISSING_START_FRAME_CHARACTER = MAKE_RETURN_CODE(0xA8); static const uint8_t CRC_INITIAL_VALUE = 0x0; @@ -58,29 +64,18 @@ private: /** W - write, 04 - 4 bytes in data field, 01 - value, 40 register to write value */ std::string setTxModeModulation = ""; std::string setTxModeCw = ""; - - SYRLINKS::RxStatusRegistersDataset rxStatusRegistersSet; - - static const uint8_t MAX_CMD_LEN = 3; - - uint8_t rememberRequestedSize = 0; - uint8_t rememberCommandId = SYRLINKS::NONE; - uint8_t cmdBuffer[MAX_CMD_LEN]; - CommunicationStep communicationStep = - CommunicationStep::START_ADC_CONVERSION; - + std::string readTxStatus = ""; /** - * @brief This function verifies the checksum of a status reply packet of the syrlinks. - * - * @param packet Pointer to the received status reply. - * - * @return RETURN_OK if successful, otherwise RETURN_FAILURE. - * - * @details A status reply only contains one byte of payload data giving information about - * the transmission status. + * In some cases it is not possible to extract from the received reply the information about + * the associated command. This variable is thus used to remember the command id. */ - ReturnValue_t verifyTansmissionStatusReply(const uint8_t* packet); + DeviceCommandId_t rememberCommandId = SYRLINKS::NONE; + + SYRLINKS::RxDataset rxDataset; + SYRLINKS::TxDataset txDataset; + + uint8_t commandBuffer[SYRLINKS::MAX_COMMAND_SIZE]; /** * @brief This function converts an uint16_t into its hexadecimal string representation. @@ -89,7 +84,7 @@ private: * * @return An std::string object containing the hex representation of intValue. */ - std::string SyrlinksHkHandler::convertIntToHexString(uint16_t intValue); + std::string convertIntToHexString(uint16_t intValue); /** * @brief This function parses the status reply @@ -98,17 +93,32 @@ private: * @details Some commands reply with a status message giving information about the preceding * command transmission and/or execution was successful. */ - ReturnValue_t parseReplyStatus(char* status); + ReturnValue_t parseReplyStatus(const char* status); /** * @brief Function verifies the received reply from the syrlinks by recalculating and * comparing the crc. * * @param packet Pointer to the received reply. + * @param size Size of the whole packet including the crc and the packet termination + * character '>'. * * @return RETURN_OK if successful, otherwise RETURN_FAILED. */ - ReturnValue_t verifyReadRxStatusRegistersReply(uint8_t* packet) + ReturnValue_t verifyReply(const uint8_t* packet, uint8_t size); + + /** + * @brief This function extracts the data from a rx status registers reply and writes the + * information to the status registers dataset. + * @param packet Pointer to the reply packet. + */ + void parseRxStatusRegistersReply(const uint8_t* packet); + + /** + * @brief This function writes the read tx status register to the txStatusDataset. + * @param packet Pointer to the received packet. + */ + void parseTxStatusReply(const uint8_t* packet); }; #endif /* MISSION_DEVICES_SYRLINKSHKHANDLER_H_ */ diff --git a/mission/devices/crc/crc_ccitt_Syrlinks.cpp b/mission/devices/crc/crc_ccitt_Syrlinks.cpp deleted file mode 100644 index cb1e867d..00000000 --- a/mission/devices/crc/crc_ccitt_Syrlinks.cpp +++ /dev/null @@ -1,58 +0,0 @@ -#include "crc_ccitt_Syrlinks.h" -#include -#include - -static const uint16_t crc_table[256] = { - 0x0000, 0x1021, 0x2042, 0x3063, 0x4084, 0x50a5, 0x60c6, 0x70e7, - 0x8108, 0x9129, 0xa14a, 0xb16b, 0xc18c, 0xd1ad, 0xe1ce, 0xf1ef, - 0x1231, 0x0210, 0x3273, 0x2252, 0x52b5, 0x4294, 0x72f7, 0x62d6, - 0x9339, 0x8318, 0xb37b, 0xa35a, 0xd3bd, 0xc39c, 0xf3ff, 0xe3de, - 0x2462, 0x3443, 0x0420, 0x1401, 0x64e6, 0x74c7, 0x44a4, 0x5485, - 0xa56a, 0xb54b, 0x8528, 0x9509, 0xe5ee, 0xf5cf, 0xc5ac, 0xd58d, - 0x3653, 0x2672, 0x1611, 0x0630, 0x76d7, 0x66f6, 0x5695, 0x46b4, - 0xb75b, 0xa77a, 0x9719, 0x8738, 0xf7df, 0xe7fe, 0xd79d, 0xc7bc, - 0x48c4, 0x58e5, 0x6886, 0x78a7, 0x0840, 0x1861, 0x2802, 0x3823, - 0xc9cc, 0xd9ed, 0xe98e, 0xf9af, 0x8948, 0x9969, 0xa90a, 0xb92b, - 0x5af5, 0x4ad4, 0x7ab7, 0x6a96, 0x1a71, 0x0a50, 0x3a33, 0x2a12, - 0xdbfd, 0xcbdc, 0xfbbf, 0xeb9e, 0x9b79, 0x8b58, 0xbb3b, 0xab1a, - 0x6ca6, 0x7c87, 0x4ce4, 0x5cc5, 0x2c22, 0x3c03, 0x0c60, 0x1c41, - 0xedae, 0xfd8f, 0xcdec, 0xddcd, 0xad2a, 0xbd0b, 0x8d68, 0x9d49, - 0x7e97, 0x6eb6, 0x5ed5, 0x4ef4, 0x3e13, 0x2e32, 0x1e51, 0x0e70, - 0xff9f, 0xefbe, 0xdfdd, 0xcffc, 0xbf1b, 0xaf3a, 0x9f59, 0x8f78, - 0x9188, 0x81a9, 0xb1ca, 0xa1eb, 0xd10c, 0xc12d, 0xf14e, 0xe16f, - 0x1080, 0x00a1, 0x30c2, 0x20e3, 0x5004, 0x4025, 0x7046, 0x6067, - 0x83b9, 0x9398, 0xa3fb, 0xb3da, 0xc33d, 0xd31c, 0xe37f, 0xf35e, - 0x02b1, 0x1290, 0x22f3, 0x32d2, 0x4235, 0x5214, 0x6277, 0x7256, - 0xb5ea, 0xa5cb, 0x95a8, 0x8589, 0xf56e, 0xe54f, 0xd52c, 0xc50d, - 0x34e2, 0x24c3, 0x14a0, 0x0481, 0x7466, 0x6447, 0x5424, 0x4405, - 0xa7db, 0xb7fa, 0x8799, 0x97b8, 0xe75f, 0xf77e, 0xc71d, 0xd73c, - 0x26d3, 0x36f2, 0x0691, 0x16b0, 0x6657, 0x7676, 0x4615, 0x5634, - 0xd94c, 0xc96d, 0xf90e, 0xe92f, 0x99c8, 0x89e9, 0xb98a, 0xa9ab, - 0x5844, 0x4865, 0x7806, 0x6827, 0x18c0, 0x08e1, 0x3882, 0x28a3, - 0xcb7d, 0xdb5c, 0xeb3f, 0xfb1e, 0x8bf9, 0x9bd8, 0xabbb, 0xbb9a, - 0x4a75, 0x5a54, 0x6a37, 0x7a16, 0x0af1, 0x1ad0, 0x2ab3, 0x3a92, - 0xfd2e, 0xed0f, 0xdd6c, 0xcd4d, 0xbdaa, 0xad8b, 0x9de8, 0x8dc9, - 0x7c26, 0x6c07, 0x5c64, 0x4c45, 0x3ca2, 0x2c83, 0x1ce0, 0x0cc1, - 0xef1f, 0xff3e, 0xcf5d, 0xdf7c, 0xaf9b, 0xbfba, 0x8fd9, 0x9ff8, - 0x6e17, 0x7e36, 0x4e55, 0x5e74, 0x2e93, 0x3eb2, 0x0ed1, 0x1ef0 -}; - - -// CRC implementation -uint16_t Calculate_CRC_Syrlinks(uint8_t const input[], uint32_t length) -{ - uint16_t crc = 0x0000; - uint8_t *data = (uint8_t *)input; - unsigned int tbl_idx; - - while (length--) { - tbl_idx = ((crc >> 8) ^ *data) & 0xff; - crc = (crc_table[tbl_idx] ^ (crc << 8)) & 0xffff; - - data++; - } - return crc & 0xffff; - -} /* Calculate_CRC() */ - - diff --git a/mission/devices/crc/crc_ccitt_Syrlinks.h b/mission/devices/crc/crc_ccitt_Syrlinks.h deleted file mode 100644 index 8b952ee8..00000000 --- a/mission/devices/crc/crc_ccitt_Syrlinks.h +++ /dev/null @@ -1,23 +0,0 @@ -#ifndef CRC_CCITT_Syrlinks_H_ -#define CRC_CCITT_Syrlinks_H_ - -#include - -/** - * @brief With this function the CRC16-CCITT over a data packet can be calculated. - * - * @param input Pointer to data over which the crc shall be calculated. - * @param length Size of data packet. - * - * @return The 16-bit wide crc calculated over the data packet. - * - * @details Wide: 16 bits - * Generator polynomial: 0x1021 - * Bit order: MSB - * Initial value: 0 - * @author Bucher, J. Meier - */ -uint16_t Calculate_CRC_Syrlinks(uint8_t const input[], uint32_t length); - - -#endif /* CRC_H_ */ diff --git a/mission/devices/devicedefinitions/SyrlinksDefinitions.h b/mission/devices/devicedefinitions/SyrlinksDefinitions.h index 2cd159af..5ab82a0c 100644 --- a/mission/devices/devicedefinitions/SyrlinksDefinitions.h +++ b/mission/devices/devicedefinitions/SyrlinksDefinitions.h @@ -1,10 +1,3 @@ -/* - * SyrlinksDefinitions.h - * - * Created on: 18.02.2021 - * Author: jakob - */ - #ifndef MISSION_DEVICES_DEVICEDEFINITIONS_SYRLINKSDEFINITIONS_H_ #define MISSION_DEVICES_DEVICEDEFINITIONS_SYRLINKSDEFINITIONS_H_ @@ -21,34 +14,57 @@ namespace SYRLINKS { static const DeviceCommandId_t SET_TX_MODE_MODULATION = 0x04; /** Sends out a single carrier wave for testing purpose */ static const DeviceCommandId_t SET_TX_MODE_CW = 0x05; + static const DeviceCommandId_t ACK_REPLY = 0x06; + static const DeviceCommandId_t READ_TX_STATUS = 0x07; /** Size of a simple transmission success response */ - static const uint8_t REQUEST_STATUS_REPLY_SIZE = 11; + static const uint8_t ACK_SIZE = 11; static const uint8_t SIZE_CRC_AND_TERMINATION = 5; /** The size of the header with the message identifier and the payload size field */ static const uint8_t MESSAGE_HEADER_SIZE = 5; /** Size of reply to an rx status registers request */ - static const uint8_t RX_STATUS_REGISTERS_REPLY_SIZE = 39; + static const uint8_t RX_STATUS_REGISTERS_REPLY_SIZE = 30; + static const uint8_t READ_TX_STATUS_REPLY_SIZE = 13; - static const uint8_t RX_STATUS_REGISTERS_SET_ID = READ_RX_STATUS_REGISTERS; + static const uint8_t RX_DATASET_ID = READ_RX_STATUS_REGISTERS; + static const uint8_t TX_DATASET_ID = READ_TX_STATUS; -class RxStatusRegistersDataset: public StaticLocalDataSet { + static const size_t MAX_REPLY_SIZE = RX_STATUS_REGISTERS_REPLY_SIZE; + static const size_t MAX_COMMAND_SIZE = 15; + + static const size_t CRC_FIELD_SIZE = 4; + + static const uint8_t RX_DATASET_SIZE = 8; + static const uint8_t TX_DATASET_SIZE = 1; + + enum SyrlinksPoolIds: lp_id_t { + RX_STATUS, + RX_SENSITIVITY, + RX_FREQUENCY_SHIFT, + RX_IQ_POWER, + RX_AGC_VALUE, + RX_DEMOD_EB, + RX_DEMOD_N0, + RX_DATA_RATE, + TX_STATUS, + TX_CONV_DIFF, + TX_CONV_FILTER, + TX_WAVEFORM, + TX_PCM_INDEX, + TX_AGC_VALUE, + }; + +class RxDataset: public StaticLocalDataSet { public: - RxStatusRegistersDataset(HasLocalDataPoolIF* owner) : - StaticLocalDataSet(owner, RX_STATUS_REGISTERS_SET_ID) { + RxDataset(HasLocalDataPoolIF* owner) : + StaticLocalDataSet(owner, RX_DATASET_ID) { } - RxStatusRegistersDataset(object_id_t objectId) : - StaticLocalDataSet(sid_t(objectId, RX_STATUS_REGISTERS_SET_ID)) { + RxDataset(object_id_t objectId) : + StaticLocalDataSet(sid_t(objectId, RX_DATASET_ID)) { } - lp_var_t fpgaVersion = lp_var_t(sid.objectId, FPGA_VERSION, this); - lp_var_t fpgaBuild = lp_var_t(sid.objectId, FPGA_BUILD, this); - lp_var_t hardwareId = lp_var_t(sid.objectId, HARDWARE_ID, this); - lp_var_t fpgaType = lp_var_t(sid.objectId, FPGA_TYPE, this); - lp_var_t lclStatus = lp_var_t(sid.objectId, LCL_STATUS, this); - lp_var_t fpgaOption = lp_var_t(sid.objectId, FPGA_OPTION, this); lp_var_t rxStatus = lp_var_t(sid.objectId, RX_STATUS, this); lp_var_t rxSensitivity = lp_var_t(sid.objectId, RX_SENSITIVITY, this); lp_var_t rxFrequencyShift = lp_var_t(sid.objectId, RX_FREQUENCY_SHIFT, this); @@ -56,13 +72,22 @@ public: lp_var_t rxAgcValue = lp_var_t(sid.objectId, RX_AGC_VALUE, this); lp_var_t rxDemodEb = lp_var_t(sid.objectId, RX_DEMOD_EB, this); lp_var_t rxDemodN0 = lp_var_t(sid.objectId, RX_DEMOD_N0, this); - lp_var_t rxDataRate = lp_var_t(sid.objectId, RX_DEMOD_N0, this); + lp_var_t rxDataRate = lp_var_t(sid.objectId, RX_DATA_RATE, this); +}; + + +class TxDataset: public StaticLocalDataSet { +public: + + TxDataset(HasLocalDataPoolIF* owner) : + StaticLocalDataSet(owner, TX_DATASET_ID) { + } + + TxDataset(object_id_t objectId) : + StaticLocalDataSet(sid_t(objectId, TX_DATASET_ID)) { + } + lp_var_t txStatus = lp_var_t(sid.objectId, TX_STATUS, this); - lp_var_t txConvDiff = lp_var_t(sid.objectId, TX_CONV_DIFF, this); - lp_var_t txConvFilter = lp_var_t(sid.objectId, TX_CONV_FILTER, this); - lp_var_t txWaveform = lp_var_t(sid.objectId, TX_WAVEFORM, this); - lp_var_t txPcmIndex = lp_var_t(sid.objectId, TX_PCM_INDEX, this); - lp_var_t txAgcValue = lp_var_t(sid.objectId, TX_AGC_VALUE, this); }; } From 99780cdc62e76d467315ecebddb88114de6cd39f Mon Sep 17 00:00:00 2001 From: Martin Zietz Date: Thu, 25 Feb 2021 15:25:49 +0100 Subject: [PATCH 07/79] adapter size of rx registers reply --- bsp_q7s/ObjectFactory.cpp | 9 +++++---- etl | 2 +- fsfw | 2 +- mission/devices/devicedefinitions/SyrlinksDefinitions.h | 2 +- tmtc | 2 +- 5 files changed, 9 insertions(+), 8 deletions(-) diff --git a/bsp_q7s/ObjectFactory.cpp b/bsp_q7s/ObjectFactory.cpp index a97118f9..afe5ff9d 100644 --- a/bsp_q7s/ObjectFactory.cpp +++ b/bsp_q7s/ObjectFactory.cpp @@ -105,10 +105,11 @@ void ObjectFactory::produce(){ * Setting PCDU devices to mode normal immediately after start up because PCDU is always * running. */ - p60dockhandler->setModeNormal(); - pdu1handler->setModeNormal(); - pdu2handler->setModeNormal(); - acuhandler->setModeNormal(); + /** For now this needs to be commented out because there is no PCDU connected to the OBC */ +// p60dockhandler->setModeNormal(); +// pdu1handler->setModeNormal(); +// pdu2handler->setModeNormal(); +// acuhandler->setModeNormal(); #endif /* Temperature sensors */ Tmp1075Handler* tmp1075Handler_1 = new Tmp1075Handler( diff --git a/etl b/etl index ae06e641..1ac3b77e 160000 --- a/etl +++ b/etl @@ -1 +1 @@ -Subproject commit ae06e6417702b770c49289c9e7162cb3f4a5a217 +Subproject commit 1ac3b77ef40aa783024d15185ee8ff41ae04a73e diff --git a/fsfw b/fsfw index 7d0916a4..e994d81e 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit 7d0916a44e18c87b00998448333023186b3d85b1 +Subproject commit e994d81e1862fade52b090311b3978fb59061966 diff --git a/mission/devices/devicedefinitions/SyrlinksDefinitions.h b/mission/devices/devicedefinitions/SyrlinksDefinitions.h index 5ab82a0c..8f9cbba2 100644 --- a/mission/devices/devicedefinitions/SyrlinksDefinitions.h +++ b/mission/devices/devicedefinitions/SyrlinksDefinitions.h @@ -23,7 +23,7 @@ namespace SYRLINKS { /** The size of the header with the message identifier and the payload size field */ static const uint8_t MESSAGE_HEADER_SIZE = 5; /** Size of reply to an rx status registers request */ - static const uint8_t RX_STATUS_REGISTERS_REPLY_SIZE = 30; + static const uint8_t RX_STATUS_REGISTERS_REPLY_SIZE = 49; static const uint8_t READ_TX_STATUS_REPLY_SIZE = 13; static const uint8_t RX_DATASET_ID = READ_RX_STATUS_REGISTERS; diff --git a/tmtc b/tmtc index 1d5fe4eb..50c6752b 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 1d5fe4ebc7165c2a4979c5f9be9cfa0324e366fb +Subproject commit 50c6752b324c080c9adc3f14e2072d575549c90d From 4bb5443ed0e3ef906797ec25b6fac9240dcd61b3 Mon Sep 17 00:00:00 2001 From: "Jakob.Meier" Date: Thu, 25 Feb 2021 15:53:28 +0100 Subject: [PATCH 08/79] hex to int wip --- etl | 2 +- fsfw | 2 +- mission/devices/SyrlinksHkHandler.cpp | 13 +++++++++++++ mission/devices/SyrlinksHkHandler.h | 22 +++++++++++++++++++++- tmtc | 2 +- 5 files changed, 37 insertions(+), 4 deletions(-) diff --git a/etl b/etl index 1ac3b77e..ae06e641 160000 --- a/etl +++ b/etl @@ -1 +1 @@ -Subproject commit 1ac3b77ef40aa783024d15185ee8ff41ae04a73e +Subproject commit ae06e6417702b770c49289c9e7162cb3f4a5a217 diff --git a/fsfw b/fsfw index e994d81e..7d0916a4 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit e994d81e1862fade52b090311b3978fb59061966 +Subproject commit 7d0916a44e18c87b00998448333023186b3d85b1 diff --git a/mission/devices/SyrlinksHkHandler.cpp b/mission/devices/SyrlinksHkHandler.cpp index 60dc439c..ec83e10b 100644 --- a/mission/devices/SyrlinksHkHandler.cpp +++ b/mission/devices/SyrlinksHkHandler.cpp @@ -184,6 +184,19 @@ std::string SyrlinksHkHandler::convertIntToHexString(uint16_t intValue) { return stream.str(); } +uint8_t SyrlinksHkHandler::convertHexStringToUint8(char* twoChars) { + uint8_t value; + std::string hexString(twoChars, 2); + std::stringstream stream; + stream << std::hex << hexString; + stream >> value; + return value; +} + +uint16_t convertHexStringToUint16(char* fourChars) { + +} + ReturnValue_t SyrlinksHkHandler::parseReplyStatus(const char* status) { switch (*status) { case '0': diff --git a/mission/devices/SyrlinksHkHandler.h b/mission/devices/SyrlinksHkHandler.h index 23a48c13..692be563 100644 --- a/mission/devices/SyrlinksHkHandler.h +++ b/mission/devices/SyrlinksHkHandler.h @@ -80,12 +80,32 @@ private: /** * @brief This function converts an uint16_t into its hexadecimal string representation. * - * @param The value to convert. + * @param intValue The value to convert. * * @return An std::string object containing the hex representation of intValue. */ std::string convertIntToHexString(uint16_t intValue); + /** + * @brief This function converts a hex number represented by to chars to an 8-bit integer. + * + * @param twoChars Pointer to the two characters representing the hex value. + * + * @details E.g. when twoChars points to an array with the two characters "A5" then the function + * will return 0xA5. + * @return The converted integer. + */ + uint8_t convertHexStringToUint8(char* twoChars); + + /** + * @brief This function converts a hex number represented by 4 chars to an uint16_t. + * + * @param Pointer to the fourCharacters representing the 16-bit integer. + * + * @return The uint16_t result. + */ + uint16_t convertHexStringToUint16(char* fourChars); + /** * @brief This function parses the status reply * @param status Pointer to the status information. diff --git a/tmtc b/tmtc index 50c6752b..1d5fe4eb 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 50c6752b324c080c9adc3f14e2072d575549c90d +Subproject commit 1d5fe4ebc7165c2a4979c5f9be9cfa0324e366fb From be7b895b179caf79e9ef37bbe85e62bc765ea385 Mon Sep 17 00:00:00 2001 From: "Jakob.Meier" Date: Thu, 25 Feb 2021 18:15:57 +0100 Subject: [PATCH 09/79] added hex string to int functions --- bsp_q7s/InitMission.cpp | 2 +- fsfwconfig/OBSWConfig.h | 3 +- mission/devices/SyrlinksHkHandler.cpp | 82 +++++++++++++++++++-------- mission/devices/SyrlinksHkHandler.h | 14 ++++- 4 files changed, 73 insertions(+), 28 deletions(-) diff --git a/bsp_q7s/InitMission.cpp b/bsp_q7s/InitMission.cpp index 681d6b48..c299b4ea 100644 --- a/bsp_q7s/InitMission.cpp +++ b/bsp_q7s/InitMission.cpp @@ -129,7 +129,7 @@ void InitMission::initTasks(){ /* Polling Sequence Table Default */ FixedTimeslotTaskIF * PollingSequenceTableTaskDefault = TaskFactory::instance()->createFixedTimeslotTask("PST_TASK_DEFAULT", - 50, PeriodicTaskIF::MINIMUM_STACK_SIZE*4, 3.0, + 50, PeriodicTaskIF::MINIMUM_STACK_SIZE*4, 4.0, nullptr); result = pst::pollingSequenceInitDefault(PollingSequenceTableTaskDefault); if (result != HasReturnvaluesIF::RETURN_OK) { diff --git a/fsfwconfig/OBSWConfig.h b/fsfwconfig/OBSWConfig.h index b5857ba1..69993b62 100644 --- a/fsfwconfig/OBSWConfig.h +++ b/fsfwconfig/OBSWConfig.h @@ -17,7 +17,8 @@ debugging. */ #define P60DOCK_DEBUG 0 #define PDU1_DEBUG 0 #define PDU2_DEBUG 0 -#define ACU_DEBUG 1 +#define ACU_DEBUG 0 +#define SYRLINKS_DEBUG 1 #include "OBSWVersion.h" diff --git a/mission/devices/SyrlinksHkHandler.cpp b/mission/devices/SyrlinksHkHandler.cpp index ec83e10b..a358ff78 100644 --- a/mission/devices/SyrlinksHkHandler.cpp +++ b/mission/devices/SyrlinksHkHandler.cpp @@ -2,6 +2,7 @@ #include #include #include +#include SyrlinksHkHandler::SyrlinksHkHandler(object_id_t objectId, object_id_t comIF, CookieIF * comCookie) : DeviceHandlerBase(objectId, comIF, comCookie), rxDataset(this), txDataset(this) { @@ -180,11 +181,11 @@ ReturnValue_t SyrlinksHkHandler::interpretDeviceReply(DeviceCommandId_t id, std::string SyrlinksHkHandler::convertIntToHexString(uint16_t intValue) { std::stringstream stream; - stream << std::hex << intValue; + stream << std::hex << std::uppercase << intValue; return stream.str(); } -uint8_t SyrlinksHkHandler::convertHexStringToUint8(char* twoChars) { +uint8_t SyrlinksHkHandler::convertHexStringToUint8(const char* twoChars) { uint8_t value; std::string hexString(twoChars, 2); std::stringstream stream; @@ -193,8 +194,33 @@ uint8_t SyrlinksHkHandler::convertHexStringToUint8(char* twoChars) { return value; } -uint16_t convertHexStringToUint16(char* fourChars) { +uint16_t SyrlinksHkHandler::convertHexStringToUint16(const char* fourChars) { + uint16_t value = 0; + value = convertHexStringToUint8(fourChars) << 8 | convertHexStringToUint8(fourChars+2); + return value; +} +uint32_t SyrlinksHkHandler::convertHexStringToUint32(const char* characters, uint8_t numberOfChars) { + + uint32_t value = 0; + + switch (numberOfChars) { + case 6: + value = convertHexStringToUint8(characters) << 16 + | convertHexStringToUint8(characters + 2) << 8 + | convertHexStringToUint8(characters + 4); + return value; + case 8: + value = convertHexStringToUint8(characters) << 24 + | convertHexStringToUint8(characters + 2) << 16 + | convertHexStringToUint8(characters + 4) << 8 + | convertHexStringToUint8(characters + 4); + return value; + default: + sif::debug << "SyrlinksHkHandler::convertHexStringToUint32: Invalid number of characters. " + << "Must be either 6 or 8" << std::endl; + return 0; + } } ReturnValue_t SyrlinksHkHandler::parseReplyStatus(const char* status) { @@ -231,13 +257,17 @@ ReturnValue_t SyrlinksHkHandler::parseReplyStatus(const char* status) { ReturnValue_t SyrlinksHkHandler::verifyReply(const uint8_t* packet, uint8_t size) { int result = 0; - /* Calculate crc of received packet */ + /* Calculate crc from received packet */ uint16_t crc = CRC::crc16ccitt(packet, size - SYRLINKS::SIZE_CRC_AND_TERMINATION, CRC_INITIAL_VALUE); std::string recalculatedCrc = convertIntToHexString(crc); - const char* replyCrc = reinterpret_cast(packet) + size - SYRLINKS::SIZE_CRC_AND_TERMINATION; - size_t startPosition = 0; - result = recalculatedCrc.compare(startPosition, SYRLINKS::CRC_FIELD_SIZE, replyCrc); + + const char* startOfCrc = reinterpret_cast(packet + size - SYRLINKS::SIZE_CRC_AND_TERMINATION); + const char* endOfCrc = reinterpret_cast(packet + size - 1); + + std::string replyCrc(startOfCrc, endOfCrc); + + result = recalculatedCrc.compare(replyCrc); if (result != 0) { return RETURN_FAILED; } @@ -247,22 +277,26 @@ ReturnValue_t SyrlinksHkHandler::verifyReply(const uint8_t* packet, uint8_t size void SyrlinksHkHandler::parseRxStatusRegistersReply(const uint8_t* packet) { PoolReadHelper readHelper(&rxDataset); uint16_t offset = SYRLINKS::MESSAGE_HEADER_SIZE; - rxDataset.rxStatus = *(packet + offset); - packet += 1; - rxDataset.rxSensitivity = *(packet + offset) << 16 | *(packet + offset + 1) << 8 | *(packet + offset + 2); - packet += 3; - rxDataset.rxFrequencyShift = *(packet + offset) << 16 | *(packet + offset + 1) << 8 | *(packet + offset + 2); - packet += 3; - rxDataset.rxIqPower = *(packet + offset) << 8 | *(packet + offset + 1); - packet += 2; - rxDataset.rxAgcValue = *(packet + offset + 1) << 8 | *(packet + offset); - packet += 2; - packet += 1; // reserved register - rxDataset.rxDemodEb= *(packet + offset) << 16 | *(packet + offset + 1) << 8 | *(packet + offset + 2); - packet += 3; - rxDataset.rxDemodN0= *(packet + offset) << 16 | *(packet + offset + 1) << 8 | *(packet + offset + 2); - packet += 3; - rxDataset.rxDataRate = *(packet + offset); + rxDataset.rxStatus = convertHexStringToUint8(reinterpret_cast(packet + offset)); + offset += 2; + rxDataset.rxSensitivity = convertHexStringToUint32(reinterpret_cast(packet + offset), 6); + offset += 6; + rxDataset.rxFrequencyShift = convertHexStringToUint32(reinterpret_cast(packet + offset), 6); + offset += 6; + rxDataset.rxIqPower = convertHexStringToUint16(reinterpret_cast(packet + offset)); + offset += 4; + rxDataset.rxAgcValue = convertHexStringToUint16(reinterpret_cast(packet + offset)); + offset += 4; + offset += 2; // reserved register + rxDataset.rxDemodEb= convertHexStringToUint32(reinterpret_cast(packet + offset), 6); + offset += 6; + rxDataset.rxDemodN0= convertHexStringToUint32(reinterpret_cast(packet + offset), 6); + offset += 6; + rxDataset.rxDataRate = convertHexStringToUint8(reinterpret_cast(packet + offset)); + +#if OBSW_VERBOSE_LEVEL >= 1 && SYRLINKS_DEBUG == 1 + sif::info << "Syrlinks RX Status: " << std::hex << rxDataset.rxStatus << std::endl; +#endif } void SyrlinksHkHandler::parseTxStatusReply(const uint8_t* packet) { @@ -283,7 +317,7 @@ ReturnValue_t SyrlinksHkHandler::initializeLocalDataPool(localpool::DataPool& lo LocalDataPoolManager& poolManager) { localDataPoolMap.emplace(SYRLINKS::RX_STATUS, new PoolEntry( { 0 })); - localDataPoolMap.emplace(SYRLINKS::RX_SENSITIVITY, new PoolEntry( { 0 })); + localDataPoolMap.emplace(SYRLINKS::RX_SENSITIVITY, new PoolEntry( { 0 })); localDataPoolMap.emplace(SYRLINKS::RX_FREQUENCY_SHIFT, new PoolEntry( { 0 })); localDataPoolMap.emplace(SYRLINKS::RX_IQ_POWER, new PoolEntry( { 0 })); localDataPoolMap.emplace(SYRLINKS::RX_AGC_VALUE, new PoolEntry( { 0 })); diff --git a/mission/devices/SyrlinksHkHandler.h b/mission/devices/SyrlinksHkHandler.h index 692be563..c15d3f34 100644 --- a/mission/devices/SyrlinksHkHandler.h +++ b/mission/devices/SyrlinksHkHandler.h @@ -95,7 +95,7 @@ private: * will return 0xA5. * @return The converted integer. */ - uint8_t convertHexStringToUint8(char* twoChars); + uint8_t convertHexStringToUint8(const char* twoChars); /** * @brief This function converts a hex number represented by 4 chars to an uint16_t. @@ -104,7 +104,17 @@ private: * * @return The uint16_t result. */ - uint16_t convertHexStringToUint16(char* fourChars); + uint16_t convertHexStringToUint16(const char* fourChars); + + /** + * @brief Function converts a hex number represented by 6 or 8 characters to an uint32_t. + * + * @param characters Pointer to the hex characters array. + * @param numberOfChars Number of characters representing the hex value. Must be 6 or 8. + * + * @return The uint32_t value. + */ + uint32_t convertHexStringToUint32(const char* characters, uint8_t numberOfChars); /** * @brief This function parses the status reply From f761789154f191ed0face1e7c26296101addcb54 Mon Sep 17 00:00:00 2001 From: "Jakob.Meier" Date: Sat, 27 Feb 2021 11:07:42 +0100 Subject: [PATCH 10/79] added readout of some tx registers --- bsp_q7s/ObjectFactory.cpp | 24 ++-- linux/gpio/LinuxLibgpioIF.cpp | 3 +- mission/devices/SyrlinksHkHandler.cpp | 103 ++++++++++++++++-- mission/devices/SyrlinksHkHandler.h | 29 ++++- .../devicedefinitions/SyrlinksDefinitions.h | 6 + 5 files changed, 145 insertions(+), 20 deletions(-) diff --git a/bsp_q7s/ObjectFactory.cpp b/bsp_q7s/ObjectFactory.cpp index afe5ff9d..ec2e2b2a 100644 --- a/bsp_q7s/ObjectFactory.cpp +++ b/bsp_q7s/ObjectFactory.cpp @@ -125,37 +125,37 @@ void ObjectFactory::produce(){ new LinuxLibgpioIF(objects::GPIO_IF); #if TE0720 == 0 /* Pin H2-11 on stack connector */ - GpioConfig_t gpioConfigHeater0(std::string("gpiochip7"), 18, + GpioConfig_t gpioConfigHeater0(std::string("gpiochip7"), 15, std::string("Heater0"), gpio::OUT, 0); heaterGpiosCookie->addGpio(gpioIds::HEATER_0, gpioConfigHeater0); /* Pin H2-12 on stack connector */ - GpioConfig_t gpioConfigHeater1(std::string("gpiochip7"), 14, + GpioConfig_t gpioConfigHeater1(std::string("gpiochip7"), 11, std::string("Heater1"), gpio::OUT, 0); heaterGpiosCookie->addGpio(gpioIds::HEATER_1, gpioConfigHeater1); /* Pin H2-13 on stack connector */ - GpioConfig_t gpioConfigHeater2(std::string("gpiochip7"), 20, + GpioConfig_t gpioConfigHeater2(std::string("gpiochip7"), 17, std::string("Heater2"), gpio::OUT, 0); heaterGpiosCookie->addGpio(gpioIds::HEATER_2, gpioConfigHeater2); - GpioConfig_t gpioConfigHeater3(std::string("gpiochip7"), 16, + GpioConfig_t gpioConfigHeater3(std::string("gpiochip7"), 13, std::string("Heater3"), gpio::OUT, 0); heaterGpiosCookie->addGpio(gpioIds::HEATER_3, gpioConfigHeater3); - GpioConfig_t gpioConfigHeater4(std::string("gpiochip7"), 24, + GpioConfig_t gpioConfigHeater4(std::string("gpiochip7"), 21, std::string("Heater4"), gpio::OUT, 0); heaterGpiosCookie->addGpio(gpioIds::HEATER_4, gpioConfigHeater4); - GpioConfig_t gpioConfigHeater5(std::string("gpiochip7"), 26, + GpioConfig_t gpioConfigHeater5(std::string("gpiochip7"), 23, std::string("Heater5"), gpio::OUT, 0); heaterGpiosCookie->addGpio(gpioIds::HEATER_5, gpioConfigHeater5); - GpioConfig_t gpioConfigHeater6(std::string("gpiochip7"), 22, + GpioConfig_t gpioConfigHeater6(std::string("gpiochip7"), 19, std::string("Heater6"), gpio::OUT, 0); heaterGpiosCookie->addGpio(gpioIds::HEATER_6, gpioConfigHeater6); - GpioConfig_t gpioConfigHeater7(std::string("gpiochip7"), 28, + GpioConfig_t gpioConfigHeater7(std::string("gpiochip7"), 10, std::string("Heater7"), gpio::OUT, 0); heaterGpiosCookie->addGpio(gpioIds::HEATER_7, gpioConfigHeater7); @@ -163,10 +163,10 @@ void ObjectFactory::produce(){ pcduSwitches::TCS_BOARD_8V_HEATER_IN); GpioCookie* solarArrayDeplCookie = new GpioCookie; - GpioConfig_t gpioConfigDeplSA1(std::string("gpiochip7"), 25, + GpioConfig_t gpioConfigDeplSA1(std::string("gpiochip7"), 22, std::string("DeplSA1"), gpio::OUT, 0); solarArrayDeplCookie->addGpio(gpioIds::DEPLSA1, gpioConfigDeplSA1); - GpioConfig_t gpioConfigDeplSA2(std::string("gpiochip7"), 23, + GpioConfig_t gpioConfigDeplSA2(std::string("gpiochip7"), 20, std::string("DeplSA2"), gpio::OUT, 0); solarArrayDeplCookie->addGpio(gpioIds::DEPLSA2, gpioConfigDeplSA2); @@ -175,8 +175,10 @@ void ObjectFactory::produce(){ solarArrayDeplCookie, objects::PCDU_HANDLER, pcduSwitches::DEPLOYMENT_MECHANISM, gpioIds::DEPLSA1, gpioIds::DEPLSA2, 1000); +// UartCookie* syrlinksUartCookie = new UartCookie( +// std::string("/dev/ttyPS1"), 38400, SYRLINKS::MAX_REPLY_SIZE); UartCookie* syrlinksUartCookie = new UartCookie( - std::string("/dev/ttyPS1"), 38400, SYRLINKS::MAX_REPLY_SIZE); + std::string("/dev/ttyUL0"), 38400, SYRLINKS::MAX_REPLY_SIZE); syrlinksUartCookie->setParityEven(); SyrlinksHkHandler* syrlinksHkHandler = new SyrlinksHkHandler(objects::SYRLINKS_HK_HANDLER, objects::UART_COM_IF, syrlinksUartCookie); diff --git a/linux/gpio/LinuxLibgpioIF.cpp b/linux/gpio/LinuxLibgpioIF.cpp index e5db2934..04148467 100644 --- a/linux/gpio/LinuxLibgpioIF.cpp +++ b/linux/gpio/LinuxLibgpioIF.cpp @@ -68,7 +68,8 @@ ReturnValue_t LinuxLibgpioIF::configureGpios(GpioMap* mapToAdd) { lineNum = mapToAddIter->second.lineNum; lineHandle = gpiod_chip_get_line(chip, lineNum); if (!lineHandle) { - sif::error << "LinuxLibgpioIF::configureGpios: Failed to open line" << std::endl; + sif::error << "LinuxLibgpioIF::configureGpios: Failed to open line for GPIO with id " + << mapToAddIter->first << std::endl; gpiod_chip_close(chip); return RETURN_FAILED; } diff --git a/mission/devices/SyrlinksHkHandler.cpp b/mission/devices/SyrlinksHkHandler.cpp index a358ff78..6049d34b 100644 --- a/mission/devices/SyrlinksHkHandler.cpp +++ b/mission/devices/SyrlinksHkHandler.cpp @@ -77,6 +77,20 @@ ReturnValue_t SyrlinksHkHandler::buildCommandFromCommand( rawPacket = commandBuffer; return RETURN_OK; } + case(SYRLINKS::READ_TX_WAVEFORM): { + readTxWaveform.copy(reinterpret_cast(commandBuffer), readTxStatus.size(), 0); + rawPacketLen = readTxWaveform.size(); + rememberCommandId = SYRLINKS::READ_TX_WAVEFORM; + rawPacket = commandBuffer; + return RETURN_OK; + } + case(SYRLINKS::READ_TX_AGC_VALUE): { + readTxAgcValue.copy(reinterpret_cast(commandBuffer), readTxStatus.size(), 0); + rawPacketLen = readTxAgcValue.size(); + rememberCommandId = SYRLINKS::READ_TX_AGC_VALUE; + rawPacket = commandBuffer; + return RETURN_OK; + } default: return DeviceHandlerIF::COMMAND_NOT_IMPLEMENTED; } @@ -118,6 +132,7 @@ ReturnValue_t SyrlinksHkHandler::scanForReply(const uint8_t *start, *foundId = SYRLINKS::READ_RX_STATUS_REGISTERS; break; case('R'): + getIdAndLenForReadResponse(foundId, foundLen); if (rememberCommandId == SYRLINKS::READ_TX_STATUS) { *foundLen = SYRLINKS::READ_TX_STATUS_REPLY_SIZE; *foundId = SYRLINKS::READ_TX_STATUS; @@ -169,6 +184,24 @@ ReturnValue_t SyrlinksHkHandler::interpretDeviceReply(DeviceCommandId_t id, } parseTxStatusReply(packet); break; + case(SYRLINKS::READ_TX_WAVEFORM): + result = verifyReply(packet, SYRLINKS::READ_TX_WAVEFORM_REPLY_SIZE); + if (result != RETURN_OK) { + sif::error << "SyrlinksHkHandler::interpretDeviceReply: Read tx waveform reply " + << "has invalid crc" << std::endl; + return CRC_FAILURE; + } + parseTxWaveformReply(packet); + break; + case(SYRLINKS::READ_TX_AGC_VALUE): + result = verifyReply(packet, SYRLINKS::READ_TX_AGC_VALUE_REPLY_SIZE); + if (result != RETURN_OK) { + sif::error << "SyrlinksHkHandler::interpretDeviceReply: Read tx AGC reply " + << "has invalid crc" << std::endl; + return CRC_FAILURE; + } + parseTxAgcValueReply(packet); + break; default: { sif::debug << "SyrlinksHkHandler::interpretDeviceReply: Unknown device reply id" << std::endl; @@ -179,19 +212,41 @@ ReturnValue_t SyrlinksHkHandler::interpretDeviceReply(DeviceCommandId_t id, return RETURN_OK; } -std::string SyrlinksHkHandler::convertIntToHexString(uint16_t intValue) { +void SyrlinksHkHandler::getIdAndLenForReadResponse(DeviceCommandId_t *foundId, size_t *foundLen) { + switch (rememberCommandId) { + case(SYRLINKS::READ_TX_STATUS): + *foundLen = SYRLINKS::READ_TX_STATUS_REPLY_SIZE; + *foundId = SYRLINKS::READ_TX_STATUS; + break; + case(SYRLINKS::READ_TX_WAVEFORM): + *foundLen = SYRLINKS::READ_TX_WAVEFORM_REPLY_SIZE; + *foundId = SYRLINKS::READ_TX_WAVEFORM; + break; + case(SYRLINKS::READ_TX_AGC_VALUE): + *foundLen = SYRLINKS::READ_TX_AGC_VALUE_REPLY_SIZE; + *foundId = SYRLINKS::READ_TX_AGC_VALUE; + break; + default: + sif::debug << "SyrlinksHkHandler::getIdAndLenForReadResponse: No command id remembered" + << std::endl; + break; + } + rememberCommandId = SYRLINKS::NONE; +} + +std::string SyrlinksHkHandler::convertUint16ToHexString(uint16_t intValue) { std::stringstream stream; - stream << std::hex << std::uppercase << intValue; + stream << std::setfill('0') << std::setw(4) << std::hex << std::uppercase << intValue; return stream.str(); } uint8_t SyrlinksHkHandler::convertHexStringToUint8(const char* twoChars) { - uint8_t value; + uint32_t value; std::string hexString(twoChars, 2); std::stringstream stream; stream << std::hex << hexString; stream >> value; - return value; + return static_cast(value); } uint16_t SyrlinksHkHandler::convertHexStringToUint16(const char* fourChars) { @@ -260,7 +315,7 @@ ReturnValue_t SyrlinksHkHandler::verifyReply(const uint8_t* packet, uint8_t size /* Calculate crc from received packet */ uint16_t crc = CRC::crc16ccitt(packet, size - SYRLINKS::SIZE_CRC_AND_TERMINATION, CRC_INITIAL_VALUE); - std::string recalculatedCrc = convertIntToHexString(crc); + std::string recalculatedCrc = convertUint16ToHexString(crc); const char* startOfCrc = reinterpret_cast(packet + size - SYRLINKS::SIZE_CRC_AND_TERMINATION); const char* endOfCrc = reinterpret_cast(packet + size - 1); @@ -295,14 +350,44 @@ void SyrlinksHkHandler::parseRxStatusRegistersReply(const uint8_t* packet) { rxDataset.rxDataRate = convertHexStringToUint8(reinterpret_cast(packet + offset)); #if OBSW_VERBOSE_LEVEL >= 1 && SYRLINKS_DEBUG == 1 - sif::info << "Syrlinks RX Status: " << std::hex << rxDataset.rxStatus << std::endl; + sif::info << "Syrlinks RX Status: 0x" << std::hex << (unsigned int)rxDataset.rxStatus.value << std::endl; + sif::info << "Syrlinks RX Sensitivity: " << rxDataset.rxSensitivity << std::endl; + sif::info << "Syrlinks RX Frequency Shift: " << rxDataset.rxFrequencyShift << std::endl; + sif::info << "Syrlinks RX IQ Power: " << rxDataset.rxIqPower << std::endl; + sif::info << "Syrlinks RX AGC Value: " << rxDataset.rxAgcValue << std::endl; + sif::info << "Syrlinks RX Demod Eb: " << rxDataset.rxDemodEb << std::endl; + sif::info << "Syrlinks RX Demod N0: " << rxDataset.rxDemodN0 << std::endl; + sif::info << "Syrlinks RX Datarate: " << (unsigned int)rxDataset.rxDataRate.value << std::endl; #endif } void SyrlinksHkHandler::parseTxStatusReply(const uint8_t* packet) { PoolReadHelper readHelper(&txDataset); uint16_t offset = SYRLINKS::MESSAGE_HEADER_SIZE; - rxDataset.rxStatus = *(packet + offset); + txDataset.txStatus = convertHexStringToUint8(reinterpret_cast(packet + offset)); +#if OBSW_VERBOSE_LEVEL >= 1 && SYRLINKS_DEBUG == 1 + sif::info << "Syrlinks TX Status: 0x" << std::hex << (unsigned int) txDataset.txStatus.value + << std::endl; +#endif +} + +void SyrlinksHkHandler::parseTxWaveformReply(const uint8_t* packet) { + PoolReadHelper readHelper(&txDataset); + uint16_t offset = SYRLINKS::MESSAGE_HEADER_SIZE; + txDataset.txWaveform = convertHexStringToUint8(reinterpret_cast(packet + offset)); +#if OBSW_VERBOSE_LEVEL >= 1 && SYRLINKS_DEBUG == 1 + sif::info << "Syrlinks TX Waveform: 0x" << std::hex << (unsigned int) txDataset.txWaveform.value + << std::endl; +#endif +} + +void SyrlinksHkHandler::parseTxAgcValueReply(const uint8_t* packet) { + PoolReadHelper readHelper(&txDataset); + uint16_t offset = SYRLINKS::MESSAGE_HEADER_SIZE; + txDataset.txAgcValue = convertHexStringToUint16(reinterpret_cast(packet + offset)); +#if OBSW_VERBOSE_LEVEL >= 1 && SYRLINKS_DEBUG == 1 + sif::info << "Syrlinks TX AGC Value: " << txDataset.txAgcValue << std::endl; +#endif } void SyrlinksHkHandler::setNormalDatapoolEntriesInvalid(){ @@ -325,6 +410,10 @@ ReturnValue_t SyrlinksHkHandler::initializeLocalDataPool(localpool::DataPool& lo localDataPoolMap.emplace(SYRLINKS::RX_DEMOD_N0, new PoolEntry( { 0 })); localDataPoolMap.emplace(SYRLINKS::RX_DATA_RATE, new PoolEntry( { 0 })); + localDataPoolMap.emplace(SYRLINKS::TX_STATUS, new PoolEntry( { 0 })); + localDataPoolMap.emplace(SYRLINKS::TX_WAVEFORM, new PoolEntry( { 0 })); + localDataPoolMap.emplace(SYRLINKS::TX_AGC_VALUE, new PoolEntry( { 0 })); + return HasReturnvaluesIF::RETURN_OK; } diff --git a/mission/devices/SyrlinksHkHandler.h b/mission/devices/SyrlinksHkHandler.h index c15d3f34..6b249826 100644 --- a/mission/devices/SyrlinksHkHandler.h +++ b/mission/devices/SyrlinksHkHandler.h @@ -65,6 +65,8 @@ private: std::string setTxModeModulation = ""; std::string setTxModeCw = ""; std::string readTxStatus = ""; + std::string readTxWaveform = ""; + std::string readTxAgcValue = ""; /** * In some cases it is not possible to extract from the received reply the information about @@ -77,6 +79,21 @@ private: uint8_t commandBuffer[SYRLINKS::MAX_COMMAND_SIZE]; + /** + * @brief This function gets the command id relating to a received read response 'R'. + * + * @param foundId Pointer to object where found id will be stored. + * @param foundLen Pointer to objet where reply length of the received response will be + * stored. + */ + void getIdAndLenForReadResponse(DeviceCommandId_t *foundId, size_t *foundLen); + + /** + * This object is used to store the id of the next command to execute. This controls the + * read out of multiple registers which can not be fetched with one single command. + */ + DeviceCommandId_t nextCommand = SYRLINKS::READ_RX_STATUS_REGISTERS; + /** * @brief This function converts an uint16_t into its hexadecimal string representation. * @@ -84,7 +101,7 @@ private: * * @return An std::string object containing the hex representation of intValue. */ - std::string convertIntToHexString(uint16_t intValue); + std::string convertUint16ToHexString(uint16_t intValue); /** * @brief This function converts a hex number represented by to chars to an 8-bit integer. @@ -149,6 +166,16 @@ private: * @param packet Pointer to the received packet. */ void parseTxStatusReply(const uint8_t* packet); + + /** + * @brief This function writes the received waveform configuration to the txDataset. + */ + void parseTxWaveformReply(const uint8_t* packet); + + /** + * @brief This function writes the received AGC value to the txDataset. + */ + void parseTxAgcValueReply(const uint8_t* packet); }; #endif /* MISSION_DEVICES_SYRLINKSHKHANDLER_H_ */ diff --git a/mission/devices/devicedefinitions/SyrlinksDefinitions.h b/mission/devices/devicedefinitions/SyrlinksDefinitions.h index 8f9cbba2..ba719ebb 100644 --- a/mission/devices/devicedefinitions/SyrlinksDefinitions.h +++ b/mission/devices/devicedefinitions/SyrlinksDefinitions.h @@ -16,6 +16,8 @@ namespace SYRLINKS { static const DeviceCommandId_t SET_TX_MODE_CW = 0x05; static const DeviceCommandId_t ACK_REPLY = 0x06; static const DeviceCommandId_t READ_TX_STATUS = 0x07; + static const DeviceCommandId_t READ_TX_WAVEFORM = 0x08; + static const DeviceCommandId_t READ_TX_AGC_VALUE = 0x09; /** Size of a simple transmission success response */ static const uint8_t ACK_SIZE = 11; @@ -25,6 +27,8 @@ namespace SYRLINKS { /** Size of reply to an rx status registers request */ static const uint8_t RX_STATUS_REGISTERS_REPLY_SIZE = 49; static const uint8_t READ_TX_STATUS_REPLY_SIZE = 13; + static const uint8_t READ_TX_WAVEFORM_REPLY_SIZE = 13; + static const uint8_t READ_TX_AGC_VALUE_REPLY_SIZE = 15; static const uint8_t RX_DATASET_ID = READ_RX_STATUS_REGISTERS; static const uint8_t TX_DATASET_ID = READ_TX_STATUS; @@ -88,6 +92,8 @@ public: } lp_var_t txStatus = lp_var_t(sid.objectId, TX_STATUS, this); + lp_var_t txWaveform = lp_var_t(sid.objectId, TX_WAVEFORM, this); + lp_var_t txAgcValue = lp_var_t(sid.objectId, TX_AGC_VALUE, this); }; } From 22f8f370e413d94b22357ec836b5eff4b0430f63 Mon Sep 17 00:00:00 2001 From: "Jakob.Meier" Date: Mon, 1 Mar 2021 12:23:39 +0100 Subject: [PATCH 11/79] syrlinks hk handler complete --- bsp_q7s/InitMission.cpp | 6 +- bsp_q7s/ObjectFactory.cpp | 7 +- .../PollingSequenceFactory.cpp | 2 + mission/devices/SyrlinksHkHandler.cpp | 120 ++++++++++++------ mission/devices/SyrlinksHkHandler.h | 21 ++- .../devicedefinitions/SyrlinksDefinitions.h | 13 +- tmtc | 2 +- 7 files changed, 106 insertions(+), 65 deletions(-) diff --git a/bsp_q7s/InitMission.cpp b/bsp_q7s/InitMission.cpp index c299b4ea..97b18051 100644 --- a/bsp_q7s/InitMission.cpp +++ b/bsp_q7s/InitMission.cpp @@ -105,13 +105,17 @@ void InitMission::initTasks(){ } PeriodicTaskIF* PusMedPrio = TaskFactory::instance()-> - createPeriodicTask("PUS_HIGH_PRIO", 40, + createPeriodicTask("PUS_MED_PRIO", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.8, nullptr); result = PusMedPrio->addComponent(objects::PUS_SERVICE_8_FUNCTION_MGMT); if(result!=HasReturnvaluesIF::RETURN_OK){ sif::error << "Object add component failed" << std::endl; } + result = PusMedPrio->addComponent(objects::PUS_SERVICE_3_HOUSEKEEPING); + if(result!=HasReturnvaluesIF::RETURN_OK){ + sif::error << "Object add component failed" << std::endl; + } result = PusMedPrio->addComponent(objects::PUS_SERVICE_200_MODE_MGMT); if(result!=HasReturnvaluesIF::RETURN_OK){ sif::error << "Object add component failed" << std::endl; diff --git a/bsp_q7s/ObjectFactory.cpp b/bsp_q7s/ObjectFactory.cpp index ec2e2b2a..2c70e9c7 100644 --- a/bsp_q7s/ObjectFactory.cpp +++ b/bsp_q7s/ObjectFactory.cpp @@ -53,7 +53,7 @@ void Factory::setStaticFrameworkObjectIds() { // No storage object for now. TmFunnel::storageDestination = objects::NO_OBJECT; - LocalDataPoolManager::defaultHkDestination = objects::NO_OBJECT; + LocalDataPoolManager::defaultHkDestination = objects::PUS_SERVICE_3_HOUSEKEEPING; VerificationReporter::messageReceiver = objects::PUS_SERVICE_1_VERIFICATION; TmPacketStored::timeStamperId = objects::TIME_STAMPER; @@ -175,13 +175,12 @@ void ObjectFactory::produce(){ solarArrayDeplCookie, objects::PCDU_HANDLER, pcduSwitches::DEPLOYMENT_MECHANISM, gpioIds::DEPLSA1, gpioIds::DEPLSA2, 1000); -// UartCookie* syrlinksUartCookie = new UartCookie( -// std::string("/dev/ttyPS1"), 38400, SYRLINKS::MAX_REPLY_SIZE); UartCookie* syrlinksUartCookie = new UartCookie( std::string("/dev/ttyUL0"), 38400, SYRLINKS::MAX_REPLY_SIZE); syrlinksUartCookie->setParityEven(); - SyrlinksHkHandler* syrlinksHkHandler = new SyrlinksHkHandler(objects::SYRLINKS_HK_HANDLER, objects::UART_COM_IF, syrlinksUartCookie); + SyrlinksHkHandler* syrlinksHkHandler = new SyrlinksHkHandler(objects::SYRLINKS_HK_HANDLER, + objects::UART_COM_IF, syrlinksUartCookie); syrlinksHkHandler->setModeNormal(); #endif diff --git a/fsfwconfig/pollingsequence/PollingSequenceFactory.cpp b/fsfwconfig/pollingsequence/PollingSequenceFactory.cpp index f098800f..00450a25 100644 --- a/fsfwconfig/pollingsequence/PollingSequenceFactory.cpp +++ b/fsfwconfig/pollingsequence/PollingSequenceFactory.cpp @@ -14,6 +14,8 @@ ReturnValue_t pst::pollingSequenceInitDefault(FixedTimeslotTaskIF *thisSequence) DeviceHandlerIF::PERFORM_OPERATION); thisSequence->addSlot(objects::TMP1075_HANDLER_2, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::SYRLINKS_HK_HANDLER, length * 0, + DeviceHandlerIF::PERFORM_OPERATION); thisSequence->addSlot(objects::HEATER_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); thisSequence->addSlot(objects::SOLAR_ARRAY_DEPL_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); diff --git a/mission/devices/SyrlinksHkHandler.cpp b/mission/devices/SyrlinksHkHandler.cpp index 6049d34b..d9b05b18 100644 --- a/mission/devices/SyrlinksHkHandler.cpp +++ b/mission/devices/SyrlinksHkHandler.cpp @@ -27,7 +27,32 @@ void SyrlinksHkHandler::doShutDown(){ ReturnValue_t SyrlinksHkHandler::buildNormalDeviceCommand( DeviceCommandId_t * id) { - *id = SYRLINKS::READ_RX_STATUS_REGISTERS; + switch (nextCommand) { + case(SYRLINKS::READ_RX_STATUS_REGISTERS): + *id = SYRLINKS::READ_RX_STATUS_REGISTERS; + nextCommand = SYRLINKS::READ_TX_STATUS; + break; + case(SYRLINKS::READ_TX_STATUS): + *id = SYRLINKS::READ_TX_STATUS; + nextCommand = SYRLINKS::READ_TX_WAVEFORM; + break; + case(SYRLINKS::READ_TX_WAVEFORM): + *id = SYRLINKS::READ_TX_WAVEFORM; + nextCommand = SYRLINKS::READ_TX_AGC_VALUE_HIGH_BYTE; + break; + case(SYRLINKS::READ_TX_AGC_VALUE_HIGH_BYTE): + *id = SYRLINKS::READ_TX_AGC_VALUE_HIGH_BYTE; + nextCommand = SYRLINKS::READ_TX_AGC_VALUE_LOW_BYTE; + break; + case(SYRLINKS::READ_TX_AGC_VALUE_LOW_BYTE): + *id = SYRLINKS::READ_TX_AGC_VALUE_LOW_BYTE; + nextCommand = SYRLINKS::READ_RX_STATUS_REGISTERS; + break; + default: + sif::debug << "SyrlinksHkHandler::buildNormalDeviceCommand: rememberCommandId has invalid" + << "command id" << std::endl; + break; + } return buildCommandFromCommand(*id, NULL, 0); } @@ -84,10 +109,17 @@ ReturnValue_t SyrlinksHkHandler::buildCommandFromCommand( rawPacket = commandBuffer; return RETURN_OK; } - case(SYRLINKS::READ_TX_AGC_VALUE): { - readTxAgcValue.copy(reinterpret_cast(commandBuffer), readTxStatus.size(), 0); - rawPacketLen = readTxAgcValue.size(); - rememberCommandId = SYRLINKS::READ_TX_AGC_VALUE; + case(SYRLINKS::READ_TX_AGC_VALUE_HIGH_BYTE): { + readTxAgcValueHighByte.copy(reinterpret_cast(commandBuffer), readTxStatus.size(), 0); + rawPacketLen = readTxAgcValueHighByte.size(); + rememberCommandId = SYRLINKS::READ_TX_AGC_VALUE_HIGH_BYTE; + rawPacket = commandBuffer; + return RETURN_OK; + } + case(SYRLINKS::READ_TX_AGC_VALUE_LOW_BYTE): { + readTxAgcValueLowByte.copy(reinterpret_cast(commandBuffer), readTxStatus.size(), 0); + rawPacketLen = readTxAgcValueLowByte.size(); + rememberCommandId = SYRLINKS::READ_TX_AGC_VALUE_LOW_BYTE; rawPacket = commandBuffer; return RETURN_OK; } @@ -107,7 +139,13 @@ void SyrlinksHkHandler::fillCommandAndReplyMap() { this->insertInCommandAndReplyMap(SYRLINKS::SET_TX_MODE_CW, 1, nullptr, SYRLINKS::ACK_SIZE, false, true, SYRLINKS::ACK_REPLY); this->insertInCommandAndReplyMap(SYRLINKS::READ_TX_STATUS, 1, &txDataset, - SYRLINKS::READ_TX_STATUS); + SYRLINKS::READ_ONE_REGISTER_REPLY_SIE); + this->insertInCommandAndReplyMap(SYRLINKS::READ_TX_WAVEFORM, 1, &txDataset, + SYRLINKS::READ_ONE_REGISTER_REPLY_SIE); + this->insertInCommandAndReplyMap(SYRLINKS::READ_TX_AGC_VALUE_HIGH_BYTE, 1, &txDataset, + SYRLINKS::READ_ONE_REGISTER_REPLY_SIE); + this->insertInCommandAndReplyMap(SYRLINKS::READ_TX_AGC_VALUE_LOW_BYTE, 1, &txDataset, + SYRLINKS::READ_ONE_REGISTER_REPLY_SIE); this->insertInCommandAndReplyMap(SYRLINKS::READ_RX_STATUS_REGISTERS, 1, &rxDataset, SYRLINKS::RX_STATUS_REGISTERS_REPLY_SIZE); } @@ -132,12 +170,8 @@ ReturnValue_t SyrlinksHkHandler::scanForReply(const uint8_t *start, *foundId = SYRLINKS::READ_RX_STATUS_REGISTERS; break; case('R'): - getIdAndLenForReadResponse(foundId, foundLen); - if (rememberCommandId == SYRLINKS::READ_TX_STATUS) { - *foundLen = SYRLINKS::READ_TX_STATUS_REPLY_SIZE; - *foundId = SYRLINKS::READ_TX_STATUS; - rememberCommandId = SYRLINKS::NONE; - } + *foundId = rememberCommandId; + *foundLen = SYRLINKS::READ_ONE_REGISTER_REPLY_SIE; break; default: sif::error << "SyrlinksHkHandler::scanForReply: Unknown reply identifier" << std::endl; @@ -176,7 +210,7 @@ ReturnValue_t SyrlinksHkHandler::interpretDeviceReply(DeviceCommandId_t id, parseRxStatusRegistersReply(packet); break; case(SYRLINKS::READ_TX_STATUS): - result = verifyReply(packet, SYRLINKS::READ_TX_STATUS_REPLY_SIZE); + result = verifyReply(packet, SYRLINKS::READ_ONE_REGISTER_REPLY_SIE); if (result != RETURN_OK) { sif::error << "SyrlinksHkHandler::interpretDeviceReply: Read tx status reply " << "has invalid crc" << std::endl; @@ -185,7 +219,7 @@ ReturnValue_t SyrlinksHkHandler::interpretDeviceReply(DeviceCommandId_t id, parseTxStatusReply(packet); break; case(SYRLINKS::READ_TX_WAVEFORM): - result = verifyReply(packet, SYRLINKS::READ_TX_WAVEFORM_REPLY_SIZE); + result = verifyReply(packet, SYRLINKS::READ_ONE_REGISTER_REPLY_SIE); if (result != RETURN_OK) { sif::error << "SyrlinksHkHandler::interpretDeviceReply: Read tx waveform reply " << "has invalid crc" << std::endl; @@ -193,14 +227,23 @@ ReturnValue_t SyrlinksHkHandler::interpretDeviceReply(DeviceCommandId_t id, } parseTxWaveformReply(packet); break; - case(SYRLINKS::READ_TX_AGC_VALUE): - result = verifyReply(packet, SYRLINKS::READ_TX_AGC_VALUE_REPLY_SIZE); + case(SYRLINKS::READ_TX_AGC_VALUE_HIGH_BYTE): + result = verifyReply(packet, SYRLINKS::READ_ONE_REGISTER_REPLY_SIE); if (result != RETURN_OK) { - sif::error << "SyrlinksHkHandler::interpretDeviceReply: Read tx AGC reply " + sif::error << "SyrlinksHkHandler::interpretDeviceReply: Read tx AGC high byte reply " << "has invalid crc" << std::endl; return CRC_FAILURE; } - parseTxAgcValueReply(packet); + parseAgcHighByte(packet); + break; + case(SYRLINKS::READ_TX_AGC_VALUE_LOW_BYTE): + result = verifyReply(packet, SYRLINKS::READ_ONE_REGISTER_REPLY_SIE); + if (result != RETURN_OK) { + sif::error << "SyrlinksHkHandler::interpretDeviceReply: Read tx AGC low byte reply " + << "has invalid crc" << std::endl; + return CRC_FAILURE; + } + parseAgcLowByte(packet); break; default: { sif::debug << "SyrlinksHkHandler::interpretDeviceReply: Unknown device reply id" @@ -212,26 +255,17 @@ ReturnValue_t SyrlinksHkHandler::interpretDeviceReply(DeviceCommandId_t id, return RETURN_OK; } -void SyrlinksHkHandler::getIdAndLenForReadResponse(DeviceCommandId_t *foundId, size_t *foundLen) { - switch (rememberCommandId) { - case(SYRLINKS::READ_TX_STATUS): - *foundLen = SYRLINKS::READ_TX_STATUS_REPLY_SIZE; - *foundId = SYRLINKS::READ_TX_STATUS; - break; - case(SYRLINKS::READ_TX_WAVEFORM): - *foundLen = SYRLINKS::READ_TX_WAVEFORM_REPLY_SIZE; - *foundId = SYRLINKS::READ_TX_WAVEFORM; - break; - case(SYRLINKS::READ_TX_AGC_VALUE): - *foundLen = SYRLINKS::READ_TX_AGC_VALUE_REPLY_SIZE; - *foundId = SYRLINKS::READ_TX_AGC_VALUE; - break; - default: - sif::debug << "SyrlinksHkHandler::getIdAndLenForReadResponse: No command id remembered" - << std::endl; - break; +LocalPoolDataSetBase* SyrlinksHkHandler::getDataSetHandle(sid_t sid) { + if (sid == rxDataset.getSid()) { + return &rxDataset; + } + else if (sid== txDataset.getSid()) { + return &txDataset; + } + else { + sif::error << "SyrlinksHkHandler::getDataSetHandle: Invalid sid" << std::endl; + return nullptr; } - rememberCommandId = SYRLINKS::NONE; } std::string SyrlinksHkHandler::convertUint16ToHexString(uint16_t intValue) { @@ -351,7 +385,7 @@ void SyrlinksHkHandler::parseRxStatusRegistersReply(const uint8_t* packet) { #if OBSW_VERBOSE_LEVEL >= 1 && SYRLINKS_DEBUG == 1 sif::info << "Syrlinks RX Status: 0x" << std::hex << (unsigned int)rxDataset.rxStatus.value << std::endl; - sif::info << "Syrlinks RX Sensitivity: " << rxDataset.rxSensitivity << std::endl; + sif::info << "Syrlinks RX Sensitivity: " << std::dec << rxDataset.rxSensitivity << std::endl; sif::info << "Syrlinks RX Frequency Shift: " << rxDataset.rxFrequencyShift << std::endl; sif::info << "Syrlinks RX IQ Power: " << rxDataset.rxIqPower << std::endl; sif::info << "Syrlinks RX AGC Value: " << rxDataset.rxAgcValue << std::endl; @@ -381,15 +415,21 @@ void SyrlinksHkHandler::parseTxWaveformReply(const uint8_t* packet) { #endif } -void SyrlinksHkHandler::parseTxAgcValueReply(const uint8_t* packet) { +void SyrlinksHkHandler::parseAgcLowByte(const uint8_t* packet) { PoolReadHelper readHelper(&txDataset); uint16_t offset = SYRLINKS::MESSAGE_HEADER_SIZE; - txDataset.txAgcValue = convertHexStringToUint16(reinterpret_cast(packet + offset)); + txDataset.txAgcValue = agcValueHighByte << 8 | convertHexStringToUint8(reinterpret_cast(packet + offset)); #if OBSW_VERBOSE_LEVEL >= 1 && SYRLINKS_DEBUG == 1 sif::info << "Syrlinks TX AGC Value: " << txDataset.txAgcValue << std::endl; #endif } +void SyrlinksHkHandler::parseAgcHighByte(const uint8_t* packet) { + PoolReadHelper readHelper(&txDataset); + uint16_t offset = SYRLINKS::MESSAGE_HEADER_SIZE; + agcValueHighByte = convertHexStringToUint8(reinterpret_cast(packet + offset)); +} + void SyrlinksHkHandler::setNormalDatapoolEntriesInvalid(){ } diff --git a/mission/devices/SyrlinksHkHandler.h b/mission/devices/SyrlinksHkHandler.h index 6b249826..c194fd18 100644 --- a/mission/devices/SyrlinksHkHandler.h +++ b/mission/devices/SyrlinksHkHandler.h @@ -41,6 +41,7 @@ protected: uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override; ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap, LocalDataPoolManager& poolManager) override; + LocalPoolDataSetBase* getDataSetHandle(sid_t sid) override; private: @@ -66,7 +67,8 @@ private: std::string setTxModeCw = ""; std::string readTxStatus = ""; std::string readTxWaveform = ""; - std::string readTxAgcValue = ""; + std::string readTxAgcValueHighByte = ""; + std::string readTxAgcValueLowByte = ""; /** * In some cases it is not possible to extract from the received reply the information about @@ -77,16 +79,9 @@ private: SYRLINKS::RxDataset rxDataset; SYRLINKS::TxDataset txDataset; - uint8_t commandBuffer[SYRLINKS::MAX_COMMAND_SIZE]; + uint8_t agcValueHighByte; - /** - * @brief This function gets the command id relating to a received read response 'R'. - * - * @param foundId Pointer to object where found id will be stored. - * @param foundLen Pointer to objet where reply length of the received response will be - * stored. - */ - void getIdAndLenForReadResponse(DeviceCommandId_t *foundId, size_t *foundLen); + uint8_t commandBuffer[SYRLINKS::MAX_COMMAND_SIZE]; /** * This object is used to store the id of the next command to execute. This controls the @@ -173,9 +168,11 @@ private: void parseTxWaveformReply(const uint8_t* packet); /** - * @brief This function writes the received AGC value to the txDataset. + * @brief The agc value is split over two registers. The parse agc functions are used to get + * the values from the received reply and write them into the txDataset. */ - void parseTxAgcValueReply(const uint8_t* packet); + void parseAgcLowByte(const uint8_t* packet); + void parseAgcHighByte(const uint8_t* packet); }; #endif /* MISSION_DEVICES_SYRLINKSHKHANDLER_H_ */ diff --git a/mission/devices/devicedefinitions/SyrlinksDefinitions.h b/mission/devices/devicedefinitions/SyrlinksDefinitions.h index ba719ebb..7aa75b99 100644 --- a/mission/devices/devicedefinitions/SyrlinksDefinitions.h +++ b/mission/devices/devicedefinitions/SyrlinksDefinitions.h @@ -17,7 +17,8 @@ namespace SYRLINKS { static const DeviceCommandId_t ACK_REPLY = 0x06; static const DeviceCommandId_t READ_TX_STATUS = 0x07; static const DeviceCommandId_t READ_TX_WAVEFORM = 0x08; - static const DeviceCommandId_t READ_TX_AGC_VALUE = 0x09; + static const DeviceCommandId_t READ_TX_AGC_VALUE_HIGH_BYTE = 0x09; + static const DeviceCommandId_t READ_TX_AGC_VALUE_LOW_BYTE = 0x0A; /** Size of a simple transmission success response */ static const uint8_t ACK_SIZE = 11; @@ -26,12 +27,10 @@ namespace SYRLINKS { static const uint8_t MESSAGE_HEADER_SIZE = 5; /** Size of reply to an rx status registers request */ static const uint8_t RX_STATUS_REGISTERS_REPLY_SIZE = 49; - static const uint8_t READ_TX_STATUS_REPLY_SIZE = 13; - static const uint8_t READ_TX_WAVEFORM_REPLY_SIZE = 13; - static const uint8_t READ_TX_AGC_VALUE_REPLY_SIZE = 15; + static const uint8_t READ_ONE_REGISTER_REPLY_SIE = 13; - static const uint8_t RX_DATASET_ID = READ_RX_STATUS_REGISTERS; - static const uint8_t TX_DATASET_ID = READ_TX_STATUS; + static const uint8_t RX_DATASET_ID = 0x1; + static const uint8_t TX_DATASET_ID = 0x2; static const size_t MAX_REPLY_SIZE = RX_STATUS_REGISTERS_REPLY_SIZE; static const size_t MAX_COMMAND_SIZE = 15; @@ -39,7 +38,7 @@ namespace SYRLINKS { static const size_t CRC_FIELD_SIZE = 4; static const uint8_t RX_DATASET_SIZE = 8; - static const uint8_t TX_DATASET_SIZE = 1; + static const uint8_t TX_DATASET_SIZE = 3; enum SyrlinksPoolIds: lp_id_t { RX_STATUS, diff --git a/tmtc b/tmtc index 1d5fe4eb..81cd88f5 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 1d5fe4ebc7165c2a4979c5f9be9cfa0324e366fb +Subproject commit 81cd88f5211e0d9853ba3d9dd7611a9c2149cd55 From 37bf20b925093668abcb76f8bf8fc9db7887f69b Mon Sep 17 00:00:00 2001 From: "Jakob.Meier" Date: Thu, 4 Mar 2021 18:22:04 +0100 Subject: [PATCH 12/79] commented out setting pcdu to normal mode --- bsp_q7s/ObjectFactory.cpp | 24 ++++++++++++------------ 1 file changed, 12 insertions(+), 12 deletions(-) diff --git a/bsp_q7s/ObjectFactory.cpp b/bsp_q7s/ObjectFactory.cpp index 2c70e9c7..f17dadda 100644 --- a/bsp_q7s/ObjectFactory.cpp +++ b/bsp_q7s/ObjectFactory.cpp @@ -125,37 +125,37 @@ void ObjectFactory::produce(){ new LinuxLibgpioIF(objects::GPIO_IF); #if TE0720 == 0 /* Pin H2-11 on stack connector */ - GpioConfig_t gpioConfigHeater0(std::string("gpiochip7"), 15, + GpioConfig_t gpioConfigHeater0(std::string("gpiochip7"), 16, std::string("Heater0"), gpio::OUT, 0); heaterGpiosCookie->addGpio(gpioIds::HEATER_0, gpioConfigHeater0); /* Pin H2-12 on stack connector */ - GpioConfig_t gpioConfigHeater1(std::string("gpiochip7"), 11, + GpioConfig_t gpioConfigHeater1(std::string("gpiochip7"), 12, std::string("Heater1"), gpio::OUT, 0); heaterGpiosCookie->addGpio(gpioIds::HEATER_1, gpioConfigHeater1); /* Pin H2-13 on stack connector */ - GpioConfig_t gpioConfigHeater2(std::string("gpiochip7"), 17, + GpioConfig_t gpioConfigHeater2(std::string("gpiochip7"), 7, std::string("Heater2"), gpio::OUT, 0); heaterGpiosCookie->addGpio(gpioIds::HEATER_2, gpioConfigHeater2); - GpioConfig_t gpioConfigHeater3(std::string("gpiochip7"), 13, + GpioConfig_t gpioConfigHeater3(std::string("gpiochip7"), 5, std::string("Heater3"), gpio::OUT, 0); heaterGpiosCookie->addGpio(gpioIds::HEATER_3, gpioConfigHeater3); - GpioConfig_t gpioConfigHeater4(std::string("gpiochip7"), 21, + GpioConfig_t gpioConfigHeater4(std::string("gpiochip7"), 3, std::string("Heater4"), gpio::OUT, 0); heaterGpiosCookie->addGpio(gpioIds::HEATER_4, gpioConfigHeater4); - GpioConfig_t gpioConfigHeater5(std::string("gpiochip7"), 23, + GpioConfig_t gpioConfigHeater5(std::string("gpiochip7"), 0, std::string("Heater5"), gpio::OUT, 0); heaterGpiosCookie->addGpio(gpioIds::HEATER_5, gpioConfigHeater5); - GpioConfig_t gpioConfigHeater6(std::string("gpiochip7"), 19, + GpioConfig_t gpioConfigHeater6(std::string("gpiochip7"), 1, std::string("Heater6"), gpio::OUT, 0); heaterGpiosCookie->addGpio(gpioIds::HEATER_6, gpioConfigHeater6); - GpioConfig_t gpioConfigHeater7(std::string("gpiochip7"), 10, + GpioConfig_t gpioConfigHeater7(std::string("gpiochip7"), 11, std::string("Heater7"), gpio::OUT, 0); heaterGpiosCookie->addGpio(gpioIds::HEATER_7, gpioConfigHeater7); @@ -163,12 +163,12 @@ void ObjectFactory::produce(){ pcduSwitches::TCS_BOARD_8V_HEATER_IN); GpioCookie* solarArrayDeplCookie = new GpioCookie; - GpioConfig_t gpioConfigDeplSA1(std::string("gpiochip7"), 22, + GpioConfig_t gpioConfigDeplSA0(std::string("gpiochip7"), 4, std::string("DeplSA1"), gpio::OUT, 0); - solarArrayDeplCookie->addGpio(gpioIds::DEPLSA1, gpioConfigDeplSA1); - GpioConfig_t gpioConfigDeplSA2(std::string("gpiochip7"), 20, + solarArrayDeplCookie->addGpio(gpioIds::DEPLSA1, gpioConfigDeplSA0); + GpioConfig_t gpioConfigDeplSA1(std::string("gpiochip7"), 2, std::string("DeplSA2"), gpio::OUT, 0); - solarArrayDeplCookie->addGpio(gpioIds::DEPLSA2, gpioConfigDeplSA2); + solarArrayDeplCookie->addGpio(gpioIds::DEPLSA2, gpioConfigDeplSA1); //TODO: Find out burn time. For now set to 1000 ms. new SolarArrayDeploymentHandler(objects::SOLAR_ARRAY_DEPL_HANDLER, objects::GPIO_IF, From 4291df77b16934e7f1169d48aca5a3918c43bdfd Mon Sep 17 00:00:00 2001 From: "Jakob.Meier" Date: Thu, 4 Mar 2021 18:29:28 +0100 Subject: [PATCH 13/79] moved some files --- .gitmodules | 5 +- README.md | 11 +- bsp_hosted/InitMission.cpp | 204 +-- bsp_hosted/InitMission.h | 2 +- bsp_hosted/fsfwconfig/OBSWConfig.h | 4 +- bsp_hosted/fsfwconfig/devices/gpioIds.h | 35 + .../fsfwconfig/devices/powerSwitcherList.h | 58 + .../fsfwconfig/objects/systemObjectList.h | 15 + bsp_hosted/main.cpp | 2 +- bsp_q7s/CMakeLists.txt | 1 + bsp_q7s/InitMission.h | 2 +- bsp_q7s/boardtest/CMakeLists.txt | 1 - bsp_q7s/devices/CMakeLists.txt | 4 + bsp_q7s/devices/HeaterHandler.cpp | 356 ++++++ bsp_q7s/devices/HeaterHandler.h | 177 +++ .../devices/SolarArrayDeploymentHandler.cpp | 201 +++ bsp_q7s/devices/SolarArrayDeploymentHandler.h | 160 +++ bsp_q7s/main.cpp | 6 +- bsp_rpi/CMakeLists.txt | 7 +- bsp_rpi/InitMission.cpp | 250 ++-- bsp_rpi/InitMission.h | 2 +- bsp_rpi/ObjectFactory.cpp | 103 +- bsp_rpi/boardconfig/rpi_config.h | 24 + bsp_rpi/boardtest/CMakeLists.txt | 2 - bsp_rpi/gpio/CMakeLists.txt | 9 + bsp_rpi/gpio/GPIORPi.cpp | 36 + bsp_rpi/gpio/GPIORPi.h | 26 + bsp_rpi/main.cpp | 12 +- cmake/scripts/Host/create_cmake_debug_cfg.sh | 3 +- .../scripts/Host/create_cmake_release_cfg.sh | 3 +- cmake/scripts/RPi/create_cmake_debug_cfg.sh | 4 +- cmake/scripts/RPi/create_cmake_release_cfg.sh | 4 +- .../RPi/create_cmake_relwithdeb_cfg.sh | 4 +- cmake/scripts/cmake_build_config.py | 5 +- common/CMakeLists.txt | 1 + common/config/CMakeLists.txt | 3 + common/config/commonConfig.h | 7 + common/config/lwgps_opts.h | 44 + fsfwconfig/OBSWVersion.h | 4 +- fsfwconfig/devices/addresses.h | 18 +- fsfwconfig/devices/gpioIds.h | 12 +- .../pollingsequence/PollingSequenceFactory.h | 2 + linux/boardtest/CMakeLists.txt | 10 + linux/boardtest/I2cTestClass.cpp | 8 + linux/boardtest/I2cTestClass.h | 17 + linux/boardtest/LibgpiodTest.cpp | 99 ++ {bsp_q7s => linux}/boardtest/LibgpiodTest.h | 10 +- linux/boardtest/SpiTestClass.cpp | 231 ++++ linux/boardtest/SpiTestClass.h | 61 + linux/boardtest/UartTestClass.cpp | 8 + linux/boardtest/UartTestClass.h | 15 + linux/csp/CspCookie.h | 6 +- linux/gpio/CMakeLists.txt | 4 + linux/gpio/GpioCookie.cpp | 28 +- linux/gpio/GpioCookie.h | 53 +- linux/gpio/GpioIF.h | 16 +- linux/gpio/LinuxLibgpioIF.h | 40 +- linux/gpio/gpioDefinitions.h | 92 ++ linux/i2c/I2cComIF.h | 10 +- linux/i2c/I2cCookie.cpp | 3 +- linux/spi/CMakeLists.txt | 2 + linux/spi/SpiComIF.cpp | 308 +++++ linux/spi/SpiComIF.h | 63 + linux/spi/SpiCookie.cpp | 99 ++ linux/spi/SpiCookie.h | 113 ++ linux/spi/spiDefinitions.h | 15 + linux/utility/CMakeLists.txt | 7 + linux/utility/Utility.cpp | 52 + linux/utility/Utility.h | 36 + .../boardtest => misc/archive}/RPiGPIO.cpp | 0 {bsp_rpi/boardtest => misc/archive}/RPiGPIO.h | 0 .../Host/eive-mingw-debug-cmake.launch | 4 +- mission/core/GenericFactory.cpp | 5 +- mission/devices/MGMHandlerLIS3MDL.cpp | 695 ++++++----- mission/devices/MGMHandlerLIS3MDL.h | 234 ++-- mission/devices/PCDUHandler.cpp | 7 +- mission/devices/PCDUHandler.h | 3 +- mission/devices/PDU2Handler.cpp | 2 +- mission/devices/Tmp1075Handler.cpp | 2 +- .../MGMHandlerLIS3Definitions.h | 36 +- mission/utility/InitMission.h | 22 + test/testtasks/TestTask.cpp | 114 +- test/testtasks/TestTask.h | 5 +- thirdparty/libcsp/CMakeLists.txt | 12 + .../libcsp/bindings/python/libcsp/__init__.py | 6 + thirdparty/libcsp/doc/example.rst | 123 ++ thirdparty/libcsp/doc/history.rst | 17 + thirdparty/libcsp/doc/interfaces.rst | 95 ++ thirdparty/libcsp/doc/libcsp.rst | 21 + thirdparty/libcsp/doc/memory.rst | 28 + thirdparty/libcsp/doc/mtu.rst | 19 + thirdparty/libcsp/doc/protocolstack.rst | 54 + thirdparty/libcsp/doc/structure.rst | 27 + thirdparty/libcsp/doc/topology.rst | 26 + thirdparty/libcsp/examples/csp_if_fifo.c | 165 +++ .../libcsp/examples/csp_if_fifo_windows.c | 225 ++++ thirdparty/libcsp/examples/kiss.c | 151 +++ .../python_bindings_example_client.py | 42 + .../python_bindings_example_client_can.py | 30 + .../python_bindings_example_server.py | 72 ++ thirdparty/libcsp/examples/simple.c | 200 +++ thirdparty/libcsp/examples/zmqproxy.c | 82 ++ thirdparty/libcsp/include/CMakeLists.txt | 9 + .../libcsp/include/csp/arch/csp_clock.h | 60 + .../libcsp/include/csp/arch/csp_malloc.h | 39 + .../libcsp/include/csp/arch/csp_queue.h | 49 + .../libcsp/include/csp/arch/csp_semaphore.h | 109 ++ .../libcsp/include/csp/arch/csp_system.h | 74 ++ .../libcsp/include/csp/arch/csp_thread.h | 100 ++ thirdparty/libcsp/include/csp/arch/csp_time.h | 57 + .../include/csp/arch/posix/pthread_queue.h | 118 ++ .../libcsp/include/csp/crypto/csp_hmac.h | 73 ++ .../libcsp/include/csp/crypto/csp_sha1.h | 81 ++ .../libcsp/include/csp/crypto/csp_xtea.h | 52 + thirdparty/libcsp/include/csp/csp.h | 545 ++++++++ .../libcsp/include/csp/csp_autoconfig.h | 48 + thirdparty/libcsp/include/csp/csp_buffer.h | 92 ++ thirdparty/libcsp/include/csp/csp_cmp.h | 189 +++ thirdparty/libcsp/include/csp/csp_crc32.h | 63 + thirdparty/libcsp/include/csp/csp_debug.h | 150 +++ thirdparty/libcsp/include/csp/csp_endian.h | 170 +++ thirdparty/libcsp/include/csp/csp_error.h | 50 + thirdparty/libcsp/include/csp/csp_iflist.h | 56 + thirdparty/libcsp/include/csp/csp_interface.h | 54 + thirdparty/libcsp/include/csp/csp_platform.h | 56 + thirdparty/libcsp/include/csp/csp_rtable.h | 149 +++ thirdparty/libcsp/include/csp/csp_types.h | 235 ++++ .../include/csp/drivers/can_socketcan.h | 22 + thirdparty/libcsp/include/csp/drivers/i2c.h | 120 ++ thirdparty/libcsp/include/csp/drivers/usart.h | 107 ++ .../include/csp/interfaces/csp_if_can.h | 76 ++ .../include/csp/interfaces/csp_if_i2c.h | 51 + .../include/csp/interfaces/csp_if_kiss.h | 110 ++ .../libcsp/include/csp/interfaces/csp_if_lo.h | 38 + .../include/csp/interfaces/csp_if_zmqhub.h | 26 + thirdparty/libcsp/libcsp.mk | 12 + thirdparty/libcsp/src/CMakeLists.txt | 27 + thirdparty/libcsp/src/arch/CMakeLists.txt | 3 + .../libcsp/src/arch/freertos/csp_malloc.c | 33 + .../libcsp/src/arch/freertos/csp_queue.c | 66 + .../libcsp/src/arch/freertos/csp_semaphore.c | 96 ++ .../libcsp/src/arch/freertos/csp_system.c | 139 +++ .../libcsp/src/arch/freertos/csp_thread.c | 38 + .../libcsp/src/arch/freertos/csp_time.c | 46 + .../libcsp/src/arch/macosx/csp_malloc.c | 31 + thirdparty/libcsp/src/arch/macosx/csp_queue.c | 64 + .../libcsp/src/arch/macosx/csp_semaphore.c | 105 ++ .../libcsp/src/arch/macosx/csp_system.c | 99 ++ .../libcsp/src/arch/macosx/csp_thread.c | 31 + thirdparty/libcsp/src/arch/macosx/csp_time.c | 65 + .../libcsp/src/arch/macosx/pthread_queue.c | 179 +++ .../libcsp/src/arch/posix/CMakeLists.txt | 9 + thirdparty/libcsp/src/arch/posix/csp_malloc.c | 31 + thirdparty/libcsp/src/arch/posix/csp_queue.c | 64 + .../libcsp/src/arch/posix/csp_semaphore.c | 164 +++ thirdparty/libcsp/src/arch/posix/csp_system.c | 131 ++ thirdparty/libcsp/src/arch/posix/csp_thread.c | 55 + thirdparty/libcsp/src/arch/posix/csp_time.c | 54 + .../libcsp/src/arch/posix/pthread_queue.c | 243 ++++ thirdparty/libcsp/src/arch/windows/README | 18 + .../libcsp/src/arch/windows/csp_malloc.c | 9 + .../libcsp/src/arch/windows/csp_queue.c | 40 + .../libcsp/src/arch/windows/csp_semaphore.c | 74 ++ .../libcsp/src/arch/windows/csp_system.c | 60 + .../libcsp/src/arch/windows/csp_thread.c | 11 + thirdparty/libcsp/src/arch/windows/csp_time.c | 20 + .../libcsp/src/arch/windows/windows_glue.h | 23 + .../libcsp/src/arch/windows/windows_queue.c | 91 ++ .../libcsp/src/arch/windows/windows_queue.h | 41 + thirdparty/libcsp/src/bindings/python/pycsp.c | 1052 ++++++++++++++++ thirdparty/libcsp/src/crypto/CMakeLists.txt | 5 + thirdparty/libcsp/src/crypto/csp_hmac.c | 202 +++ thirdparty/libcsp/src/crypto/csp_sha1.c | 217 ++++ thirdparty/libcsp/src/crypto/csp_xtea.c | 134 ++ thirdparty/libcsp/src/csp_bridge.c | 94 ++ thirdparty/libcsp/src/csp_buffer.c | 224 ++++ thirdparty/libcsp/src/csp_conn.c | 498 ++++++++ thirdparty/libcsp/src/csp_conn.h | 112 ++ thirdparty/libcsp/src/csp_crc32.c | 140 +++ thirdparty/libcsp/src/csp_debug.c | 133 ++ thirdparty/libcsp/src/csp_dedup.c | 66 + thirdparty/libcsp/src/csp_dedup.h | 31 + thirdparty/libcsp/src/csp_endian.c | 204 +++ thirdparty/libcsp/src/csp_hex_dump.c | 55 + thirdparty/libcsp/src/csp_iflist.c | 100 ++ thirdparty/libcsp/src/csp_io.c | 502 ++++++++ thirdparty/libcsp/src/csp_io.h | 47 + thirdparty/libcsp/src/csp_port.c | 105 ++ thirdparty/libcsp/src/csp_port.h | 55 + thirdparty/libcsp/src/csp_promisc.c | 82 ++ thirdparty/libcsp/src/csp_promisc.h | 30 + thirdparty/libcsp/src/csp_qfifo.c | 149 +++ thirdparty/libcsp/src/csp_qfifo.h | 54 + thirdparty/libcsp/src/csp_route.c | 346 ++++++ thirdparty/libcsp/src/csp_route.h | 24 + thirdparty/libcsp/src/csp_service_handler.c | 334 +++++ thirdparty/libcsp/src/csp_services.c | 233 ++++ thirdparty/libcsp/src/csp_sfp.c | 170 +++ thirdparty/libcsp/src/drivers/CMakeLists.txt | 1 + .../libcsp/src/drivers/can/CMakeLists.txt | 3 + .../libcsp/src/drivers/can/can_socketcan.c | 201 +++ .../libcsp/src/drivers/usart/usart_linux.c | 254 ++++ .../libcsp/src/drivers/usart/usart_windows.c | 230 ++++ .../libcsp/src/interfaces/CMakeLists.txt | 7 + thirdparty/libcsp/src/interfaces/csp_if_can.c | 279 +++++ .../libcsp/src/interfaces/csp_if_can_pbuf.c | 77 ++ .../libcsp/src/interfaces/csp_if_can_pbuf.h | 31 + thirdparty/libcsp/src/interfaces/csp_if_i2c.c | 116 ++ .../libcsp/src/interfaces/csp_if_kiss.c | 260 ++++ thirdparty/libcsp/src/interfaces/csp_if_lo.c | 61 + thirdparty/libcsp/src/rtable/CMakeLists.txt | 3 + .../libcsp/src/rtable/csp_rtable_cidr.c | 233 ++++ .../libcsp/src/rtable/csp_rtable_static.c | 128 ++ .../libcsp/src/transport/CMakeLists.txt | 4 + thirdparty/libcsp/src/transport/csp_rdp.c | 1102 +++++++++++++++++ .../libcsp/src/transport/csp_transport.h | 46 + thirdparty/libcsp/src/transport/csp_udp.c | 49 + thirdparty/libcsp/utils/cfpsplit.py | 52 + thirdparty/libcsp/utils/cspsplit.py | 52 + 219 files changed, 18872 insertions(+), 874 deletions(-) create mode 100644 bsp_hosted/fsfwconfig/devices/gpioIds.h create mode 100644 bsp_hosted/fsfwconfig/devices/powerSwitcherList.h create mode 100644 bsp_q7s/devices/CMakeLists.txt create mode 100644 bsp_q7s/devices/HeaterHandler.cpp create mode 100644 bsp_q7s/devices/HeaterHandler.h create mode 100644 bsp_q7s/devices/SolarArrayDeploymentHandler.cpp create mode 100644 bsp_q7s/devices/SolarArrayDeploymentHandler.h create mode 100644 bsp_rpi/boardconfig/rpi_config.h create mode 100644 bsp_rpi/gpio/CMakeLists.txt create mode 100644 bsp_rpi/gpio/GPIORPi.cpp create mode 100644 bsp_rpi/gpio/GPIORPi.h create mode 100644 common/CMakeLists.txt create mode 100644 common/config/CMakeLists.txt create mode 100644 common/config/commonConfig.h create mode 100644 common/config/lwgps_opts.h create mode 100644 linux/boardtest/CMakeLists.txt create mode 100644 linux/boardtest/I2cTestClass.cpp create mode 100644 linux/boardtest/I2cTestClass.h create mode 100644 linux/boardtest/LibgpiodTest.cpp rename {bsp_q7s => linux}/boardtest/LibgpiodTest.h (74%) create mode 100644 linux/boardtest/SpiTestClass.cpp create mode 100644 linux/boardtest/SpiTestClass.h create mode 100644 linux/boardtest/UartTestClass.cpp create mode 100644 linux/boardtest/UartTestClass.h create mode 100644 linux/gpio/gpioDefinitions.h create mode 100644 linux/spi/SpiComIF.cpp create mode 100644 linux/spi/SpiComIF.h create mode 100644 linux/spi/SpiCookie.cpp create mode 100644 linux/spi/SpiCookie.h create mode 100644 linux/spi/spiDefinitions.h create mode 100644 linux/utility/CMakeLists.txt create mode 100644 linux/utility/Utility.cpp create mode 100644 linux/utility/Utility.h rename {bsp_rpi/boardtest => misc/archive}/RPiGPIO.cpp (100%) rename {bsp_rpi/boardtest => misc/archive}/RPiGPIO.h (100%) create mode 100644 mission/utility/InitMission.h create mode 100644 thirdparty/libcsp/CMakeLists.txt create mode 100644 thirdparty/libcsp/bindings/python/libcsp/__init__.py create mode 100644 thirdparty/libcsp/doc/example.rst create mode 100644 thirdparty/libcsp/doc/history.rst create mode 100644 thirdparty/libcsp/doc/interfaces.rst create mode 100644 thirdparty/libcsp/doc/libcsp.rst create mode 100644 thirdparty/libcsp/doc/memory.rst create mode 100644 thirdparty/libcsp/doc/mtu.rst create mode 100644 thirdparty/libcsp/doc/protocolstack.rst create mode 100644 thirdparty/libcsp/doc/structure.rst create mode 100644 thirdparty/libcsp/doc/topology.rst create mode 100644 thirdparty/libcsp/examples/csp_if_fifo.c create mode 100644 thirdparty/libcsp/examples/csp_if_fifo_windows.c create mode 100644 thirdparty/libcsp/examples/kiss.c create mode 100644 thirdparty/libcsp/examples/python_bindings_example_client.py create mode 100644 thirdparty/libcsp/examples/python_bindings_example_client_can.py create mode 100644 thirdparty/libcsp/examples/python_bindings_example_server.py create mode 100644 thirdparty/libcsp/examples/simple.c create mode 100644 thirdparty/libcsp/examples/zmqproxy.c create mode 100644 thirdparty/libcsp/include/CMakeLists.txt create mode 100644 thirdparty/libcsp/include/csp/arch/csp_clock.h create mode 100644 thirdparty/libcsp/include/csp/arch/csp_malloc.h create mode 100644 thirdparty/libcsp/include/csp/arch/csp_queue.h create mode 100644 thirdparty/libcsp/include/csp/arch/csp_semaphore.h create mode 100644 thirdparty/libcsp/include/csp/arch/csp_system.h create mode 100644 thirdparty/libcsp/include/csp/arch/csp_thread.h create mode 100644 thirdparty/libcsp/include/csp/arch/csp_time.h create mode 100644 thirdparty/libcsp/include/csp/arch/posix/pthread_queue.h create mode 100644 thirdparty/libcsp/include/csp/crypto/csp_hmac.h create mode 100644 thirdparty/libcsp/include/csp/crypto/csp_sha1.h create mode 100644 thirdparty/libcsp/include/csp/crypto/csp_xtea.h create mode 100644 thirdparty/libcsp/include/csp/csp.h create mode 100644 thirdparty/libcsp/include/csp/csp_autoconfig.h create mode 100644 thirdparty/libcsp/include/csp/csp_buffer.h create mode 100644 thirdparty/libcsp/include/csp/csp_cmp.h create mode 100644 thirdparty/libcsp/include/csp/csp_crc32.h create mode 100644 thirdparty/libcsp/include/csp/csp_debug.h create mode 100644 thirdparty/libcsp/include/csp/csp_endian.h create mode 100644 thirdparty/libcsp/include/csp/csp_error.h create mode 100644 thirdparty/libcsp/include/csp/csp_iflist.h create mode 100644 thirdparty/libcsp/include/csp/csp_interface.h create mode 100644 thirdparty/libcsp/include/csp/csp_platform.h create mode 100644 thirdparty/libcsp/include/csp/csp_rtable.h create mode 100644 thirdparty/libcsp/include/csp/csp_types.h create mode 100644 thirdparty/libcsp/include/csp/drivers/can_socketcan.h create mode 100644 thirdparty/libcsp/include/csp/drivers/i2c.h create mode 100644 thirdparty/libcsp/include/csp/drivers/usart.h create mode 100644 thirdparty/libcsp/include/csp/interfaces/csp_if_can.h create mode 100644 thirdparty/libcsp/include/csp/interfaces/csp_if_i2c.h create mode 100644 thirdparty/libcsp/include/csp/interfaces/csp_if_kiss.h create mode 100644 thirdparty/libcsp/include/csp/interfaces/csp_if_lo.h create mode 100644 thirdparty/libcsp/include/csp/interfaces/csp_if_zmqhub.h create mode 100644 thirdparty/libcsp/libcsp.mk create mode 100644 thirdparty/libcsp/src/CMakeLists.txt create mode 100644 thirdparty/libcsp/src/arch/CMakeLists.txt create mode 100644 thirdparty/libcsp/src/arch/freertos/csp_malloc.c create mode 100644 thirdparty/libcsp/src/arch/freertos/csp_queue.c create mode 100644 thirdparty/libcsp/src/arch/freertos/csp_semaphore.c create mode 100644 thirdparty/libcsp/src/arch/freertos/csp_system.c create mode 100644 thirdparty/libcsp/src/arch/freertos/csp_thread.c create mode 100644 thirdparty/libcsp/src/arch/freertos/csp_time.c create mode 100644 thirdparty/libcsp/src/arch/macosx/csp_malloc.c create mode 100644 thirdparty/libcsp/src/arch/macosx/csp_queue.c create mode 100644 thirdparty/libcsp/src/arch/macosx/csp_semaphore.c create mode 100644 thirdparty/libcsp/src/arch/macosx/csp_system.c create mode 100644 thirdparty/libcsp/src/arch/macosx/csp_thread.c create mode 100644 thirdparty/libcsp/src/arch/macosx/csp_time.c create mode 100644 thirdparty/libcsp/src/arch/macosx/pthread_queue.c create mode 100644 thirdparty/libcsp/src/arch/posix/CMakeLists.txt create mode 100644 thirdparty/libcsp/src/arch/posix/csp_malloc.c create mode 100644 thirdparty/libcsp/src/arch/posix/csp_queue.c create mode 100644 thirdparty/libcsp/src/arch/posix/csp_semaphore.c create mode 100644 thirdparty/libcsp/src/arch/posix/csp_system.c create mode 100644 thirdparty/libcsp/src/arch/posix/csp_thread.c create mode 100644 thirdparty/libcsp/src/arch/posix/csp_time.c create mode 100644 thirdparty/libcsp/src/arch/posix/pthread_queue.c create mode 100644 thirdparty/libcsp/src/arch/windows/README create mode 100644 thirdparty/libcsp/src/arch/windows/csp_malloc.c create mode 100644 thirdparty/libcsp/src/arch/windows/csp_queue.c create mode 100644 thirdparty/libcsp/src/arch/windows/csp_semaphore.c create mode 100644 thirdparty/libcsp/src/arch/windows/csp_system.c create mode 100644 thirdparty/libcsp/src/arch/windows/csp_thread.c create mode 100644 thirdparty/libcsp/src/arch/windows/csp_time.c create mode 100644 thirdparty/libcsp/src/arch/windows/windows_glue.h create mode 100644 thirdparty/libcsp/src/arch/windows/windows_queue.c create mode 100644 thirdparty/libcsp/src/arch/windows/windows_queue.h create mode 100644 thirdparty/libcsp/src/bindings/python/pycsp.c create mode 100644 thirdparty/libcsp/src/crypto/CMakeLists.txt create mode 100644 thirdparty/libcsp/src/crypto/csp_hmac.c create mode 100644 thirdparty/libcsp/src/crypto/csp_sha1.c create mode 100644 thirdparty/libcsp/src/crypto/csp_xtea.c create mode 100644 thirdparty/libcsp/src/csp_bridge.c create mode 100644 thirdparty/libcsp/src/csp_buffer.c create mode 100644 thirdparty/libcsp/src/csp_conn.c create mode 100644 thirdparty/libcsp/src/csp_conn.h create mode 100644 thirdparty/libcsp/src/csp_crc32.c create mode 100644 thirdparty/libcsp/src/csp_debug.c create mode 100644 thirdparty/libcsp/src/csp_dedup.c create mode 100644 thirdparty/libcsp/src/csp_dedup.h create mode 100644 thirdparty/libcsp/src/csp_endian.c create mode 100644 thirdparty/libcsp/src/csp_hex_dump.c create mode 100644 thirdparty/libcsp/src/csp_iflist.c create mode 100644 thirdparty/libcsp/src/csp_io.c create mode 100644 thirdparty/libcsp/src/csp_io.h create mode 100644 thirdparty/libcsp/src/csp_port.c create mode 100644 thirdparty/libcsp/src/csp_port.h create mode 100644 thirdparty/libcsp/src/csp_promisc.c create mode 100644 thirdparty/libcsp/src/csp_promisc.h create mode 100644 thirdparty/libcsp/src/csp_qfifo.c create mode 100644 thirdparty/libcsp/src/csp_qfifo.h create mode 100644 thirdparty/libcsp/src/csp_route.c create mode 100644 thirdparty/libcsp/src/csp_route.h create mode 100644 thirdparty/libcsp/src/csp_service_handler.c create mode 100644 thirdparty/libcsp/src/csp_services.c create mode 100644 thirdparty/libcsp/src/csp_sfp.c create mode 100644 thirdparty/libcsp/src/drivers/CMakeLists.txt create mode 100644 thirdparty/libcsp/src/drivers/can/CMakeLists.txt create mode 100644 thirdparty/libcsp/src/drivers/can/can_socketcan.c create mode 100644 thirdparty/libcsp/src/drivers/usart/usart_linux.c create mode 100644 thirdparty/libcsp/src/drivers/usart/usart_windows.c create mode 100644 thirdparty/libcsp/src/interfaces/CMakeLists.txt create mode 100644 thirdparty/libcsp/src/interfaces/csp_if_can.c create mode 100644 thirdparty/libcsp/src/interfaces/csp_if_can_pbuf.c create mode 100644 thirdparty/libcsp/src/interfaces/csp_if_can_pbuf.h create mode 100644 thirdparty/libcsp/src/interfaces/csp_if_i2c.c create mode 100644 thirdparty/libcsp/src/interfaces/csp_if_kiss.c create mode 100644 thirdparty/libcsp/src/interfaces/csp_if_lo.c create mode 100644 thirdparty/libcsp/src/rtable/CMakeLists.txt create mode 100644 thirdparty/libcsp/src/rtable/csp_rtable_cidr.c create mode 100644 thirdparty/libcsp/src/rtable/csp_rtable_static.c create mode 100644 thirdparty/libcsp/src/transport/CMakeLists.txt create mode 100644 thirdparty/libcsp/src/transport/csp_rdp.c create mode 100644 thirdparty/libcsp/src/transport/csp_transport.h create mode 100644 thirdparty/libcsp/src/transport/csp_udp.c create mode 100644 thirdparty/libcsp/utils/cfpsplit.py create mode 100644 thirdparty/libcsp/utils/cspsplit.py diff --git a/.gitmodules b/.gitmodules index dae431d4..7af82082 100644 --- a/.gitmodules +++ b/.gitmodules @@ -1,5 +1,5 @@ [submodule "etl"] - path = etl + path = thirdparty/etl url = https://github.com/ETLCPP/etl.git [submodule "arduino"] path = arduino @@ -10,3 +10,6 @@ [submodule "tmtc"] path = tmtc url = https://egit.irs.uni-stuttgart.de/eive/eive_tmtc.git +[submodule "thirdparty/lwgps"] + path = thirdparty/lwgps + url = https://github.com/rmspacefish/lwgps.git diff --git a/README.md b/README.md index 4d8c0ecf..6d38fd66 100644 --- a/README.md +++ b/README.md @@ -208,7 +208,16 @@ or ssh eive@192.168.199.227 ``` -To access the console of the Q7S run the following: +If the static IP address of the Q7S has already been set, +you can access it with ssh + +```sh +ssh root@192.168.133.10 +``` + +If this has not been done yet, you can access the serial +console of the Q7S like this to set it + ```sh picocom -b 115200 /dev/ttyUSB0 ``` diff --git a/bsp_hosted/InitMission.cpp b/bsp_hosted/InitMission.cpp index 39dcafff..06bc5646 100644 --- a/bsp_hosted/InitMission.cpp +++ b/bsp_hosted/InitMission.cpp @@ -11,9 +11,10 @@ #include #include +#include + #include -// This is configured for linux without \cr #ifdef LINUX ServiceInterfaceStream sif::debug("DEBUG"); ServiceInterfaceStream sif::info("INFO"); @@ -28,9 +29,9 @@ ServiceInterfaceStream sif::error("ERROR", true, false, true); ObjectManagerIF *objectManager = nullptr; -void InitMission::initMission() { - sif::info << "Building global objects.." << std::endl; - /* Instantiate global object manager and also create all objects */ +void initmission::initMission() { + sif::info << "Building global objects.." << std::endl; + /* Instantiate global object manager and also create all objects */ objectManager = new ObjectManager(ObjectFactory::produce); sif::info << "Initializing all objects.." << std::endl; objectManager->initialize(); @@ -39,117 +40,120 @@ void InitMission::initMission() { initTasks(); } -void InitMission::initTasks(){ - /* TMTC Distribution */ - PeriodicTaskIF* TmTcDistributor = TaskFactory::instance()-> - createPeriodicTask("DIST", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, - 0.100, nullptr); - ReturnValue_t result = TmTcDistributor->addComponent( - objects::CCSDS_PACKET_DISTRIBUTOR); - if(result!=HasReturnvaluesIF::RETURN_OK){ - sif::error << "Object add component failed" << std::endl; - } - result = TmTcDistributor->addComponent(objects::PUS_PACKET_DISTRIBUTOR); - if(result!=HasReturnvaluesIF::RETURN_OK){ - sif::error << "Object add component failed" << std::endl; - } - result = TmTcDistributor->addComponent(objects::TM_FUNNEL); +void initmission::initTasks() { + TaskFactory* factory = TaskFactory::instance(); + if(factory == nullptr) { + /* Should never happen ! */ + return; + } +#if OBSW_PRINT_MISSED_DEADLINES == 1 + void (*missedDeadlineFunc) (void) = TaskFactory::printMissedDeadline; +#else + void (*missedDeadlineFunc) (void) = nullptr; +#endif + + /* TMTC Distribution */ + PeriodicTaskIF* tmTcDistributor = factory->createPeriodicTask( + "DIST", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc); + ReturnValue_t result = tmTcDistributor->addComponent( + objects::CCSDS_PACKET_DISTRIBUTOR); + if(result != HasReturnvaluesIF::RETURN_OK){ + sif::error << "Object add component failed" << std::endl; + } + result = tmTcDistributor->addComponent(objects::PUS_PACKET_DISTRIBUTOR); + if(result != HasReturnvaluesIF::RETURN_OK){ + sif::error << "Object add component failed" << std::endl; + } + result = tmTcDistributor->addComponent(objects::TM_FUNNEL); if(result != HasReturnvaluesIF::RETURN_OK) { - sif::error << "Object add component failed" << std::endl; + sif::error << "Object add component failed" << std::endl; } /* UDP bridge */ - PeriodicTaskIF* UdpBridgeTask = TaskFactory::instance()->createPeriodicTask( - "UDP_UNIX_BRIDGE", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, - 0.2, nullptr); - result = UdpBridgeTask->addComponent(objects::UDP_BRIDGE); + PeriodicTaskIF* udpBridgeTask = factory->createPeriodicTask( + "UDP_UNIX_BRIDGE", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc); + result = udpBridgeTask->addComponent(objects::UDP_BRIDGE); if(result != HasReturnvaluesIF::RETURN_OK) { - sif::error << "Add component UDP Unix Bridge failed" << std::endl; + sif::error << "Add component UDP Unix Bridge failed" << std::endl; } - PeriodicTaskIF* UdpPollingTask = TaskFactory::instance()-> - createPeriodicTask("UDP_POLLING", 80, - PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, nullptr); - result = UdpPollingTask->addComponent(objects::UDP_POLLING_TASK); + PeriodicTaskIF* udpPollingTask = factory->createPeriodicTask( + "UDP_POLLING", 80, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, missedDeadlineFunc); + result = udpPollingTask->addComponent(objects::UDP_POLLING_TASK); if(result != HasReturnvaluesIF::RETURN_OK) { - sif::error << "Add component UDP Polling failed" << std::endl; + sif::error << "Add component UDP Polling failed" << std::endl; } - /* PUS Services */ - PeriodicTaskIF* PusVerification = TaskFactory::instance()-> - createPeriodicTask("PUS_VERIF_1", 40, - PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, nullptr); - result = PusVerification->addComponent(objects::PUS_SERVICE_1_VERIFICATION); - if(result != HasReturnvaluesIF::RETURN_OK){ - sif::error << "Object add component failed" << std::endl; - } + /* PUS Services */ + PeriodicTaskIF* pusVerification = factory->createPeriodicTask( + "PUS_VERIF", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc); + result = pusVerification->addComponent(objects::PUS_SERVICE_1_VERIFICATION); + if(result != HasReturnvaluesIF::RETURN_OK){ + sif::error << "Object add component failed" << std::endl; + } - PeriodicTaskIF* PusEvents = TaskFactory::instance()-> - createPeriodicTask("PUS_VERIF_1", 60, - PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, nullptr); - result = PusVerification->addComponent(objects::PUS_SERVICE_5_EVENT_REPORTING); - if(result != HasReturnvaluesIF::RETURN_OK){ - sif::error << "Object add component failed" << std::endl; - } + PeriodicTaskIF* pusEvents = factory->createPeriodicTask( + "PUS_EVENTS", 60, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc); + result = pusVerification->addComponent(objects::PUS_SERVICE_5_EVENT_REPORTING); + if(result != HasReturnvaluesIF::RETURN_OK){ + initmission::printAddObjectError("PUS5", objects::PUS_SERVICE_5_EVENT_REPORTING); + } - PeriodicTaskIF* PusHighPrio = TaskFactory::instance()-> - createPeriodicTask("PUS_HIGH_PRIO", 50, - PeriodicTaskIF::MINIMUM_STACK_SIZE, - 0.200, nullptr); - result = PusHighPrio->addComponent(objects::PUS_SERVICE_2_DEVICE_ACCESS); - if(result!=HasReturnvaluesIF::RETURN_OK){ - sif::error << "Object add component failed" << std::endl; - } - result = PusHighPrio->addComponent(objects::PUS_SERVICE_9_TIME_MGMT); - if(result!=HasReturnvaluesIF::RETURN_OK){ - sif::error << "Object add component failed" << std::endl; - } + PeriodicTaskIF* pusHighPrio = factory->createPeriodicTask( + "PUS_HIGH_PRIO", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc); + result = pusHighPrio->addComponent(objects::PUS_SERVICE_2_DEVICE_ACCESS); + if(result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS2", objects::PUS_SERVICE_2_DEVICE_ACCESS); + } + result = pusHighPrio->addComponent(objects::PUS_SERVICE_9_TIME_MGMT); + if(result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS9", objects::PUS_SERVICE_9_TIME_MGMT); + } - PeriodicTaskIF* PusMedPrio = TaskFactory::instance()-> - createPeriodicTask("PUS_HIGH_PRIO", 40, - PeriodicTaskIF::MINIMUM_STACK_SIZE, - 0.8, nullptr); - result = PusMedPrio->addComponent(objects::PUS_SERVICE_8_FUNCTION_MGMT); - if(result!=HasReturnvaluesIF::RETURN_OK){ - sif::error << "Object add component failed" << std::endl; - } - result = PusMedPrio->addComponent(objects::PUS_SERVICE_200_MODE_MGMT); - if(result!=HasReturnvaluesIF::RETURN_OK){ - sif::error << "Object add component failed" << std::endl; - } + PeriodicTaskIF* pusMedPrio = factory->createPeriodicTask( + "PUS_MED_PRIO", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.8, missedDeadlineFunc); + result = pusMedPrio->addComponent(objects::PUS_SERVICE_8_FUNCTION_MGMT); + if(result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS8", objects::PUS_SERVICE_8_FUNCTION_MGMT); + } + result = pusMedPrio->addComponent(objects::PUS_SERVICE_200_MODE_MGMT); + if(result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS200", objects::PUS_SERVICE_200_MODE_MGMT); + } + result = pusMedPrio->addComponent(objects::PUS_SERVICE_20_PARAMETERS); + if(result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS20", objects::PUS_SERVICE_20_PARAMETERS); + } - PeriodicTaskIF* PusLowPrio = TaskFactory::instance()-> - createPeriodicTask("PUSB", 30, PeriodicTaskIF::MINIMUM_STACK_SIZE, - 1.6, nullptr); - result = PusLowPrio->addComponent(objects::PUS_SERVICE_17_TEST); - if(result!=HasReturnvaluesIF::RETURN_OK){ - sif::error << "Object add component failed" << std::endl; - } + PeriodicTaskIF* pusLowPrio = factory->createPeriodicTask( + "PUS_LOW_PRIO", 30, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.6, missedDeadlineFunc); + result = pusLowPrio->addComponent(objects::PUS_SERVICE_17_TEST); + if(result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS17", objects::PUS_SERVICE_17_TEST); + } + PeriodicTaskIF* testTask = factory->createPeriodicTask( + "TEST_TASK", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, missedDeadlineFunc); +#if OBSW_ADD_TEST_CODE == 1 + result = testTask->addComponent(objects::TEST_TASK); + if(result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("TEST_TASK", objects::TEST_TASK); + } +#endif /* OBSW_ADD_TEST_CODE == 1 */ + + sif::info << "Starting tasks.." << std::endl; + tmTcDistributor->startTask(); + udpBridgeTask->startTask(); + udpPollingTask->startTask(); + + pusVerification->startTask(); + pusEvents->startTask(); + pusHighPrio->startTask(); + pusMedPrio->startTask(); + pusLowPrio->startTask(); #if OBSW_ADD_TEST_CODE == 1 - FixedTimeslotTaskIF* TestTimeslotTask = TaskFactory::instance()-> - createFixedTimeslotTask("PST_TEST_TASK", 10, - PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.0, nullptr); - result = pst::pollingSequenceTestFunction(TestTimeslotTask); - if(result != HasReturnvaluesIF::RETURN_OK) { - sif::error << "InitMission::createTasks: Test PST initialization " - << "failed!" << std::endl; - } -#endif + testTask->startTask(); +#endif /* OBSW_ADD_TEST_CODE == 1 */ - //Main thread sleep - sif::info << "Starting tasks.." << std::endl; - TmTcDistributor->startTask(); - UdpBridgeTask->startTask(); - UdpPollingTask->startTask(); - - PusVerification->startTask(); - PusEvents->startTask(); - PusHighPrio->startTask(); - PusMedPrio->startTask(); - PusLowPrio->startTask(); -#if OBSW_ADD_TEST_CODE == 1 - TestTimeslotTask->startTask(); -#endif - sif::info << "Tasks started.." << std::endl; + sif::info << "Tasks started.." << std::endl; } diff --git a/bsp_hosted/InitMission.h b/bsp_hosted/InitMission.h index 5ecf9e41..01c72008 100644 --- a/bsp_hosted/InitMission.h +++ b/bsp_hosted/InitMission.h @@ -1,7 +1,7 @@ #ifndef BSP_LINUX_INITMISSION_H_ #define BSP_LINUX_INITMISSION_H_ -namespace InitMission { +namespace initmission { void initMission(); void initTasks(); }; diff --git a/bsp_hosted/fsfwconfig/OBSWConfig.h b/bsp_hosted/fsfwconfig/OBSWConfig.h index b784cd03..5996e3a2 100644 --- a/bsp_hosted/fsfwconfig/OBSWConfig.h +++ b/bsp_hosted/fsfwconfig/OBSWConfig.h @@ -6,7 +6,9 @@ #ifndef CONFIG_OBSWCONFIG_H_ #define CONFIG_OBSWCONFIG_H_ -#define OBSW_ADD_TEST_CODE 0 +#include "commonConfig.h" + +#define OBSW_ADD_TEST_CODE 1 /* These defines should be disabled for mission code but are useful for debugging. */ diff --git a/bsp_hosted/fsfwconfig/devices/gpioIds.h b/bsp_hosted/fsfwconfig/devices/gpioIds.h new file mode 100644 index 00000000..8963bd20 --- /dev/null +++ b/bsp_hosted/fsfwconfig/devices/gpioIds.h @@ -0,0 +1,35 @@ +#ifndef FSFWCONFIG_DEVICES_GPIOIDS_H_ +#define FSFWCONFIG_DEVICES_GPIOIDS_H_ + +#include + +namespace gpioIds { + enum gpioId_t { + HEATER_0, + HEATER_1, + HEATER_2, + HEATER_3, + HEATER_4, + HEATER_5, + HEATER_6, + HEATER_7, + DEPLSA1, + DEPLSA2, + + MGM_0_LIS3_CS, + MGM_1_RM3100_CS, + GYRO_0_ADIS_CS, + GYRO_1_L3G_CS, + GYRO_2_L3G_CS, + MGM_2_LIS3_CS, + MGM_3_RM3100_CS, + + TEST_ID_0, + TEST_ID_1 + }; +} + + + + +#endif /* FSFWCONFIG_DEVICES_GPIOIDS_H_ */ diff --git a/bsp_hosted/fsfwconfig/devices/powerSwitcherList.h b/bsp_hosted/fsfwconfig/devices/powerSwitcherList.h new file mode 100644 index 00000000..09bdf568 --- /dev/null +++ b/bsp_hosted/fsfwconfig/devices/powerSwitcherList.h @@ -0,0 +1,58 @@ +#ifndef FSFWCONFIG_DEVICES_POWERSWITCHERLIST_H_ +#define FSFWCONFIG_DEVICES_POWERSWITCHERLIST_H_ + +#include + +namespace pcduSwitches { + /* Switches are uint8_t datatype and go from 0 to 255 */ + enum switcherList { + Q7S, + PAYLOAD_PCDU_CH1, + RW, + TCS_BOARD_8V_HEATER_IN, + SUS_REDUNDANT, + DEPLOYMENT_MECHANISM, + PAYLOAD_PCDU_CH6, + ACS_BOARD_SIDE_B, + PAYLOAD_CAMERA, + TCS_BOARD_3V3, + SYRLINKS, + STAR_TRACKER, + MGT, + SUS_NOMINAL, + SOLAR_CELL_EXP, + PLOC, + ACS_BORAD_SIDE_A, + NUMBER_OF_SWITCHES + }; + + static const uint8_t ON = 1; + static const uint8_t OFF = 0; + + /* Output states after reboot of the PDUs */ + static const uint8_t INIT_STATE_Q7S = ON; + static const uint8_t INIT_STATE_PAYLOAD_PCDU_CH1 = OFF; + static const uint8_t INIT_STATE_RW = OFF; +#if TE0720 == 1 + /* Because the TE0720 is not connected to the PCDU, this switch is always on */ + static const uint8_t INIT_STATE_TCS_BOARD_8V_HEATER_IN = ON; +#else + static const uint8_t INIT_STATE_TCS_BOARD_8V_HEATER_IN = OFF; +#endif + static const uint8_t INIT_STATE_SUS_REDUNDANT = OFF; + static const uint8_t INIT_STATE_DEPLOYMENT_MECHANISM = OFF; + static const uint8_t INIT_STATE_PAYLOAD_PCDU_CH6 = OFF; + static const uint8_t INIT_STATE_ACS_BOARD_SIDE_B = OFF; + static const uint8_t INIT_STATE_PAYLOAD_CAMERA = OFF; + static const uint8_t INIT_STATE_TCS_BOARD_3V3 = OFF; + static const uint8_t INIT_STATE_SYRLINKS = OFF; + static const uint8_t INIT_STATE_STAR_TRACKER = OFF; + static const uint8_t INIT_STATE_MGT = OFF; + static const uint8_t INIT_STATE_SUS_NOMINAL = OFF; + static const uint8_t INIT_STATE_SOLAR_CELL_EXP = OFF; + static const uint8_t INIT_STATE_PLOC = OFF; + static const uint8_t INIT_STATE_ACS_BOARD_SIDE_A = OFF; +} + + +#endif /* FSFWCONFIG_DEVICES_POWERSWITCHERLIST_H_ */ diff --git a/bsp_hosted/fsfwconfig/objects/systemObjectList.h b/bsp_hosted/fsfwconfig/objects/systemObjectList.h index 05ed2c52..d7a1abd7 100644 --- a/bsp_hosted/fsfwconfig/objects/systemObjectList.h +++ b/bsp_hosted/fsfwconfig/objects/systemObjectList.h @@ -27,6 +27,21 @@ namespace objects { DUMMY_INTERFACE = 0xCAFECAFE, DUMMY_HANDLER = 0x4400AFFE, + /* 0x44 ('D') for device handlers */ + P60DOCK_HANDLER = 0x44000001, + PDU1_HANDLER = 0x44000002, + PDU2_HANDLER = 0x44000003, + ACU_HANDLER = 0x44000004, + TMP1075_HANDLER_1 = 0x44000005, + TMP1075_HANDLER_2 = 0x44000006, + MGM_0_LIS3_HANDLER = 0x4400007, + MGM_1_RM3100_HANDLER = 0x44000008, + MGM_2_LIS3_HANDLER = 0x44000009, + MGM_3_RM3100_HANDLER = 0x44000010, + GYRO_0_ADIS_HANDLER = 0x44000011, + GYRO_1_L3G_HANDLER = 0x44000012, + GYRO_2_L3G_HANDLER = 0x44000013, + /* 0x49 ('I') for Communication Interfaces **/ ARDUINO_COM_IF = 0x49000001 }; diff --git a/bsp_hosted/main.cpp b/bsp_hosted/main.cpp index 02d793f9..4fa1eb04 100644 --- a/bsp_hosted/main.cpp +++ b/bsp_hosted/main.cpp @@ -24,7 +24,7 @@ int main(void) << SW_SUBVERSION << "." << SW_SUBSUBVERSION << " -- " << std::endl; std::cout << "-- " << __DATE__ << " " << __TIME__ << " --" << std::endl; - InitMission::initMission(); + initmission::initMission(); for(;;) { // suspend main thread by sleeping it. diff --git a/bsp_q7s/CMakeLists.txt b/bsp_q7s/CMakeLists.txt index 3d3a1c91..7b985558 100644 --- a/bsp_q7s/CMakeLists.txt +++ b/bsp_q7s/CMakeLists.txt @@ -6,6 +6,7 @@ target_sources(${TARGET_NAME} PUBLIC add_subdirectory(boardconfig) add_subdirectory(comIF) +add_subdirectory(devices) add_subdirectory(boardtest) diff --git a/bsp_q7s/InitMission.h b/bsp_q7s/InitMission.h index 89d65ada..568b26b5 100644 --- a/bsp_q7s/InitMission.h +++ b/bsp_q7s/InitMission.h @@ -1,7 +1,7 @@ #ifndef BSP_Q7S_INITMISSION_H_ #define BSP_Q7S_INITMISSION_H_ -namespace InitMission { +namespace initmission { void initMission(); void initTasks(); }; diff --git a/bsp_q7s/boardtest/CMakeLists.txt b/bsp_q7s/boardtest/CMakeLists.txt index 7e59ddb9..0599b73f 100644 --- a/bsp_q7s/boardtest/CMakeLists.txt +++ b/bsp_q7s/boardtest/CMakeLists.txt @@ -1,5 +1,4 @@ target_sources(${TARGET_NAME} PRIVATE - LibgpiodTest.cpp ) diff --git a/bsp_q7s/devices/CMakeLists.txt b/bsp_q7s/devices/CMakeLists.txt new file mode 100644 index 00000000..9e6fb793 --- /dev/null +++ b/bsp_q7s/devices/CMakeLists.txt @@ -0,0 +1,4 @@ +target_sources(${TARGET_NAME} PRIVATE + HeaterHandler.cpp + SolarArrayDeploymentHandler.cpp +) diff --git a/bsp_q7s/devices/HeaterHandler.cpp b/bsp_q7s/devices/HeaterHandler.cpp new file mode 100644 index 00000000..ccf5b65c --- /dev/null +++ b/bsp_q7s/devices/HeaterHandler.cpp @@ -0,0 +1,356 @@ +#include "HeaterHandler.h" +#include +#include +#include +#include + +HeaterHandler::HeaterHandler(object_id_t setObjectId_, object_id_t gpioDriverId_, + CookieIF * gpioCookie_, object_id_t mainLineSwitcherObjectId_, uint8_t mainLineSwitch_) : + SystemObject(setObjectId_), gpioDriverId(gpioDriverId_), gpioCookie(gpioCookie_), + mainLineSwitcherObjectId(mainLineSwitcherObjectId_), mainLineSwitch(mainLineSwitch_), + actionHelper(this, nullptr) { + commandQueue = QueueFactory::instance()->createMessageQueue(cmdQueueSize, + MessageQueueMessage::MAX_MESSAGE_SIZE); +} + +HeaterHandler::~HeaterHandler() { +} + +ReturnValue_t HeaterHandler::performOperation(uint8_t operationCode) { + + if (operationCode == DeviceHandlerIF::PERFORM_OPERATION) { + readCommandQueue(); + handleActiveCommands(); + return RETURN_OK; + } + return RETURN_OK; +} + +ReturnValue_t HeaterHandler::initialize() { + ReturnValue_t result = SystemObject::initialize(); + if (result != RETURN_OK) { + return ObjectManagerIF::CHILD_INIT_FAILED; + } + + result = initializeHeaterMap(); + if (result != RETURN_OK) { + return ObjectManagerIF::CHILD_INIT_FAILED; + } + + gpioInterface = objectManager->get(gpioDriverId); + if (gpioInterface == nullptr) { + sif::error << "HeaterHandler::initialize: Invalid Gpio interface." << std::endl; + return ObjectManagerIF::CHILD_INIT_FAILED; + } + + result = gpioInterface->addGpios(dynamic_cast(gpioCookie)); + if (result != RETURN_OK) { + sif::error << "HeaterHandler::initialize: Failed to initialize Gpio interface" << std::endl; + return ObjectManagerIF::CHILD_INIT_FAILED; + } + + IPCStore = objectManager->get(objects::IPC_STORE); + if (IPCStore == nullptr) { + sif::error << "HeaterHandler::initialize: IPC store not set up in factory." << std::endl; + return ObjectManagerIF::CHILD_INIT_FAILED; + } + + if(mainLineSwitcherObjectId != objects::NO_OBJECT) { + mainLineSwitcher = objectManager->get(mainLineSwitcherObjectId); + if (mainLineSwitcher == nullptr) { + sif::error << "HeaterHandler::initialize: Main line switcher failed to fetch object" + << "from object ID." << std::endl; + return ObjectManagerIF::CHILD_INIT_FAILED; + } + } + + result = actionHelper.initialize(commandQueue); + if (result != RETURN_OK) { + return ObjectManagerIF::CHILD_INIT_FAILED; + } + + return RETURN_OK; +} + +ReturnValue_t HeaterHandler::initializeHeaterMap(){ + HeaterCommandInfo_t heaterCommandInfo; + for(switchNr_t switchNr = 0; switchNr < heaterSwitches::NUMBER_OF_SWITCHES; switchNr++) { + std::pair status = heaterMap.emplace(switchNr, heaterCommandInfo); + if (status.second == false) { + sif::error << "HeaterHandler::initializeHeaterMap: Failed to initialize heater map" + << std::endl; + return RETURN_FAILED; + } + } + return RETURN_OK; +} + +void HeaterHandler::setInitialSwitchStates() { + for (switchNr_t switchNr = 0; switchNr < heaterSwitches::NUMBER_OF_SWITCHES; switchNr++) { + switchStates[switchNr] = OFF; + } +} + +void HeaterHandler::readCommandQueue() { + CommandMessage command; + ReturnValue_t result = commandQueue->receiveMessage(&command); + if (result != RETURN_OK) { + return; + } + + result = actionHelper.handleActionMessage(&command); + if (result == RETURN_OK) { + return; + } +} + +ReturnValue_t HeaterHandler::executeAction(ActionId_t actionId, + MessageQueueId_t commandedBy, const uint8_t* data, size_t size) { + ReturnValue_t result; + if (actionId != SWITCH_HEATER) { + result = COMMAND_NOT_SUPPORTED; + } else { + switchNr_t switchNr = *data; + HeaterMapIter heaterMapIter = heaterMap.find(switchNr); + if (heaterMapIter != heaterMap.end()) { + if (heaterMapIter->second.active) { + return COMMAND_ALREADY_WAITING; + } + heaterMapIter->second.action = *(data + 1); + heaterMapIter->second.active = true; + heaterMapIter->second.replyQueue = commandedBy; + } + else { + sif::error << "HeaterHandler::executeAction: Invalid switchNr" << std::endl; + return INVALID_SWITCH_NR; + } + result = RETURN_OK; + } + return result; +} + + +void HeaterHandler::sendSwitchCommand(uint8_t switchNr, + ReturnValue_t onOff) const { + + ReturnValue_t result; + store_address_t storeAddress; + uint8_t commandData[2]; + + switch(onOff) { + case PowerSwitchIF::SWITCH_ON: + commandData[0] = switchNr; + commandData[1] = SET_SWITCH_ON; + break; + case PowerSwitchIF::SWITCH_OFF: + commandData[0] = switchNr; + commandData[1] = SET_SWITCH_OFF; + break; + default: + sif::error << "HeaterHandler::sendSwitchCommand: Invalid switch request" + << std::endl; + break; + } + + result = IPCStore->addData(&storeAddress, commandData, sizeof(commandData)); + if (result == RETURN_OK) { + CommandMessage message; + ActionMessage::setCommand(&message, SWITCH_HEATER, storeAddress); + /* Send heater command to own command queue */ + result = commandQueue->sendMessage(commandQueue->getId(), &message, 0); + if (result != RETURN_OK) { + sif::debug << "HeaterHandler::sendSwitchCommand: Failed to send switch" + << "message" << std::endl; + } + } +} + +void HeaterHandler::handleActiveCommands(){ + + HeaterMapIter heaterMapIter = heaterMap.begin(); + for (; heaterMapIter != heaterMap.end(); heaterMapIter++) { + if (heaterMapIter->second.active) { + switch(heaterMapIter->second.action) { + case SET_SWITCH_ON: + handleSwitchOnCommand(heaterMapIter); + break; + case SET_SWITCH_OFF: + handleSwitchOffCommand(heaterMapIter); + break; + default: + sif::error << "HeaterHandler::handleActiveCommands: Invalid action commanded" + << std::endl; + break; + } + } + } +} + +void HeaterHandler::handleSwitchOnCommand(HeaterMapIter heaterMapIter) { + + ReturnValue_t result = RETURN_OK; + switchNr_t switchNr; + + /* Check if command waits for main switch being set on and whether the timeout has expired */ + if (heaterMapIter->second.waitMainSwitchOn + && heaterMapIter->second.mainSwitchCountdown.hasTimedOut()) { + //TODO - This requires the initiation of an FDIR procedure + triggerEvent(MAIN_SWITCH_TIMEOUT); + sif::error << "HeaterHandler::handleSwitchOnCommand: Main switch setting on timeout" + << std::endl; + heaterMapIter->second.active = false; + heaterMapIter->second.waitMainSwitchOn = false; + if (heaterMapIter->second.replyQueue != commandQueue->getId()) { + actionHelper.finish(heaterMapIter->second.replyQueue, heaterMapIter->second.action, + MAIN_SWITCH_SET_TIMEOUT ); + } + return; + } + + switchNr = heaterMapIter->first; + /* Check state of main line switch */ + ReturnValue_t mainSwitchState = mainLineSwitcher->getSwitchState(mainLineSwitch); + if (mainSwitchState == PowerSwitchIF::SWITCH_ON) { + if (!checkSwitchState(switchNr)) { + gpioId_t gpioId = getGpioIdFromSwitchNr(switchNr); + result = gpioInterface->pullHigh(gpioId); + if (result != RETURN_OK) { + sif::error << "HeaterHandler::handleSwitchOnCommand: Failed to pull gpio with id " + << gpioId << " high" << std::endl; + triggerEvent(GPIO_PULL_HIGH_FAILED, result); + } + else { + switchStates[switchNr] = ON; + } + } + else { + triggerEvent(SWITCH_ALREADY_ON, switchNr); + } + /* There is no need to send action finish replies if the sender was the + * HeaterHandler itself. */ + if (heaterMapIter->second.replyQueue != commandQueue->getId()) { + actionHelper.finish(heaterMapIter->second.replyQueue, + heaterMapIter->second.action, result); + } + heaterMapIter->second.active = false; + heaterMapIter->second.waitMainSwitchOn = false; + } + else if (mainSwitchState == PowerSwitchIF::SWITCH_OFF + && heaterMapIter->second.waitMainSwitchOn) { + /* Just waiting for the main switch being set on */ + return; + } + else if (mainSwitchState == PowerSwitchIF::SWITCH_OFF) { + mainLineSwitcher->sendSwitchCommand(mainLineSwitch, + PowerSwitchIF::SWITCH_ON); + heaterMapIter->second.mainSwitchCountdown.setTimeout(mainLineSwitcher->getSwitchDelayMs()); + heaterMapIter->second.waitMainSwitchOn = true; + } + else { + sif::debug << "HeaterHandler::handleActiveCommands: Failed to get state of" + << " main line switch" << std::endl; + if (heaterMapIter->second.replyQueue != commandQueue->getId()) { + actionHelper.finish(heaterMapIter->second.replyQueue, + heaterMapIter->second.action, mainSwitchState); + } + heaterMapIter->second.active = false; + } +} + +void HeaterHandler::handleSwitchOffCommand(HeaterMapIter heaterMapIter) { + ReturnValue_t result = RETURN_OK; + switchNr_t switchNr = heaterMapIter->first; + /* Check whether switch is already off */ + if (checkSwitchState(switchNr)) { + gpioId_t gpioId = getGpioIdFromSwitchNr(switchNr); + result = gpioInterface->pullLow(gpioId); + if (result != RETURN_OK) { + sif::error << "HeaterHandler::handleSwitchOffCommand: Failed to pull gpio with id" + << gpioId << " low" << std::endl; + triggerEvent(GPIO_PULL_LOW_FAILED, result); + } + else { + switchStates[switchNr] = OFF; + /* When all switches are off, also main line switch will be turned off */ + if (allSwitchesOff()) { + mainLineSwitcher->sendSwitchCommand(mainLineSwitch, PowerSwitchIF::SWITCH_OFF); + } + } + } + else { + sif::info << "HeaterHandler::handleSwitchOffCommand: Switch already off" << std::endl; + triggerEvent(SWITCH_ALREADY_OFF, switchNr); + } + if (heaterMapIter->second.replyQueue != NO_COMMANDER) { + actionHelper.finish(heaterMapIter->second.replyQueue, + heaterMapIter->second.action, result); + } + heaterMapIter->second.active = false; +} + +bool HeaterHandler::checkSwitchState(int switchNr) { + return switchStates[switchNr]; +} + +bool HeaterHandler::allSwitchesOff() { + bool allSwitchesOrd = false; + /* Or all switches. As soon one switch is on, allSwitchesOrd will be true */ + for (switchNr_t switchNr = 0; switchNr < heaterSwitches::NUMBER_OF_SWITCHES; switchNr++) { + allSwitchesOrd = allSwitchesOrd || switchStates[switchNr]; + } + return !allSwitchesOrd; +} + +gpioId_t HeaterHandler::getGpioIdFromSwitchNr(int switchNr) { + gpioId_t gpioId = 0xFFFF; + switch(switchNr) { + case heaterSwitches::HEATER_0: + gpioId = gpioIds::HEATER_0; + break; + case heaterSwitches::HEATER_1: + gpioId = gpioIds::HEATER_1; + break; + case heaterSwitches::HEATER_2: + gpioId = gpioIds::HEATER_2; + break; + case heaterSwitches::HEATER_3: + gpioId = gpioIds::HEATER_3; + break; + case heaterSwitches::HEATER_4: + gpioId = gpioIds::HEATER_4; + break; + case heaterSwitches::HEATER_5: + gpioId = gpioIds::HEATER_5; + break; + case heaterSwitches::HEATER_6: + gpioId = gpioIds::HEATER_6; + break; + case heaterSwitches::HEATER_7: + gpioId = gpioIds::HEATER_7; + break; + default: + sif::error << "HeaterHandler::getGpioIdFromSwitchNr: Unknown heater switch number" + << std::endl; + break; + } + return gpioId; +} + +MessageQueueId_t HeaterHandler::getCommandQueue() const { + return commandQueue->getId(); +} + +void HeaterHandler::sendFuseOnCommand(uint8_t fuseNr) const { +} + +ReturnValue_t HeaterHandler::getSwitchState( uint8_t switchNr ) const { + return 0; +} + +ReturnValue_t HeaterHandler::getFuseState( uint8_t fuseNr ) const { + return 0; +} + +uint32_t HeaterHandler::getSwitchDelayMs(void) const { + return 0; +} diff --git a/bsp_q7s/devices/HeaterHandler.h b/bsp_q7s/devices/HeaterHandler.h new file mode 100644 index 00000000..01319ce9 --- /dev/null +++ b/bsp_q7s/devices/HeaterHandler.h @@ -0,0 +1,177 @@ +#ifndef MISSION_DEVICES_HEATERHANDLER_H_ +#define MISSION_DEVICES_HEATERHANDLER_H_ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +/** + * @brief This class intends the control of heaters. + * + * @author J. Meier + */ +class HeaterHandler: public ExecutableObjectIF, + public PowerSwitchIF, + public SystemObject, + public HasActionsIF { +public: + + /** Device command IDs */ + static const DeviceCommandId_t SWITCH_HEATER = 0x0; + + HeaterHandler(object_id_t setObjectId, object_id_t gpioDriverId, CookieIF * gpioCookie, + object_id_t mainLineSwitcherObjectId, uint8_t mainLineSwitch); + + virtual ~HeaterHandler(); + + virtual ReturnValue_t performOperation(uint8_t operationCode = 0) override; + + virtual void sendSwitchCommand(uint8_t switchNr, ReturnValue_t onOff) const override; + virtual void sendFuseOnCommand(uint8_t fuseNr) const override; + /** + * @brief This function will be called from the Heater object to check + * the current switch state. + */ + virtual ReturnValue_t getSwitchState( uint8_t switchNr ) const override; + virtual ReturnValue_t getFuseState( uint8_t fuseNr ) const override; + virtual uint32_t getSwitchDelayMs(void) const override; + + virtual MessageQueueId_t getCommandQueue() const override; + virtual ReturnValue_t executeAction(ActionId_t actionId, MessageQueueId_t commandedBy, + const uint8_t* data, size_t size) override; + virtual ReturnValue_t initialize() override; + +private: + + static const uint8_t INTERFACE_ID = CLASS_ID::HEATER_HANDLER; + + static const ReturnValue_t COMMAND_NOT_SUPPORTED = MAKE_RETURN_CODE(0xA1); + static const ReturnValue_t INIT_FAILED = MAKE_RETURN_CODE(0xA2); + static const ReturnValue_t INVALID_SWITCH_NR = MAKE_RETURN_CODE(0xA3); + static const ReturnValue_t MAIN_SWITCH_SET_TIMEOUT = MAKE_RETURN_CODE(0xA4); + static const ReturnValue_t COMMAND_ALREADY_WAITING = MAKE_RETURN_CODE(0xA5); + + static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::HEATER_HANDLER; + static const Event GPIO_PULL_HIGH_FAILED = MAKE_EVENT(0, severity::LOW); + static const Event GPIO_PULL_LOW_FAILED = MAKE_EVENT(1, severity::LOW); + static const Event SWITCH_ALREADY_ON = MAKE_EVENT(2, severity::LOW); + static const Event SWITCH_ALREADY_OFF = MAKE_EVENT(3, severity::LOW); + static const Event MAIN_SWITCH_TIMEOUT = MAKE_EVENT(4, severity::LOW); + + static const MessageQueueId_t NO_COMMANDER = 0; + + enum SwitchState : bool { + ON = true, + OFF = false + }; + + + /** + * @brief Struct holding information about a heater command to execute. + * + * @param action The action to perform. + * @param replyQueue The queue of the commander to which status replies + * will be sent. + * @param active True if command is waiting for execution, otherwise false. + * @param waitSwitchOn True if the command is waiting for the main switch being set on. + * @param mainSwitchCountdown Sets timeout to wait for main switch being set on. + */ + typedef struct HeaterCommandInfo { + uint8_t action; + MessageQueueId_t replyQueue; + bool active = false; + bool waitMainSwitchOn = false; + Countdown mainSwitchCountdown; + } HeaterCommandInfo_t; + + enum SwitchAction { + SET_SWITCH_OFF, + SET_SWITCH_ON + }; + + using switchNr_t = uint8_t; + using HeaterMap = std::unordered_map; + using HeaterMapIter = HeaterMap::iterator; + + HeaterMap heaterMap; + + bool switchStates[heaterSwitches::NUMBER_OF_SWITCHES]; + + /** Size of command queue */ + size_t cmdQueueSize = 20; + + /** + * The object ID of the GPIO driver which enables and disables the + * heaters. + */ + object_id_t gpioDriverId; + + CookieIF * gpioCookie; + + GpioIF* gpioInterface = nullptr; + + /** Queue to receive messages from other objects. */ + MessageQueueIF* commandQueue = nullptr; + + object_id_t mainLineSwitcherObjectId; + + /** Switch number of the heater power supply switch */ + uint8_t mainLineSwitch; + + /** + * Power switcher object which controls the 8V main line of the heater + * logic on the TCS board. + */ + PowerSwitchIF *mainLineSwitcher = nullptr; + + ActionHelper actionHelper; + + StorageManagerIF *IPCStore = nullptr; + + void readCommandQueue(); + + /** + * @brief Returns the state of a switch (ON - true, or OFF - false). + * @param switchNr The number of the switch to check. + */ + bool checkSwitchState(int switchNr); + + /** + * @brief Returns the ID of the GPIO related to a heater identified by the switch number + * which is defined in the heaterSwitches list. + */ + gpioId_t getGpioIdFromSwitchNr(int switchNr); + + /** + * @brief This function runs commands waiting for execution. + */ + void handleActiveCommands(); + + ReturnValue_t initializeHeaterMap(); + + /** + * @brief Sets all switches to OFF. + */ + void setInitialSwitchStates(); + + void handleSwitchOnCommand(HeaterMapIter heaterMapIter); + + void handleSwitchOffCommand(HeaterMapIter heaterMapIter); + + /** + * @brief Checks if all switches are off. + * @return True if all switches are off, otherwise false. + */ + bool allSwitchesOff(); + +}; + +#endif /* MISSION_DEVICES_HEATERHANDLER_H_ */ diff --git a/bsp_q7s/devices/SolarArrayDeploymentHandler.cpp b/bsp_q7s/devices/SolarArrayDeploymentHandler.cpp new file mode 100644 index 00000000..80d941bf --- /dev/null +++ b/bsp_q7s/devices/SolarArrayDeploymentHandler.cpp @@ -0,0 +1,201 @@ +#include "SolarArrayDeploymentHandler.h" + +#include +#include + +#include +#include + + +SolarArrayDeploymentHandler::SolarArrayDeploymentHandler(object_id_t setObjectId_, + object_id_t gpioDriverId_, CookieIF * gpioCookie_, object_id_t mainLineSwitcherObjectId_, + uint8_t mainLineSwitch_, gpioId_t deplSA1, gpioId_t deplSA2, uint32_t burnTimeMs) : + SystemObject(setObjectId_), gpioDriverId(gpioDriverId_), gpioCookie(gpioCookie_), + mainLineSwitcherObjectId(mainLineSwitcherObjectId_), mainLineSwitch(mainLineSwitch_), + deplSA1(deplSA1), deplSA2(deplSA2), burnTimeMs(burnTimeMs), actionHelper(this, nullptr) { + commandQueue = QueueFactory::instance()->createMessageQueue(cmdQueueSize, + MessageQueueMessage::MAX_MESSAGE_SIZE); +} + +SolarArrayDeploymentHandler::~SolarArrayDeploymentHandler() { +} + +ReturnValue_t SolarArrayDeploymentHandler::performOperation(uint8_t operationCode) { + + if (operationCode == DeviceHandlerIF::PERFORM_OPERATION) { + handleStateMachine(); + return RETURN_OK; + } + return RETURN_OK; +} + +ReturnValue_t SolarArrayDeploymentHandler::initialize() { + ReturnValue_t result = SystemObject::initialize(); + if (result != RETURN_OK) { + return ObjectManagerIF::CHILD_INIT_FAILED; + } + + gpioInterface = objectManager->get(gpioDriverId); + if (gpioInterface == nullptr) { + sif::error << "SolarArrayDeploymentHandler::initialize: Invalid Gpio interface." + << std::endl; + return ObjectManagerIF::CHILD_INIT_FAILED; + } + + result = gpioInterface->addGpios(dynamic_cast(gpioCookie)); + if (result != RETURN_OK) { + sif::error << "SolarArrayDeploymentHandler::initialize: Failed to initialize Gpio interface" + << std::endl; + return ObjectManagerIF::CHILD_INIT_FAILED; + } + + if (mainLineSwitcherObjectId != objects::NO_OBJECT) { + mainLineSwitcher = objectManager->get(mainLineSwitcherObjectId); + if (mainLineSwitcher == nullptr) { + sif::error + << "SolarArrayDeploymentHandler::initialize: Main line switcher failed to fetch object" + << "from object ID." << std::endl; + return ObjectManagerIF::CHILD_INIT_FAILED; + } + } + + result = actionHelper.initialize(commandQueue); + if (result != RETURN_OK) { + return ObjectManagerIF::CHILD_INIT_FAILED; + } + + return RETURN_OK; +} + +void SolarArrayDeploymentHandler::handleStateMachine() { + switch (stateMachine) { + case WAIT_ON_DELOYMENT_COMMAND: + readCommandQueue(); + break; + case SWITCH_8V_ON: + mainLineSwitcher->sendSwitchCommand(mainLineSwitch, PowerSwitchIF::SWITCH_ON); + mainSwitchCountdown.setTimeout(mainLineSwitcher->getSwitchDelayMs()); + stateMachine = WAIT_ON_8V_SWITCH; + break; + case WAIT_ON_8V_SWITCH: + performWaitOn8VActions(); + break; + case SWITCH_DEPL_GPIOS: + switchDeploymentTransistors(); + break; + case WAIT_ON_DEPLOYMENT_FINISH: + handleDeploymentFinish(); + break; + case WAIT_FOR_MAIN_SWITCH_OFF: + if (mainLineSwitcher->getSwitchState(mainLineSwitch) == PowerSwitchIF::SWITCH_OFF) { + stateMachine = WAIT_ON_DELOYMENT_COMMAND; + } else if (mainSwitchCountdown.hasTimedOut()) { + triggerEvent(MAIN_SWITCH_OFF_TIMEOUT); + sif::error << "SolarArrayDeploymentHandler::handleStateMachine: Failed to switch main" + << " switch off" << std::endl; + stateMachine = WAIT_ON_DELOYMENT_COMMAND; + } + break; + default: + sif::debug << "SolarArrayDeploymentHandler::handleStateMachine: Invalid state" << std::endl; + break; + } +} + +void SolarArrayDeploymentHandler::performWaitOn8VActions() { + if (mainLineSwitcher->getSwitchState(mainLineSwitch) == PowerSwitchIF::SWITCH_ON) { + stateMachine = SWITCH_DEPL_GPIOS; + } else { + if (mainSwitchCountdown.hasTimedOut()) { + triggerEvent(MAIN_SWITCH_ON_TIMEOUT); + actionHelper.finish(rememberCommanderId, DEPLOY_SOLAR_ARRAYS, + MAIN_SWITCH_TIMEOUT_FAILURE); + stateMachine = WAIT_ON_DELOYMENT_COMMAND; + } + } +} + +void SolarArrayDeploymentHandler::switchDeploymentTransistors() { + ReturnValue_t result = RETURN_OK; + result = gpioInterface->pullHigh(deplSA1); + if (result != RETURN_OK) { + sif::debug << "SolarArrayDeploymentHandler::handleStateMachine: Failed to pull solar" + " array deployment switch 1 high " << std::endl; + /* If gpio switch high failed, state machine is reset to wait for a command reinitiating + * the deployment sequence. */ + stateMachine = WAIT_ON_DELOYMENT_COMMAND; + triggerEvent(DEPL_SA1_GPIO_SWTICH_ON_FAILED); + actionHelper.finish(rememberCommanderId, DEPLOY_SOLAR_ARRAYS, + SWITCHING_DEPL_SA2_FAILED); + mainLineSwitcher->sendSwitchCommand(mainLineSwitch, PowerSwitchIF::SWITCH_OFF); + } + result = gpioInterface->pullHigh(deplSA2); + if (result != RETURN_OK) { + sif::debug << "SolarArrayDeploymentHandler::handleStateMachine: Failed to pull solar" + " array deployment switch 2 high " << std::endl; + stateMachine = WAIT_ON_DELOYMENT_COMMAND; + triggerEvent(DEPL_SA2_GPIO_SWTICH_ON_FAILED); + actionHelper.finish(rememberCommanderId, DEPLOY_SOLAR_ARRAYS, + SWITCHING_DEPL_SA2_FAILED); + mainLineSwitcher->sendSwitchCommand(mainLineSwitch, PowerSwitchIF::SWITCH_OFF); + } + deploymentCountdown.setTimeout(burnTimeMs); + stateMachine = WAIT_ON_DEPLOYMENT_FINISH; +} + +void SolarArrayDeploymentHandler::handleDeploymentFinish() { + ReturnValue_t result = RETURN_OK; + if (deploymentCountdown.hasTimedOut()) { + actionHelper.finish(rememberCommanderId, DEPLOY_SOLAR_ARRAYS, RETURN_OK); + result = gpioInterface->pullLow(deplSA1); + if (result != RETURN_OK) { + sif::debug << "SolarArrayDeploymentHandler::handleStateMachine: Failed to pull solar" + " array deployment switch 1 low " << std::endl; + } + result = gpioInterface->pullLow(deplSA2); + if (result != RETURN_OK) { + sif::debug << "SolarArrayDeploymentHandler::handleStateMachine: Failed to pull solar" + " array deployment switch 2 low " << std::endl; + } + mainLineSwitcher->sendSwitchCommand(mainLineSwitch, PowerSwitchIF::SWITCH_OFF); + mainSwitchCountdown.setTimeout(mainLineSwitcher->getSwitchDelayMs()); + stateMachine = WAIT_FOR_MAIN_SWITCH_OFF; + } +} + +void SolarArrayDeploymentHandler::readCommandQueue() { + CommandMessage command; + ReturnValue_t result = commandQueue->receiveMessage(&command); + if (result != RETURN_OK) { + return; + } + + result = actionHelper.handleActionMessage(&command); + if (result == RETURN_OK) { + return; + } +} + +ReturnValue_t SolarArrayDeploymentHandler::executeAction(ActionId_t actionId, + MessageQueueId_t commandedBy, const uint8_t* data, size_t size) { + ReturnValue_t result; + if (stateMachine != WAIT_ON_DELOYMENT_COMMAND) { + sif::error << "SolarArrayDeploymentHandler::executeAction: Received command while not in" + << "waiting-on-command-state" << std::endl; + return DEPLOYMENT_ALREADY_EXECUTING; + } + if (actionId != DEPLOY_SOLAR_ARRAYS) { + sif::error << "SolarArrayDeploymentHandler::executeAction: Received invalid command" + << std::endl; + result = COMMAND_NOT_SUPPORTED; + } else { + stateMachine = SWITCH_8V_ON; + rememberCommanderId = commandedBy; + result = RETURN_OK; + } + return result; +} + +MessageQueueId_t SolarArrayDeploymentHandler::getCommandQueue() const { + return commandQueue->getId(); +} diff --git a/bsp_q7s/devices/SolarArrayDeploymentHandler.h b/bsp_q7s/devices/SolarArrayDeploymentHandler.h new file mode 100644 index 00000000..b7e94f23 --- /dev/null +++ b/bsp_q7s/devices/SolarArrayDeploymentHandler.h @@ -0,0 +1,160 @@ +#ifndef MISSION_DEVICES_SOLARARRAYDEPLOYMENT_H_ +#define MISSION_DEVICES_SOLARARRAYDEPLOYMENT_H_ + +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +/** + * @brief This class is used to control the solar array deployment. + * + * @author J. Meier + */ +class SolarArrayDeploymentHandler: public ExecutableObjectIF, + public SystemObject, + public HasReturnvaluesIF, + public HasActionsIF { +public: + + static const DeviceCommandId_t DEPLOY_SOLAR_ARRAYS = 0x5; + + /** + * @brief constructor + * + * @param setObjectId The object id of the SolarArrayDeploymentHandler. + * @param gpioDriverId The id of the gpio com if. + * @param gpioCookie GpioCookie holding information about the gpios used to switch the + * transistors. + * @param mainLineSwitcherObjectId The object id of the object responsible for switching + * the 8V power source. This is normally the PCDU. + * @param mainLineSwitch The id of the main line switch. This is defined in + * powerSwitcherList.h. + * @param deplSA1 gpioId of the GPIO controlling the deployment 1 transistor. + * @param deplSA2 gpioId of the GPIO controlling the deployment 2 transistor. + * @param burnTimeMs Time duration the power will be applied to the burn wires. + */ + SolarArrayDeploymentHandler(object_id_t setObjectId, object_id_t gpioDriverId, + CookieIF * gpioCookie, object_id_t mainLineSwitcherObjectId, uint8_t mainLineSwitch, + gpioId_t deplSA1, gpioId_t deplSA2, uint32_t burnTimeMs); + + virtual ~SolarArrayDeploymentHandler(); + + virtual ReturnValue_t performOperation(uint8_t operationCode = 0) override; + + virtual MessageQueueId_t getCommandQueue() const override; + virtual ReturnValue_t executeAction(ActionId_t actionId, MessageQueueId_t commandedBy, + const uint8_t* data, size_t size) override; + virtual ReturnValue_t initialize() override; + +private: + + static const uint8_t INTERFACE_ID = CLASS_ID::SA_DEPL_HANDLER; + static const ReturnValue_t COMMAND_NOT_SUPPORTED = MAKE_RETURN_CODE(0xA0); + static const ReturnValue_t DEPLOYMENT_ALREADY_EXECUTING = MAKE_RETURN_CODE(0xA1); + static const ReturnValue_t MAIN_SWITCH_TIMEOUT_FAILURE = MAKE_RETURN_CODE(0xA2); + static const ReturnValue_t SWITCHING_DEPL_SA1_FAILED = MAKE_RETURN_CODE(0xA3); + static const ReturnValue_t SWITCHING_DEPL_SA2_FAILED = MAKE_RETURN_CODE(0xA4); + + static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::SA_DEPL_HANDLER; + static const Event MAIN_SWITCH_ON_TIMEOUT = MAKE_EVENT(0, severity::LOW); + static const Event MAIN_SWITCH_OFF_TIMEOUT = MAKE_EVENT(1, severity::LOW); + static const Event DEPLOYMENT_FAILED = MAKE_EVENT(2, severity::HIGH); + static const Event DEPL_SA1_GPIO_SWTICH_ON_FAILED = MAKE_EVENT(3, severity::HIGH); + static const Event DEPL_SA2_GPIO_SWTICH_ON_FAILED = MAKE_EVENT(4, severity::HIGH); + + + enum StateMachine { + WAIT_ON_DELOYMENT_COMMAND, + SWITCH_8V_ON, + WAIT_ON_8V_SWITCH, + SWITCH_DEPL_GPIOS, + WAIT_ON_DEPLOYMENT_FINISH, + WAIT_FOR_MAIN_SWITCH_OFF + }; + + StateMachine stateMachine = WAIT_ON_DELOYMENT_COMMAND; + + /** + * This countdown is used to check if the PCDU sets the 8V line on in the intended time. + */ + Countdown mainSwitchCountdown; + + /** + * This countdown is used to wait for the burn wire being successful cut. + */ + Countdown deploymentCountdown; + + + /** + * The message queue id of the component commanding an action will be stored in this variable. + * This is necessary to send later the action finish replies. + */ + MessageQueueId_t rememberCommanderId = 0; + + /** Size of command queue */ + size_t cmdQueueSize = 20; + + /** The object ID of the GPIO driver which switches the deployment transistors */ + object_id_t gpioDriverId; + + CookieIF * gpioCookie; + + /** Object id of the object responsible to switch the 8V power input. Typically the PCDU. */ + object_id_t mainLineSwitcherObjectId; + + /** Switch number of the 8V power switch */ + uint8_t mainLineSwitch; + + gpioId_t deplSA1; + gpioId_t deplSA2; + + GpioIF* gpioInterface = nullptr; + + /** Time duration switches are active to cut the burn wire */ + uint32_t burnTimeMs; + + /** Queue to receive messages from other objects. */ + MessageQueueIF* commandQueue = nullptr; + + /** + * After initialization this pointer will hold the reference to the main line switcher object. + */ + PowerSwitchIF *mainLineSwitcher = nullptr; + + ActionHelper actionHelper; + + void readCommandQueue(); + + /** + * @brief This function performs actions dependent on the current state. + */ + void handleStateMachine(); + + /** + * @brief This function polls the 8V switch state and changes the state machine when the + * switch has been enabled. + */ + void performWaitOn8VActions(); + + /** + * @brief This functions handles the switching of the solar array deployment transistors. + */ + void switchDeploymentTransistors(); + + /** + * @brief This function performs actions to finish the deployment. Essentially switches + * are turned of after the burn time has expired. + */ + void handleDeploymentFinish(); +}; + +#endif /* MISSION_DEVICES_SOLARARRAYDEPLOYMENT_H_ */ diff --git a/bsp_q7s/main.cpp b/bsp_q7s/main.cpp index 49416ae2..b087e315 100644 --- a/bsp_q7s/main.cpp +++ b/bsp_q7s/main.cpp @@ -13,15 +13,15 @@ int main(void) { std::cout << "-- EIVE OBSW --" << std::endl; - std::cout << "-- Compiled for Linux " << " --" << std::endl; + std::cout << "-- Compiled for Linux (Xiphos Q7S) --" << std::endl; std::cout << "-- Software version " << SW_NAME << " v" << SW_VERSION << "." << SW_SUBVERSION << "." << SW_SUBSUBVERSION << " -- " << std::endl; std::cout << "-- " << __DATE__ << " " << __TIME__ << " --" << std::endl; - InitMission::initMission(); + initmission::initMission(); for(;;) { - // suspend main thread by sleeping it. + /* Suspend main thread by sleeping it. */ TaskFactory::delayTask(5000); } } diff --git a/bsp_rpi/CMakeLists.txt b/bsp_rpi/CMakeLists.txt index 281994bf..da35633d 100644 --- a/bsp_rpi/CMakeLists.txt +++ b/bsp_rpi/CMakeLists.txt @@ -6,11 +6,8 @@ target_sources(${TARGET_NAME} PUBLIC add_subdirectory(boardconfig) add_subdirectory(boardtest) - -# wiringPi is deprecated unfortunately.. -#target_link_libraries(${TARGET_NAME} PRIVATE -# wiringPi -#) +add_subdirectory(gpio) + diff --git a/bsp_rpi/InitMission.cpp b/bsp_rpi/InitMission.cpp index 197abcc6..ce2a5940 100644 --- a/bsp_rpi/InitMission.cpp +++ b/bsp_rpi/InitMission.cpp @@ -1,16 +1,19 @@ #include "InitMission.h" #include "ObjectFactory.h" +#include +#include +#include + +#include + #include #include -#include +#include #include #include #include #include -#include -#include -#include #include @@ -21,9 +24,9 @@ ServiceInterfaceStream sif::error("ERROR"); ObjectManagerIF *objectManager = nullptr; -void InitMission::initMission() { - sif::info << "Building global objects.." << std::endl; - /* Instantiate global object manager and also create all objects */ +void initmission::initMission() { + sif::info << "Building global objects.." << std::endl; + /* Instantiate global object manager and also create all objects */ objectManager = new ObjectManager(ObjectFactory::produce); sif::info << "Initializing all objects.." << std::endl; objectManager->initialize(); @@ -32,129 +35,144 @@ void InitMission::initMission() { initTasks(); } -void InitMission::initTasks(){ - /* TMTC Distribution */ - PeriodicTaskIF* TmTcDistributor = TaskFactory::instance()-> - createPeriodicTask("DIST", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, - 0.100, nullptr); - ReturnValue_t result = TmTcDistributor->addComponent( - objects::CCSDS_PACKET_DISTRIBUTOR); - if(result != HasReturnvaluesIF::RETURN_OK){ - sif::error << "Object add component failed" << std::endl; - } - result = TmTcDistributor->addComponent(objects::PUS_PACKET_DISTRIBUTOR); - if(result != HasReturnvaluesIF::RETURN_OK){ - sif::error << "Object add component failed" << std::endl; - } - result = TmTcDistributor->addComponent(objects::TM_FUNNEL); +void initmission::initTasks() { + TaskFactory* factory = TaskFactory::instance(); + if(factory == nullptr) { + /* Should never happen ! */ + return; + } +#if OBSW_PRINT_MISSED_DEADLINES == 1 + void (*missedDeadlineFunc) (void) = TaskFactory::printMissedDeadline; +#else + void (*missedDeadlineFunc) (void) = nullptr; +#endif + + /* TMTC Distribution */ + PeriodicTaskIF* tmTcDistributor = factory->createPeriodicTask( + "DIST", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc); + ReturnValue_t result = tmTcDistributor->addComponent( + objects::CCSDS_PACKET_DISTRIBUTOR); + if(result != HasReturnvaluesIF::RETURN_OK){ + sif::error << "Object add component failed" << std::endl; + } + result = tmTcDistributor->addComponent(objects::PUS_PACKET_DISTRIBUTOR); + if(result != HasReturnvaluesIF::RETURN_OK){ + sif::error << "Object add component failed" << std::endl; + } + result = tmTcDistributor->addComponent(objects::TM_FUNNEL); if(result != HasReturnvaluesIF::RETURN_OK) { - sif::error << "Object add component failed" << std::endl; + sif::error << "Object add component failed" << std::endl; } /* UDP bridge */ - PeriodicTaskIF* UdpBridgeTask = TaskFactory::instance()->createPeriodicTask( - "UDP_UNIX_BRIDGE", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, - 0.2, nullptr); - result = UdpBridgeTask->addComponent(objects::UDP_BRIDGE); + PeriodicTaskIF* udpBridgeTask = factory->createPeriodicTask( + "UDP_UNIX_BRIDGE", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc); + result = udpBridgeTask->addComponent(objects::UDP_BRIDGE); if(result != HasReturnvaluesIF::RETURN_OK) { - sif::error << "Add component UDP Unix Bridge failed" << std::endl; + sif::error << "Add component UDP Unix Bridge failed" << std::endl; } - PeriodicTaskIF* UdpPollingTask = TaskFactory::instance()-> - createPeriodicTask("UDP_POLLING", 80, - PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, nullptr); - result = UdpPollingTask->addComponent(objects::UDP_POLLING_TASK); + PeriodicTaskIF* udpPollingTask = factory->createPeriodicTask( + "UDP_POLLING", 80, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, missedDeadlineFunc); + result = udpPollingTask->addComponent(objects::UDP_POLLING_TASK); if(result != HasReturnvaluesIF::RETURN_OK) { - sif::error << "Add component UDP Polling failed" << std::endl; + sif::error << "Add component UDP Polling failed" << std::endl; } - /* PUS Services */ - PeriodicTaskIF* PusVerification = TaskFactory::instance()-> - createPeriodicTask("PUS_VERIF_1", 40, - PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, nullptr); - result = PusVerification->addComponent(objects::PUS_SERVICE_1_VERIFICATION); - if(result != HasReturnvaluesIF::RETURN_OK){ - sif::error << "Object add component failed" << std::endl; - } - - PeriodicTaskIF* PusEvents = TaskFactory::instance()-> - createPeriodicTask("PUS_VERIF_1", 60, - PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, nullptr); - result = PusVerification->addComponent(objects::PUS_SERVICE_5_EVENT_REPORTING); - if(result != HasReturnvaluesIF::RETURN_OK){ - sif::error << "Object add component failed" << std::endl; - } - - PeriodicTaskIF* PusHighPrio = TaskFactory::instance()-> - createPeriodicTask("PUS_HIGH_PRIO", 50, - PeriodicTaskIF::MINIMUM_STACK_SIZE, - 0.200, nullptr); - result = PusHighPrio->addComponent(objects::PUS_SERVICE_2_DEVICE_ACCESS); - if(result != HasReturnvaluesIF::RETURN_OK){ - sif::error << "Object add component failed" << std::endl; - } - result = PusHighPrio->addComponent(objects::PUS_SERVICE_9_TIME_MGMT); - if(result != HasReturnvaluesIF::RETURN_OK){ - sif::error << "Object add component failed" << std::endl; - } - - PeriodicTaskIF* PusMedPrio = TaskFactory::instance()-> - createPeriodicTask("PUS_HIGH_PRIO", 40, - PeriodicTaskIF::MINIMUM_STACK_SIZE, - 0.8, nullptr); - result = PusMedPrio->addComponent(objects::PUS_SERVICE_8_FUNCTION_MGMT); - if(result != HasReturnvaluesIF::RETURN_OK){ - sif::error << "Object add component failed" << std::endl; - } - result = PusMedPrio->addComponent(objects::PUS_SERVICE_200_MODE_MGMT); - if(result != HasReturnvaluesIF::RETURN_OK){ - sif::error << "Object add component failed" << std::endl; - } - - PeriodicTaskIF* PusLowPrio = TaskFactory::instance()-> - createPeriodicTask("PUSB", 30, PeriodicTaskIF::MINIMUM_STACK_SIZE, - 1.6, nullptr); - result = PusLowPrio->addComponent(objects::PUS_SERVICE_17_TEST); - if(result != HasReturnvaluesIF::RETURN_OK){ - sif::error << "Object add component failed" << std::endl; - } - - -#if OBSW_ADD_TEST_CODE == 1 - FixedTimeslotTaskIF* TestTimeslotTask = TaskFactory::instance()-> - createFixedTimeslotTask("PST_TEST_TASK", 10, - PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.0, nullptr); - result = pst::pollingSequenceTestFunction(TestTimeslotTask); - if(result != HasReturnvaluesIF::RETURN_OK) { - sif::error << "InitMission::createTasks: Test PST initialization " - << "failed!" << std::endl; - } - -#endif - - PeriodicTaskIF* SpiTestTask = TaskFactory::instance()-> - createPeriodicTask("SPI_TEST", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, - 2.0, nullptr); - result = SpiTestTask->addComponent(objects::SPI_TEST); + /* PUS Services */ + PeriodicTaskIF* pusVerification = factory->createPeriodicTask( + "PUS_VERIF", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc); + result = pusVerification->addComponent(objects::PUS_SERVICE_1_VERIFICATION); if(result != HasReturnvaluesIF::RETURN_OK){ - sif::error << "Object add SPI test failed" << std::endl; + sif::error << "Object add component failed" << std::endl; } - //Main thread sleep - sif::info << "Starting tasks.." << std::endl; - TmTcDistributor->startTask(); - UdpBridgeTask->startTask(); - UdpPollingTask->startTask(); + PeriodicTaskIF* pusEvents = factory->createPeriodicTask( + "PUS_EVENTS", 60, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc); + result = pusVerification->addComponent(objects::PUS_SERVICE_5_EVENT_REPORTING); + if(result != HasReturnvaluesIF::RETURN_OK){ + initmission::printAddObjectError("PUS5", objects::PUS_SERVICE_5_EVENT_REPORTING); + } - PusVerification->startTask(); - PusEvents->startTask(); - PusHighPrio->startTask(); - PusMedPrio->startTask(); - PusLowPrio->startTask(); + PeriodicTaskIF* pusHighPrio = factory->createPeriodicTask( + "PUS_HIGH_PRIO", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc); + result = pusHighPrio->addComponent(objects::PUS_SERVICE_2_DEVICE_ACCESS); + if(result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS2", objects::PUS_SERVICE_2_DEVICE_ACCESS); + } + result = pusHighPrio->addComponent(objects::PUS_SERVICE_9_TIME_MGMT); + if(result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS9", objects::PUS_SERVICE_9_TIME_MGMT); + } - SpiTestTask->startTask(); + PeriodicTaskIF* pusMedPrio = factory->createPeriodicTask( + "PUS_MED_PRIO", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.8, missedDeadlineFunc); + result = pusMedPrio->addComponent(objects::PUS_SERVICE_8_FUNCTION_MGMT); + if(result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS8", objects::PUS_SERVICE_8_FUNCTION_MGMT); + } + result = pusMedPrio->addComponent(objects::PUS_SERVICE_200_MODE_MGMT); + if(result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS200", objects::PUS_SERVICE_200_MODE_MGMT); + } + result = pusMedPrio->addComponent(objects::PUS_SERVICE_20_PARAMETERS); + if(result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS20", objects::PUS_SERVICE_20_PARAMETERS); + } + + PeriodicTaskIF* pusLowPrio = factory->createPeriodicTask( + "PUS_LOW_PRIO", 30, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.6, missedDeadlineFunc); + result = pusLowPrio->addComponent(objects::PUS_SERVICE_17_TEST); + if(result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS17", objects::PUS_SERVICE_17_TEST); + } + +#if RPI_TEST_ACS_BOARD == 1 + FixedTimeslotTaskIF* acsTask = factory->createFixedTimeslotTask( + "ACS_PST", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE * 2, 2.0, missedDeadlineFunc); + result = pst::pollingSequenceAcsTest(acsTask); + if(result != HasReturnvaluesIF::RETURN_OK) { + sif::warning << "initmission::initTasks: ACS PST initialization failed!" << std::endl; + } +#endif /* RPI_TEST_ACS_BOARD == 1 */ + + PeriodicTaskIF* testTask = factory->createPeriodicTask( + "TEST_TASK", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, missedDeadlineFunc); +#if OBSW_ADD_TEST_CODE == 1 + result = testTask->addComponent(objects::TEST_TASK); + if(result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("TEST_TASK", objects::TEST_TASK); + } +#endif /* OBSW_ADD_TEST_CODE == 1 */ +#if RPI_ADD_SPI_TEST == 1 + result = testTask->addComponent(objects::SPI_TEST); + if(result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("SPI_TEST", objects::SPI_TEST); + } +#endif /* RPI_ADD_SPI_TEST == 1 */ +#if RPI_ADD_GPIO_TEST == 1 + result = testTask->addComponent(objects::LIBGPIOD_TEST); + if(result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("GPIOD_TEST", objects::LIBGPIOD_TEST); + } +#endif /* RPI_ADD_GPIO_TEST == 1 */ + + sif::info << "Starting tasks.." << std::endl; + tmTcDistributor->startTask(); + udpBridgeTask->startTask(); + udpPollingTask->startTask(); + + pusVerification->startTask(); + pusEvents->startTask(); + pusHighPrio->startTask(); + pusMedPrio->startTask(); + pusLowPrio->startTask(); #if OBSW_ADD_TEST_CODE == 1 - TestTimeslotTask->startTask(); -#endif - sif::info << "Tasks started.." << std::endl; + testTask->startTask(); +#endif /* OBSW_ADD_TEST_CODE == 1 */ + +#if RPI_TEST_ACS_BOARD == 1 + acsTask->startTask(); +#endif /* RPI_TEST_ACS_BOARD == 1 */ + sif::info << "Tasks started.." << std::endl; } diff --git a/bsp_rpi/InitMission.h b/bsp_rpi/InitMission.h index 5ecf9e41..01c72008 100644 --- a/bsp_rpi/InitMission.h +++ b/bsp_rpi/InitMission.h @@ -1,7 +1,7 @@ #ifndef BSP_LINUX_INITMISSION_H_ #define BSP_LINUX_INITMISSION_H_ -namespace InitMission { +namespace initmission { void initMission(); void initTasks(); }; diff --git a/bsp_rpi/ObjectFactory.cpp b/bsp_rpi/ObjectFactory.cpp index c90db492..3e6eeaa2 100644 --- a/bsp_rpi/ObjectFactory.cpp +++ b/bsp_rpi/ObjectFactory.cpp @@ -1,48 +1,107 @@ #include "ObjectFactory.h" -#include -#include +#include #include +#include +#include #include #include #include +#include +#include +#include +#include + +#include + +#include +#include +#include + +#include #include #include #include #include #include - -#include -#include +#include +#include void Factory::setStaticFrameworkObjectIds() { - PusServiceBase::packetSource = objects::PUS_PACKET_DISTRIBUTOR; - PusServiceBase::packetDestination = objects::TM_FUNNEL; + PusServiceBase::packetSource = objects::PUS_PACKET_DISTRIBUTOR; + PusServiceBase::packetDestination = objects::TM_FUNNEL; - CommandingServiceBase::defaultPacketSource = objects::PUS_PACKET_DISTRIBUTOR; - CommandingServiceBase::defaultPacketDestination = objects::TM_FUNNEL; + CommandingServiceBase::defaultPacketSource = objects::PUS_PACKET_DISTRIBUTOR; + CommandingServiceBase::defaultPacketDestination = objects::TM_FUNNEL; - TmFunnel::downlinkDestination = objects::UDP_BRIDGE; - // No storage object for now. - TmFunnel::storageDestination = objects::NO_OBJECT; + TmFunnel::downlinkDestination = objects::UDP_BRIDGE; + // No storage object for now. + TmFunnel::storageDestination = objects::NO_OBJECT; - LocalDataPoolManager::defaultHkDestination = objects::NO_OBJECT; + LocalDataPoolManager::defaultHkDestination = objects::NO_OBJECT; - VerificationReporter::messageReceiver = objects::PUS_SERVICE_1_VERIFICATION; - TmPacketStored::timeStamperId = objects::TIME_STAMPER; + VerificationReporter::messageReceiver = objects::PUS_SERVICE_1_VERIFICATION; + TmPacketStored::timeStamperId = objects::TIME_STAMPER; } void ObjectFactory::produce(){ - Factory::setStaticFrameworkObjectIds(); - ObjectFactory::produceGenericObjects(); + Factory::setStaticFrameworkObjectIds(); + ObjectFactory::produceGenericObjects(); - new TmTcUnixUdpBridge(objects::UDP_BRIDGE, - objects::CCSDS_PACKET_DISTRIBUTOR, - objects::TM_STORE, objects::TC_STORE); - new TcUnixUdpPollingTask(objects::UDP_POLLING_TASK, objects::UDP_BRIDGE); + new TmTcUnixUdpBridge(objects::UDP_BRIDGE, + objects::CCSDS_PACKET_DISTRIBUTOR, + objects::TM_STORE, objects::TC_STORE); + new TcUnixUdpPollingTask(objects::UDP_POLLING_TASK, objects::UDP_BRIDGE); - new SpiTest(objects::SPI_TEST); + GpioIF* gpioIF = new LinuxLibgpioIF(objects::GPIO_IF); + +#if RPI_ADD_SPI_TEST == 1 + new SpiTestClass(objects::SPI_TEST, gpioIF); +#endif + +#if RPI_LOOPBACK_TEST_GPIO == 1 + GpioCookie* gpioCookieLoopback = new GpioCookie(); + /* Loopback pins. Adapt according to setup */ + gpioId_t gpioIdSender = gpioIds::TEST_ID_0; + int bcmPinSender = 26; + gpioId_t gpioIdReader = gpioIds::TEST_ID_1; + int bcmPinReader = 16; + gpio::createRpiGpioConfig(gpioCookieLoopback, gpioIdSender, bcmPinSender, "GPIO_LB_SENDER", + gpio::Direction::OUT, 0); + gpio::createRpiGpioConfig(gpioCookieLoopback, gpioIdReader, bcmPinReader, "GPIO_LB_READER", + gpio::Direction::IN, 0); + new LibgpiodTest(objects::LIBGPIOD_TEST, objects::GPIO_IF, gpioCookieLoopback); +#endif /* RPI_LOOPBACK_TEST_GPIO == 1 */ + + new SpiComIF(objects::SPI_COM_IF, gpioIF); + +#if RPI_TEST_ACS_BOARD == 1 + + GpioCookie* gpioCookieAcsBoard = new GpioCookie(); + gpio::createRpiGpioConfig(gpioCookieAcsBoard, gpioIds::MGM_0_LIS3_CS, gpio::MGM_0_BCM_PIN, + "MGM_0_LIS3", gpio::Direction::OUT, 1); + gpio::createRpiGpioConfig(gpioCookieAcsBoard, gpioIds::MGM_1_RM3100_CS, gpio::MGM_1_BCM_PIN, + "MGM_1_RM3100", gpio::Direction::OUT, 1); + gpio::createRpiGpioConfig(gpioCookieAcsBoard, gpioIds::MGM_2_LIS3_CS, gpio::MGM_2_BCM_PIN, + "MGM_2_LIS3", gpio::Direction::OUT, 1); + gpio::createRpiGpioConfig(gpioCookieAcsBoard, gpioIds::MGM_3_RM3100_CS, gpio::MGM_3_BCM_PIN, + "MGM_3_RM3100", gpio::Direction::OUT, 1); + gpio::createRpiGpioConfig(gpioCookieAcsBoard, gpioIds::GYRO_0_ADIS_CS, gpio::GYRO_0_BCM_PIN, + "GYRO_0_ADIS", gpio::Direction::OUT, 1); + gpio::createRpiGpioConfig(gpioCookieAcsBoard, gpioIds::GYRO_1_L3G_CS, gpio::GYRO_1_BCM_PIN, + "GYRO_1_L3G", gpio::Direction::OUT, 1); + gpio::createRpiGpioConfig(gpioCookieAcsBoard, gpioIds::GYRO_2_L3G_CS, gpio::GYRO_2_BCM_PIN, + "GYRO_2_L3G", gpio::Direction::OUT, 1); + gpioIF->addGpios(gpioCookieAcsBoard); + + SpiCookie* spiCookie = new SpiCookie(addresses::MGM_0_LIS3, + gpioIds::MGM_0_LIS3_CS, "/dev/spidev0.0", 24, spi::SpiMode::MODE_3, 3'900'000); + auto mgmHandler = new MGMHandlerLIS3MDL(objects::MGM_0_LIS3_HANDLER, + objects::SPI_COM_IF, spiCookie); + mgmHandler->setStartUpImmediately(); + +#endif /* RPI_TEST_ACS_BOARD == 1 */ } diff --git a/bsp_rpi/boardconfig/rpi_config.h b/bsp_rpi/boardconfig/rpi_config.h new file mode 100644 index 00000000..d1acacb6 --- /dev/null +++ b/bsp_rpi/boardconfig/rpi_config.h @@ -0,0 +1,24 @@ +#ifndef BSP_RPI_BOARDCONFIG_RPI_CONFIG_H_ +#define BSP_RPI_BOARDCONFIG_RPI_CONFIG_H_ + +#include + +#define RPI_ADD_GPIO_TEST 0 +#define RPI_LOOPBACK_TEST_GPIO 0 + +/* Only one of those 2 should be enabled! */ +#define RPI_ADD_SPI_TEST 0 +#define RPI_TEST_ACS_BOARD 1 + +/* Adapt these values accordingly */ +namespace gpio { +static constexpr uint8_t MGM_0_BCM_PIN = 0; +static constexpr uint8_t MGM_1_BCM_PIN = 1; +static constexpr uint8_t MGM_2_BCM_PIN = 17; +static constexpr uint8_t MGM_3_BCM_PIN = 27; +static constexpr uint8_t GYRO_0_BCM_PIN = 5; +static constexpr uint8_t GYRO_1_BCM_PIN = 6; +static constexpr uint8_t GYRO_2_BCM_PIN = 4; +} + +#endif /* BSP_RPI_BOARDCONFIG_RPI_CONFIG_H_ */ diff --git a/bsp_rpi/boardtest/CMakeLists.txt b/bsp_rpi/boardtest/CMakeLists.txt index 1e373efb..0599b73f 100644 --- a/bsp_rpi/boardtest/CMakeLists.txt +++ b/bsp_rpi/boardtest/CMakeLists.txt @@ -1,6 +1,4 @@ target_sources(${TARGET_NAME} PRIVATE - SpiTest.cpp - RPiGPIO.cpp ) diff --git a/bsp_rpi/gpio/CMakeLists.txt b/bsp_rpi/gpio/CMakeLists.txt new file mode 100644 index 00000000..85bd6aa6 --- /dev/null +++ b/bsp_rpi/gpio/CMakeLists.txt @@ -0,0 +1,9 @@ +target_sources(${TARGET_NAME} PUBLIC + GPIORPi.cpp +) + + + + + + diff --git a/bsp_rpi/gpio/GPIORPi.cpp b/bsp_rpi/gpio/GPIORPi.cpp new file mode 100644 index 00000000..74b67a42 --- /dev/null +++ b/bsp_rpi/gpio/GPIORPi.cpp @@ -0,0 +1,36 @@ +#include "GPIORPi.h" +#include + +#include +#include + +ReturnValue_t gpio::createRpiGpioConfig(GpioCookie* cookie, gpioId_t gpioId, int bcmPin, + std::string consumer, gpio::Direction direction, int initValue) { + if(cookie == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } + + GpiodRegular config; + /* Default chipname for Raspberry Pi. There is still gpiochip1 for expansion, but most users + will not need this */ + config.chipname = "gpiochip0"; + + config.consumer = consumer; + config.direction = direction; + config.initValue = initValue; + + /* Sanity check for the BCM pins before assigning it */ + if(bcmPin > 27) { +#if FSFW_VERBOSE_LEVEL >= 1 +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::error << "createRpiGpioConfig: BCM pin " << bcmPin << " invalid!" << std::endl; +#else + sif::printError("createRpiGpioConfig: BCM pin %d invalid!\n", bcmPin); +#endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ +#endif /* FSFW_VERBOSE_LEVEL >= 1 */ + return HasReturnvaluesIF::RETURN_FAILED; + } + config.lineNum = bcmPin; + cookie->addGpio(gpioId, config); + return HasReturnvaluesIF::RETURN_OK; +} diff --git a/bsp_rpi/gpio/GPIORPi.h b/bsp_rpi/gpio/GPIORPi.h new file mode 100644 index 00000000..a2c11879 --- /dev/null +++ b/bsp_rpi/gpio/GPIORPi.h @@ -0,0 +1,26 @@ +#ifndef BSP_RPI_GPIO_GPIORPI_H_ +#define BSP_RPI_GPIO_GPIORPI_H_ + +#include +#include + +class GpioCookie; + +namespace gpio { + +/** + * Create a GpioConfig_t. This function does a sanity check on the BCM pin number and fails if the + * BCM pin is invalid. + * @param cookie Adds the configuration to this cookie directly + * @param gpioId ID which identifies the GPIO configuration + * @param bcmPin Raspberry Pi BCM pin + * @param consumer Information string + * @param direction GPIO direction + * @param initValue Intial value for output pins, 0 for low, 1 for high + * @return + */ +ReturnValue_t createRpiGpioConfig(GpioCookie* cookie, gpioId_t gpioId, int bcmPin, + std::string consumer, gpio::Direction direction, int initValue); +} + +#endif /* BSP_RPI_GPIO_GPIORPI_H_ */ diff --git a/bsp_rpi/main.cpp b/bsp_rpi/main.cpp index 5f6be8db..8eea768c 100644 --- a/bsp_rpi/main.cpp +++ b/bsp_rpi/main.cpp @@ -1,28 +1,26 @@ #include "InitMission.h" - #include + #include #include -#include - /** - * @brief This is the main program for the target hardware. + * @brief This is the main program and entry point for the Raspberry Pi. * @return */ int main(void) { std::cout << "-- EIVE OBSW --" << std::endl; - std::cout << "-- Compiled for Linux " << " --" << std::endl; + std::cout << "-- Compiled for Linux (Raspberry Pi) --" << std::endl; std::cout << "-- Software version " << SW_NAME << " v" << SW_VERSION << "." << SW_SUBVERSION << "." << SW_SUBSUBVERSION << " -- " << std::endl; std::cout << "-- " << __DATE__ << " " << __TIME__ << " --" << std::endl; - InitMission::initMission(); + initmission::initMission(); for(;;) { - // suspend main thread by sleeping it. + /* Suspend main thread by sleeping it. */ TaskFactory::delayTask(5000); } } diff --git a/cmake/scripts/Host/create_cmake_debug_cfg.sh b/cmake/scripts/Host/create_cmake_debug_cfg.sh index ee7b441a..23c74de0 100644 --- a/cmake/scripts/Host/create_cmake_debug_cfg.sh +++ b/cmake/scripts/Host/create_cmake_debug_cfg.sh @@ -15,6 +15,7 @@ if [ "${counter}" -ge 5 ];then fi build_generator="" +build_dir="Debug-Host" os_fsfw="host" if [ "${OS}" = "Windows_NT" ]; then build_generator="MinGW Makefiles" @@ -23,4 +24,4 @@ else build_generator="Unix Makefiles" fi -python3 cmake_build_config.py -o "${os_fsfw}" -g "${build_generator}" -b "debug" +python3 cmake_build_config.py -o "${os_fsfw}" -g "${build_generator}" -b "debug" -l"${build_dir}" diff --git a/cmake/scripts/Host/create_cmake_release_cfg.sh b/cmake/scripts/Host/create_cmake_release_cfg.sh index 778cde3b..03378e98 100644 --- a/cmake/scripts/Host/create_cmake_release_cfg.sh +++ b/cmake/scripts/Host/create_cmake_release_cfg.sh @@ -16,6 +16,7 @@ fi build_generator="" os_fsfw="host" +build_dir="Debug-Release" if [ "${OS}" = "Windows_NT" ]; then build_generator="MinGW Makefiles" # Could be other OS but this works for now. @@ -23,4 +24,4 @@ else build_generator="Unix Makefiles" fi -python3 cmake_build_config.py -o "${os_fsfw}" -g "${build_generator}" -b "release" +python3 cmake_build_config.py -o "${os_fsfw}" -g "${build_generator}" -b "release" -l"${build_dir}" diff --git a/cmake/scripts/RPi/create_cmake_debug_cfg.sh b/cmake/scripts/RPi/create_cmake_debug_cfg.sh index deb78243..d0ec5d76 100644 --- a/cmake/scripts/RPi/create_cmake_debug_cfg.sh +++ b/cmake/scripts/RPi/create_cmake_debug_cfg.sh @@ -17,6 +17,7 @@ fi os_fsfw="linux" tgt_bsp="arm/raspberrypi" build_generator="" +build_dir="Debug-RPi" if [ "${OS}" = "Windows_NT" ]; then build_generator="MinGW Makefiles" # Could be other OS but this works for now. @@ -24,4 +25,5 @@ else build_generator="Unix Makefiles" fi -python3 cmake_build_config.py -o "${os_fsfw}" -g "${build_generator}" -b "debug" -t "${tgt_bsp}" +python3 cmake_build_config.py -o "${os_fsfw}" -g "${build_generator}" -b "debug" -t "${tgt_bsp}" \ + -l"${build_dir}" diff --git a/cmake/scripts/RPi/create_cmake_release_cfg.sh b/cmake/scripts/RPi/create_cmake_release_cfg.sh index 0e23bee4..4eb9b38a 100644 --- a/cmake/scripts/RPi/create_cmake_release_cfg.sh +++ b/cmake/scripts/RPi/create_cmake_release_cfg.sh @@ -17,6 +17,7 @@ fi os_fsfw="linux" tgt_bsp="arm/raspberrypi" build_generator="" +build_dir="Release-RPi" if [ "${OS}" = "Windows_NT" ]; then build_generator="MinGW Makefiles" # Could be other OS but this works for now. @@ -24,4 +25,5 @@ else build_generator="Unix Makefiles" fi -python3 cmake_build_config.py -o "${os_fsfw}" -g "${build_generator}" -b "release" -t "${tgt_bsp}" +python3 cmake_build_config.py -o "${os_fsfw}" -g "${build_generator}" -b "release" -t "${tgt_bsp}" \ + -l"${build_dir}" diff --git a/cmake/scripts/RPi/create_cmake_relwithdeb_cfg.sh b/cmake/scripts/RPi/create_cmake_relwithdeb_cfg.sh index 3e952750..de7651a7 100644 --- a/cmake/scripts/RPi/create_cmake_relwithdeb_cfg.sh +++ b/cmake/scripts/RPi/create_cmake_relwithdeb_cfg.sh @@ -17,6 +17,7 @@ fi os_fsfw="linux" tgt_bsp="arm/raspberrypi" build_generator="" +build_dir="RelWithDeb-RPi" if [ "${OS}" = "Windows_NT" ]; then build_generator="MinGW Makefiles" # Could be other OS but this works for now. @@ -24,4 +25,5 @@ else build_generator="Unix Makefiles" fi -python3 cmake_build_config.py -o "${os_fsfw}" -g "${build_generator}" -b "reldeb" -t "${tgt_bsp}" +python3 cmake_build_config.py -o "${os_fsfw}" -g "${build_generator}" -b "reldeb" -t "${tgt_bsp}" \ + -l"${build_dir}" diff --git a/cmake/scripts/cmake_build_config.py b/cmake/scripts/cmake_build_config.py index a6388ef8..0e4b6f25 100644 --- a/cmake/scripts/cmake_build_config.py +++ b/cmake/scripts/cmake_build_config.py @@ -61,9 +61,10 @@ def main(): else: cmake_target_cfg_cmd = "" - # TODO: Use builddir if given (need to check whether path is relative or absolute) build_folder = cmake_build_type - + if args.builddir is not None: + build_folder = args.builddir + build_path = source_location + os.path.sep + build_folder if os.path.isdir(build_path): remove_old_dir = input(f"{build_folder} folder already exists. Remove old directory? [y/n]: ") diff --git a/common/CMakeLists.txt b/common/CMakeLists.txt new file mode 100644 index 00000000..9040988f --- /dev/null +++ b/common/CMakeLists.txt @@ -0,0 +1 @@ +add_subdirectory(config) diff --git a/common/config/CMakeLists.txt b/common/config/CMakeLists.txt new file mode 100644 index 00000000..f38f2c50 --- /dev/null +++ b/common/config/CMakeLists.txt @@ -0,0 +1,3 @@ +target_include_directories(${TARGET_NAME} PRIVATE + ${CMAKE_CURRENT_SOURCE_DIR} +) \ No newline at end of file diff --git a/common/config/commonConfig.h b/common/config/commonConfig.h new file mode 100644 index 00000000..6c5cb4c4 --- /dev/null +++ b/common/config/commonConfig.h @@ -0,0 +1,7 @@ +#ifndef COMMON_CONFIG_COMMONCONFIG_H_ +#define COMMON_CONFIG_COMMONCONFIG_H_ + +#define OBSW_ADD_LWGPS_TEST 0 + + +#endif /* COMMON_CONFIG_COMMONCONFIG_H_ */ diff --git a/common/config/lwgps_opts.h b/common/config/lwgps_opts.h new file mode 100644 index 00000000..20632d6f --- /dev/null +++ b/common/config/lwgps_opts.h @@ -0,0 +1,44 @@ +/** + * \file lwgps_opts_template.h + * \brief LwGPS configuration file + */ + +/* + * Copyright (c) 2020 Tilen MAJERLE + * + * Permission is hereby granted, free of charge, to any person + * obtaining a copy of this software and associated documentation + * files (the "Software"), to deal in the Software without restriction, + * including without limitation the rights to use, copy, modify, merge, + * publish, distribute, sublicense, and/or sell copies of the Software, + * and to permit persons to whom the Software is furnished to do so, + * subject to the following conditions: + * + * The above copyright notice and this permission notice shall be + * included in all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES + * OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE + * AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT + * HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, + * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING + * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR + * OTHER DEALINGS IN THE SOFTWARE. + * + * This file is part of LwGPS - Lightweight GPS NMEA parser library. + * + * Author: Tilen MAJERLE + * Version: v2.1.0 + */ +#ifndef LWGPS_HDR_OPTS_H +#define LWGPS_HDR_OPTS_H + +/* Rename this file to "lwgps_opts.h" for your application */ + +/* + * Open "include/lwgps/lwgps_opt.h" and + * copy & replace here settings you want to change values + */ + +#endif /* LWGPS_HDR_OPTS_H */ diff --git a/fsfwconfig/OBSWVersion.h b/fsfwconfig/OBSWVersion.h index d76b65c9..fd76332e 100644 --- a/fsfwconfig/OBSWVersion.h +++ b/fsfwconfig/OBSWVersion.h @@ -4,8 +4,8 @@ //! TODO: Think of a cool name for the software releases. const char* const SW_NAME = "eive"; -#define SW_VERSION 0 -#define SW_SUBVERSION 2 +#define SW_VERSION 1 +#define SW_SUBVERSION 0 #define SW_SUBSUBVERSION 0 diff --git a/fsfwconfig/devices/addresses.h b/fsfwconfig/devices/addresses.h index c894fcc7..cd0b9d29 100644 --- a/fsfwconfig/devices/addresses.h +++ b/fsfwconfig/devices/addresses.h @@ -1,20 +1,24 @@ -/** - * \file addresses.cpp - * - * \date 07.11.2019 - */ - #ifndef FSFWCONFIG_DEVICES_ADDRESSES_H_ #define FSFWCONFIG_DEVICES_ADDRESSES_H_ -#include + #include #include +#include namespace addresses { /* Logical addresses have uint32_t datatype */ enum logicalAddresses: address_t { PCDU, + MGM_0_LIS3 = objects::MGM_0_LIS3_HANDLER, + MGM_1_RM3100 = objects::MGM_1_RM3100_HANDLER, + MGM_2_LIS3 = objects::MGM_2_LIS3_HANDLER, + MGM_3_RM3100 = objects::MGM_3_RM3100_HANDLER, + + GYRO_0_ADIS = objects::GYRO_0_ADIS_HANDLER, + GYRO_1_L3G = objects::GYRO_1_L3G_HANDLER, + GYRO_2_L3G = objects::GYRO_2_L3G_HANDLER, + /* Dummy and Test Addresses */ DUMMY_ECHO = 129, DUMMY_GPS0 = 130, diff --git a/fsfwconfig/devices/gpioIds.h b/fsfwconfig/devices/gpioIds.h index 70507b42..8963bd20 100644 --- a/fsfwconfig/devices/gpioIds.h +++ b/fsfwconfig/devices/gpioIds.h @@ -15,7 +15,17 @@ namespace gpioIds { HEATER_7, DEPLSA1, DEPLSA2, - Test_ID + + MGM_0_LIS3_CS, + MGM_1_RM3100_CS, + GYRO_0_ADIS_CS, + GYRO_1_L3G_CS, + GYRO_2_L3G_CS, + MGM_2_LIS3_CS, + MGM_3_RM3100_CS, + + TEST_ID_0, + TEST_ID_1 }; } diff --git a/fsfwconfig/pollingsequence/PollingSequenceFactory.h b/fsfwconfig/pollingsequence/PollingSequenceFactory.h index 0b12e6b8..4003058b 100644 --- a/fsfwconfig/pollingsequence/PollingSequenceFactory.h +++ b/fsfwconfig/pollingsequence/PollingSequenceFactory.h @@ -32,6 +32,8 @@ ReturnValue_t pollingSequenceInitDefault(FixedTimeslotTaskIF *thisSequence); * blocking calls when requesting data from devices. */ ReturnValue_t gomspacePstInit(FixedTimeslotTaskIF *thisSequence); + +ReturnValue_t pollingSequenceAcsTest(FixedTimeslotTaskIF* thisSequence); } diff --git a/linux/boardtest/CMakeLists.txt b/linux/boardtest/CMakeLists.txt new file mode 100644 index 00000000..0fa4e322 --- /dev/null +++ b/linux/boardtest/CMakeLists.txt @@ -0,0 +1,10 @@ +target_sources(${TARGET_NAME} PRIVATE + LibgpiodTest.cpp + I2cTestClass.cpp + SpiTestClass.cpp + UartTestClass.cpp +) + + + + diff --git a/linux/boardtest/I2cTestClass.cpp b/linux/boardtest/I2cTestClass.cpp new file mode 100644 index 00000000..66c16b33 --- /dev/null +++ b/linux/boardtest/I2cTestClass.cpp @@ -0,0 +1,8 @@ +#include + +I2cTestClass::I2cTestClass(object_id_t objectId): TestTask(objectId) { +} + +ReturnValue_t I2cTestClass::performPeriodicAction() { + return HasReturnvaluesIF::RETURN_OK; +} diff --git a/linux/boardtest/I2cTestClass.h b/linux/boardtest/I2cTestClass.h new file mode 100644 index 00000000..172a7f71 --- /dev/null +++ b/linux/boardtest/I2cTestClass.h @@ -0,0 +1,17 @@ +#ifndef LINUX_BOARDTEST_I2CTESTCLASS_H_ +#define LINUX_BOARDTEST_I2CTESTCLASS_H_ + +#include + +class I2cTestClass: public TestTask { +public: + I2cTestClass(object_id_t objectId); + + ReturnValue_t performPeriodicAction() override; +private: + +}; + + + +#endif /* LINUX_BOARDTEST_I2CTESTCLASS_H_ */ diff --git a/linux/boardtest/LibgpiodTest.cpp b/linux/boardtest/LibgpiodTest.cpp new file mode 100644 index 00000000..d085671a --- /dev/null +++ b/linux/boardtest/LibgpiodTest.cpp @@ -0,0 +1,99 @@ +#include "LibgpiodTest.h" + +#include +#include +#include +#include + +LibgpiodTest::LibgpiodTest(object_id_t objectId, object_id_t gpioIfobjectId, + GpioCookie* gpioCookie): + TestTask(objectId) { + + gpioInterface = objectManager->get(gpioIfobjectId); + if (gpioInterface == nullptr) { + sif::error << "LibgpiodTest::LibgpiodTest: Invalid Gpio interface." << std::endl; + } + gpioInterface->addGpios(gpioCookie); + testCase = TestCases::LOOPBACK; +} + +LibgpiodTest::~LibgpiodTest() { +} + +ReturnValue_t LibgpiodTest::performPeriodicAction() { + int gpioState; + ReturnValue_t result; + + switch(testCase) { + case(TestCases::READ): { + result = gpioInterface->readGpio(gpioIds::TEST_ID_0, &gpioState); + if (result != RETURN_OK) { + sif::debug << "LibgpiodTest::performPeriodicAction: Failed to read gpio " + << std::endl; + return RETURN_FAILED; + } + else { + sif::debug << "LibgpiodTest::performPeriodicAction: MIO 0 state = " << gpioState + << std::endl; + } + break; + } + case(TestCases::LOOPBACK): { + break; + } + } + + + return RETURN_OK; +} + +ReturnValue_t LibgpiodTest::performOneShotAction() { + int gpioState; + ReturnValue_t result; + + switch(testCase) { + case(TestCases::READ): { + break; + } + case(TestCases::LOOPBACK): { + result = gpioInterface->pullHigh(gpioIds::TEST_ID_0); + if(result == HasReturnvaluesIF::RETURN_OK) { + sif::info << "LibgpiodTest::performOneShotAction: " + "GPIO pulled high successfully for loopback test" << std::endl; + } + else { + sif::warning << "LibgpiodTest::performOneShotAction: Could not pull GPIO high!" + << std::endl; + return HasReturnvaluesIF::RETURN_OK; + } + result = gpioInterface->readGpio(gpioIds::TEST_ID_1, &gpioState); + if(result == HasReturnvaluesIF::RETURN_OK and gpioState == 1) { + sif::info << "LibgpiodTest::performOneShotAction: " + "GPIO state read successfully and is high" << std::endl; + } + else { + sif::warning << "LibgpiodTest::performOneShotAction: GPIO read and is not high!" + << std::endl; + return HasReturnvaluesIF::RETURN_OK; + } + + result = gpioInterface->pullLow(gpioIds::TEST_ID_0); + if(result == HasReturnvaluesIF::RETURN_OK) { + sif::info << "LibgpiodTest::performOneShotAction: " + "GPIO pulled low successfully for loopback test" << std::endl; + } + result = gpioInterface->readGpio(gpioIds::TEST_ID_1, &gpioState); + if(result == HasReturnvaluesIF::RETURN_OK and gpioState == 0) { + sif::info << "LibgpiodTest::performOneShotAction: " + "GPIO state read successfully and is low" << std::endl; + } + else { + sif::warning << "LibgpiodTest::performOneShotAction: GPIO read and is not low!" + << std::endl; + return HasReturnvaluesIF::RETURN_OK; + } + break; + } + } + return HasReturnvaluesIF::RETURN_OK; +} diff --git a/bsp_q7s/boardtest/LibgpiodTest.h b/linux/boardtest/LibgpiodTest.h similarity index 74% rename from bsp_q7s/boardtest/LibgpiodTest.h rename to linux/boardtest/LibgpiodTest.h index 678c06a3..e9c6c030 100644 --- a/bsp_q7s/boardtest/LibgpiodTest.h +++ b/linux/boardtest/LibgpiodTest.h @@ -12,11 +12,19 @@ */ class LibgpiodTest: public TestTask { public: + enum TestCases { + READ = 0, + LOOPBACK = 1 + }; + + TestCases testCase; + LibgpiodTest(object_id_t objectId, object_id_t gpioIfobjectId, GpioCookie* gpioCookie); virtual ~LibgpiodTest(); protected: - virtual ReturnValue_t performPeriodicAction() override; + ReturnValue_t performOneShotAction() override; + ReturnValue_t performPeriodicAction() override; private: GpioIF* gpioInterface; diff --git a/linux/boardtest/SpiTestClass.cpp b/linux/boardtest/SpiTestClass.cpp new file mode 100644 index 00000000..df32ec5b --- /dev/null +++ b/linux/boardtest/SpiTestClass.cpp @@ -0,0 +1,231 @@ +#include "SpiTestClass.h" + +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include + + +SpiTestClass::SpiTestClass(object_id_t objectId, GpioIF* gpioIF): TestTask(objectId), + gpioIF(gpioIF) { + if(gpioIF == nullptr) { + sif::error << "SpiTestClass::SpiTestClass: Invalid GPIO ComIF!" << std::endl; + } + testMode = TestModes::MGM_LIS3MDL; + spiTransferStruct.rx_buf = reinterpret_cast<__u64>(recvBuffer.data()); + spiTransferStruct.tx_buf = reinterpret_cast<__u64>(sendBuffer.data()); +} + +ReturnValue_t SpiTestClass::performOneShotAction() { + switch(testMode) { + case(TestModes::NONE): { + break; + } + case(TestModes::MGM_LIS3MDL): { + performLis3MdlTest(mgm0Lis3ChipSelect); + break; + } + case(TestModes::MGM_RM3100): { + performRm3100Test(mgm1Rm3100ChipSelect); + break; + } + case(TestModes::GYRO_L3GD20H): { + break; + } + } + return HasReturnvaluesIF::RETURN_OK; +} + +ReturnValue_t SpiTestClass::performPeriodicAction() { + return HasReturnvaluesIF::RETURN_OK; +} + +void SpiTestClass::performRm3100Test(uint8_t mgmId) { + /* Configure all SPI chip selects and pull them high */ + acsInit(); + + /* Adapt accordingly */ + if(mgmId != mgm1Rm3100ChipSelect and mgmId != mgm3Rm3100ChipSelect) { + sif::warning << "SpiTestClass::performRm3100Test: Invalid MGM ID!" << std::endl; + } + gpioId_t currentGpioId = 0; + uint8_t chipSelectPin = mgmId; + if(chipSelectPin == mgm1Rm3100ChipSelect) { + currentGpioId = gpioIds::MGM_1_RM3100_CS; + } + else { + currentGpioId = gpioIds::MGM_3_RM3100_CS; + } + uint32_t rm3100speed = 3'900'000; + uint8_t rm3100revidReg = 0x36; + spi::SpiMode rm3100mode = spi::SpiMode::MODE_3; + //spiTransferStruct.speed_hz = rm3100Speed; +#ifdef RASPBERRY_PI + std::string deviceName = "/dev/spidev0.0"; +#else + std::string deviceName = "placeholder"; +#endif + int fileDescriptor = 0; + + + utility::UnixFileHelper fileHelper(deviceName, &fileDescriptor, O_RDWR, + "SpiComIF::initializeInterface: "); + if(fileHelper.getOpenResult()) { + sif::error << "SpiTestClass::performRm3100Test: File descriptor could not be opened!" + << std::endl; + return; + } + setSpiSpeedAndMode(fileDescriptor, rm3100mode, rm3100speed); + + uint8_t revId = readStmRegister(fileDescriptor, currentGpioId, rm3100revidReg, false); + sif::info << "SpiTestClass::performRm3100Test: Revision ID 0b" << std::bitset<8>(revId) << + std::endl; +} + +void SpiTestClass::performLis3MdlTest(uint8_t lis3Id) { + /* Configure all SPI chip selects and pull them high */ + acsInit(); + + /* Adapt accordingly */ + if(lis3Id != mgm0Lis3ChipSelect and lis3Id != mgm2Lis3mdlChipSelect) { + sif::warning << "SpiTestClass::performLis3MdlTest: Invalid MGM ID!" << std::endl; + } + gpioId_t currentGpioId = 0; + uint8_t chipSelectPin = lis3Id; + uint8_t whoAmIReg = 0b0000'1111; + if(chipSelectPin == mgm0Lis3ChipSelect) { + currentGpioId = gpioIds::MGM_0_LIS3_CS; + } + else { + currentGpioId = gpioIds::MGM_2_LIS3_CS; + } + uint32_t spiSpeed = 3'900'000; + spi::SpiMode spiMode = spi::SpiMode::MODE_3; +#ifdef RASPBERRY_PI + std::string deviceName = "/dev/spidev0.0"; +#else + std::string deviceName = "placeholder"; +#endif + int fileDescriptor = 0; + + utility::UnixFileHelper fileHelper(deviceName, &fileDescriptor, O_RDWR, + "SpiComIF::initializeInterface: "); + if(fileHelper.getOpenResult()) { + sif::error << "SpiTestClass::performLis3Mdl3100Test: File descriptor could not be opened!" + << std::endl; + return; + } + setSpiSpeedAndMode(fileDescriptor, spiMode, spiSpeed); + + uint8_t whoAmIRegVal = readStmRegister(fileDescriptor, currentGpioId, whoAmIReg, false); + sif::info << "SpiTestClass::performLis3MdlTest: WHO AM I Regiter 0b" << + std::bitset<8>(whoAmIRegVal) << std::endl; +} + + +void SpiTestClass::acsInit() { + GpioCookie* gpioCookie = new GpioCookie(); + std::string rpiGpioName = "gpiochip0"; + { + GpiodRegular gpio(rpiGpioName, mgm0Lis3ChipSelect, "MGM_0_LIS3", + gpio::Direction::OUT, 1); + gpioCookie->addGpio(gpioIds::MGM_0_LIS3_CS, gpio); + } + { + GpiodRegular gpio(rpiGpioName, mgm1Rm3100ChipSelect, "MGM_1_RM3100", + gpio::Direction::OUT, 1); + gpioCookie->addGpio(gpioIds::MGM_1_RM3100_CS, gpio); + } + { + GpiodRegular gpio(rpiGpioName, gyro0AdisChipSelect, "GYRO_0_ADIS", + gpio::Direction::OUT, 1); + gpioCookie->addGpio(gpioIds::GYRO_0_ADIS_CS, gpio); + } + { + GpiodRegular gpio(rpiGpioName, gyro1L3gd20ChipSelect, "GYRO_1_L3G", + gpio::Direction::OUT, 1); + gpioCookie->addGpio(gpioIds::GYRO_1_L3G_CS, gpio); + } + { + GpiodRegular gpio(rpiGpioName, gyro2L3gd20ChipSelect, "GYRO_2_L3G", + gpio::Direction::OUT, 1); + gpioCookie->addGpio(gpioIds::GYRO_2_L3G_CS, gpio); + } + { + GpiodRegular gpio(rpiGpioName, mgm2Lis3mdlChipSelect, "MGM_2_LIS3", + gpio::Direction::OUT, 1); + gpioCookie->addGpio(gpioIds::MGM_2_LIS3_CS, gpio); + } + { + GpiodRegular gpio(rpiGpioName, mgm3Rm3100ChipSelect, "MGM_3_RM3100", + gpio::Direction::OUT, 1); + gpioCookie->addGpio(gpioIds::MGM_3_RM3100_CS, gpio); + } + if(gpioIF != nullptr) { + gpioIF->addGpios(gpioCookie); + } +} + +void SpiTestClass::writeStmRegister(int fd, gpioId_t chipSelect, uint8_t reg, uint8_t value, + bool autoIncrement) { + if(autoIncrement) { + reg |= STM_AUTO_INCR_MASK; + } + spiTransferStruct.len = 2; + sendBuffer[0] = reg; + sendBuffer[1] = value; + + if(gpioIF != nullptr and chipSelect != gpio::NO_GPIO) { + gpioIF->pullLow(chipSelect); + } + int retval = ioctl(fd, SPI_IOC_MESSAGE(1), &spiTransferStruct); + if(retval != 0) { + utility::handleIoctlError("SpiTestClass::writeStmRegister: Write failed"); + } + if(gpioIF != nullptr and chipSelect != gpio::NO_GPIO) { + gpioIF->pullHigh(chipSelect); + } +} + +void SpiTestClass::setSpiSpeedAndMode(int spiFd, spi::SpiMode mode, uint32_t speed) { + int retval = ioctl(spiFd, SPI_IOC_WR_MODE, reinterpret_cast(&mode)); + if(retval != 0) { + utility::handleIoctlError("SpiTestClass::performRm3100Test: Setting SPI mode failed!"); + } + + retval = ioctl(spiFd, SPI_IOC_WR_MAX_SPEED_HZ, &speed); + if(retval != 0) { + utility::handleIoctlError("SpiTestClass::performRm3100Test: Setting SPI speed failed!"); + } +} + +uint8_t SpiTestClass::readStmRegister(int fd, gpioId_t chipSelect, uint8_t reg, + bool autoIncrement) { + reg |= STM_READ_MASK; + if(autoIncrement) { + reg |= STM_AUTO_INCR_MASK; + } + spiTransferStruct.len = 2; + sendBuffer[0] = reg; + sendBuffer[1] = 0; + + if(gpioIF != nullptr and chipSelect != gpio::NO_GPIO) { + gpioIF->pullLow(chipSelect); + } + int retval = ioctl(fd, SPI_IOC_MESSAGE(1), &spiTransferStruct); + if(retval < 0) { + utility::handleIoctlError("SpiTestClass::readStmRegiste: Read failed"); + } + if(gpioIF != nullptr and chipSelect != gpio::NO_GPIO) { + gpioIF->pullHigh(chipSelect); + } + return recvBuffer[1]; +} diff --git a/linux/boardtest/SpiTestClass.h b/linux/boardtest/SpiTestClass.h new file mode 100644 index 00000000..61c2d2b2 --- /dev/null +++ b/linux/boardtest/SpiTestClass.h @@ -0,0 +1,61 @@ +#ifndef LINUX_BOARDTEST_SPITESTCLASS_H_ +#define LINUX_BOARDTEST_SPITESTCLASS_H_ + +#include +#include +#include + +#include + +class SpiTestClass: public TestTask { +public: + enum TestModes { + NONE, + MGM_LIS3MDL, + MGM_RM3100, + GYRO_L3GD20H, + }; + + TestModes testMode; + + SpiTestClass(object_id_t objectId, GpioIF* gpioIF); + + ReturnValue_t performOneShotAction() override; + ReturnValue_t performPeriodicAction() override; +private: + + GpioIF* gpioIF; + + std::array recvBuffer; + std::array sendBuffer; + struct spi_ioc_transfer spiTransferStruct; + + void performRm3100Test(uint8_t mgmId); + void performLis3MdlTest(uint8_t lis3Id); + + /* ACS board specific code which pulls all GPIOs high */ + void acsInit(); + + /* ACS board specific variables */ + uint8_t mgm0Lis3ChipSelect = 0; + uint8_t mgm1Rm3100ChipSelect = 1; + uint8_t gyro0AdisChipSelect = 5; + uint8_t gyro1L3gd20ChipSelect = 6; + uint8_t gyro2L3gd20ChipSelect = 4; + uint8_t mgm2Lis3mdlChipSelect = 17; + uint8_t mgm3Rm3100ChipSelect = 27; + + static constexpr uint8_t STM_READ_MASK = 0b1000'0000; + static constexpr uint8_t STM_AUTO_INCR_MASK = 0b0100'0000; + + void setSpiSpeedAndMode(int spiFd, spi::SpiMode mode, uint32_t speed); + void writeStmRegister(int fd, gpioId_t chipSelect, uint8_t reg, uint8_t value, + bool autoIncrement); + uint8_t readStmRegister(int fd, gpioId_t chipSelect, uint8_t reg, bool autoIncrement); + +}; + + + + +#endif /* LINUX_BOARDTEST_SPITESTCLASS_H_ */ diff --git a/linux/boardtest/UartTestClass.cpp b/linux/boardtest/UartTestClass.cpp new file mode 100644 index 00000000..dc9f79c3 --- /dev/null +++ b/linux/boardtest/UartTestClass.cpp @@ -0,0 +1,8 @@ +#include + +UartTestClass::UartTestClass(object_id_t objectId): TestTask(objectId) { +} + +ReturnValue_t UartTestClass::performPeriodicAction() { + return HasReturnvaluesIF::RETURN_OK; +} diff --git a/linux/boardtest/UartTestClass.h b/linux/boardtest/UartTestClass.h new file mode 100644 index 00000000..406d2af5 --- /dev/null +++ b/linux/boardtest/UartTestClass.h @@ -0,0 +1,15 @@ +#ifndef LINUX_BOARDTEST_UARTTESTCLASS_H_ +#define LINUX_BOARDTEST_UARTTESTCLASS_H_ + +#include + +class UartTestClass: public TestTask { +public: + UartTestClass(object_id_t objectId); + + ReturnValue_t performPeriodicAction() override; +private: + +}; + +#endif /* LINUX_BOARDTEST_UARTTESTCLASS_H_ */ diff --git a/linux/csp/CspCookie.h b/linux/csp/CspCookie.h index e877761d..4514c257 100644 --- a/linux/csp/CspCookie.h +++ b/linux/csp/CspCookie.h @@ -1,5 +1,5 @@ -#ifndef BSP_Q7S_COMIF_COOKIES_CSPCOOKIE_H_ -#define BSP_Q7S_COMIF_COOKIES_CSPCOOKIE_H_ +#ifndef LINUX_CSP_CSPCOOKIE_H_ +#define LINUX_CSP_CSPCOOKIE_H_ #include #include @@ -24,4 +24,4 @@ private: uint8_t cspAddress; }; -#endif /* BSP_Q7S_COMIF_COOKIES_CSPCOOKIE_H_ */ +#endif /* LINUX_CSP_CSPCOOKIE_H_ */ diff --git a/linux/gpio/CMakeLists.txt b/linux/gpio/CMakeLists.txt index 052173b3..9b20b35e 100644 --- a/linux/gpio/CMakeLists.txt +++ b/linux/gpio/CMakeLists.txt @@ -3,6 +3,10 @@ target_sources(${TARGET_NAME} PUBLIC LinuxLibgpioIF.cpp ) +target_link_libraries(${TARGET_NAME} PUBLIC + gpiod +) + diff --git a/linux/gpio/GpioCookie.cpp b/linux/gpio/GpioCookie.cpp index f4e585d1..f957d070 100644 --- a/linux/gpio/GpioCookie.cpp +++ b/linux/gpio/GpioCookie.cpp @@ -1,25 +1,29 @@ #include "GpioCookie.h" -#include +#include GpioCookie::GpioCookie() { } -void GpioCookie::addGpio(gpioId_t gpioId, GpioConfig_t gpioConfig){ - gpioMapIter = gpioMap.find(gpioId); +ReturnValue_t GpioCookie::addGpio(gpioId_t gpioId, GpiodRegular& gpioConfig){ + auto gpioMapIter = gpioMap.find(gpioId); if(gpioMapIter == gpioMap.end()) { - std::pair status = gpioMap.emplace(gpioId, gpioConfig); - if (status.second == false) { - sif::error << "GpioCookie::addGpio: Failed to add GPIO " - << gpioId << "to GPIO map" << std::endl; + auto statusPair = gpioMap.emplace(gpioId, new GpiodRegular(gpioConfig)); + if (statusPair.second == false) { +#if FSFW_VERBOSE_LEVEL >= 1 + sif::error << "GpioCookie::addGpio: Failed to add GPIO " << gpioId << + "to GPIO map" << std::endl; +#endif + return HasReturnvaluesIF::RETURN_FAILED; } + return HasReturnvaluesIF::RETURN_OK; } - else { - sif::error << "GpioCookie::addGpio: GPIO already exists in GPIO map " - << std::endl; - } +#if FSFW_VERBOSE_LEVEL >= 1 + sif::error << "GpioCookie::addGpio: GPIO already exists in GPIO map " << std::endl; +#endif + return HasReturnvaluesIF::RETURN_FAILED; } -GpioMap GpioCookie::getGpioMap() const{ +GpioMap GpioCookie::getGpioMap() const { return gpioMap; } diff --git a/linux/gpio/GpioCookie.h b/linux/gpio/GpioCookie.h index 72011750..c7721a98 100644 --- a/linux/gpio/GpioCookie.h +++ b/linux/gpio/GpioCookie.h @@ -1,48 +1,10 @@ -#ifndef SAM9G20_COMIF_COOKIES_GPIO_COOKIE_H_ -#define SAM9G20_COMIF_COOKIES_GPIO_COOKIE_H_ +#ifndef LINUX_GPIO_GPIOCOOKIE_H_ +#define LINUX_GPIO_GPIOCOOKIE_H_ #include "GpioIF.h" +#include "gpioDefinitions.h" #include #include -#include -#include - -namespace gpio { -enum Direction { - IN = 0, - OUT = 1 -}; -} - -/** - * @brief Struct containing information about the GPIO to use. This is - * required by the libgpiod to access and drive a GPIO. - * @param chipname String of the chipname specifying the group which contains - * the GPIO to access. E.g. gpiochip0. To detect names of - * GPIO groups run gpiodetect on the linux command line. - * @param lineNum The offset of the GPIO within the GPIO group. - * @param consumer Name of the consumer. Simply a description of the GPIO configuration. - * @param direction Specifies whether the GPIO should be used as in- or output. - * @param initValue Defines the initial state of the GPIO when configured as output. Only required - * for output GPIOs. - * @param lineHandle The handle returned by gpiod_chip_get_line will be later written to this - * pointer. - */ -typedef struct GpioConfig { - GpioConfig(std::string chipname_, int lineNum_, std::string consumer_, - gpio::Direction direction_, int initValue_) : - chipname(chipname_), lineNum(lineNum_), consumer(consumer_), direction(direction_), - initValue(initValue_) { - } - std::string chipname; - int lineNum; - std::string consumer; - gpio::Direction direction; - int initValue; - struct gpiod_line* lineHandle = nullptr; -} GpioConfig_t; -using GpioMap = std::unordered_map; -using GpioMapIter = GpioMap::iterator; /** * @brief Cookie for the GpioIF. Allows the GpioIF to determine which @@ -61,16 +23,17 @@ public: virtual ~GpioCookie(); - void addGpio(gpioId_t gpioId, GpioConfig_t gpioConfig); + ReturnValue_t addGpio(gpioId_t gpioId, GpiodRegular& gpioConfig); /** * @brief Get map with registered GPIOs. */ GpioMap getGpioMap() const; private: - + /** + * Returns a copy of the internal GPIO map. + */ GpioMap gpioMap; - GpioMapIter gpioMapIter; }; -#endif +#endif /* LINUX_GPIO_GPIOCOOKIE_H_ */ diff --git a/linux/gpio/GpioIF.h b/linux/gpio/GpioIF.h index 4965c6f9..75feb3ce 100644 --- a/linux/gpio/GpioIF.h +++ b/linux/gpio/GpioIF.h @@ -1,33 +1,35 @@ -#ifndef BSP_Q7S_GPIO_GPIOIF_H_ -#define BSP_Q7S_GPIO_GPIOIF_H_ +#ifndef LINUX_GPIO_GPIOIF_H_ +#define LINUX_GPIO_GPIOIF_H_ +#include "gpioDefinitions.h" #include #include -typedef uint16_t gpioId_t; +class GpioCookie; /** * @brief This class defines the interface for objects requiring the control * over GPIOs. * @author J. Meier */ -class GpioIF : public HasReturnvaluesIF{ +class GpioIF : public HasReturnvaluesIF { public: virtual ~GpioIF() {}; /** - * @brief Called by the GPIO using object. + * @brief Called by the GPIO using object. * @param cookie Cookie specifying informations of the GPIOs required * by a object. */ - virtual ReturnValue_t initialize(CookieIF * cookie) = 0; + virtual ReturnValue_t addGpios(GpioCookie* cookie) = 0; /** * @brief By implementing this function a child must provide the * functionality to pull a certain GPIO to high logic level. * * @param gpioId A unique number which specifies the GPIO to drive. + * @return Returns RETURN_OK for success. This should never return RETURN_FAILED. */ virtual ReturnValue_t pullHigh(gpioId_t gpioId) = 0; @@ -49,4 +51,4 @@ public: virtual ReturnValue_t readGpio(gpioId_t gpioId, int* gpioState) = 0; }; -#endif /* BSP_Q7S_GPIO_GPIOIF_H_ */ +#endif /* LINUX_GPIO_GPIOIF_H_ */ diff --git a/linux/gpio/LinuxLibgpioIF.h b/linux/gpio/LinuxLibgpioIF.h index f91a35ca..a5015999 100644 --- a/linux/gpio/LinuxLibgpioIF.h +++ b/linux/gpio/LinuxLibgpioIF.h @@ -1,11 +1,12 @@ -#ifndef BSP_Q7S_GPIO_LINUXLIBGPIOIF_H_ -#define BSP_Q7S_GPIO_LINUXLIBGPIOIF_H_ +#ifndef LINUX_GPIO_LINUXLIBGPIOIF_H_ +#define LINUX_GPIO_LINUXLIBGPIOIF_H_ #include -#include #include #include +class GpioCookie; + /** * @brief This class implements the GpioIF for a linux based system. The * implementation is based on the libgpiod lib which requires linux 4.8 @@ -16,21 +17,27 @@ class LinuxLibgpioIF : public GpioIF, public SystemObject { public: - static const uint8_t INTERFACE_ID = CLASS_ID::LINUX_LIBGPIO_IF; + static const uint8_t gpioRetvalId = CLASS_ID::LINUX_LIBGPIO_IF; - static const ReturnValue_t DRIVE_GPIO_FAILURE = MAKE_RETURN_CODE(0x2); + static constexpr ReturnValue_t UNKNOWN_GPIO_ID = + HasReturnvaluesIF::makeReturnCode(gpioRetvalId, 1); + static constexpr ReturnValue_t DRIVE_GPIO_FAILURE = + HasReturnvaluesIF::makeReturnCode(gpioRetvalId, 2); + static constexpr ReturnValue_t GPIO_TYPE_FAILURE = + HasReturnvaluesIF::makeReturnCode(gpioRetvalId, 3); + static constexpr ReturnValue_t GPIO_INVALID_INSTANCE = + HasReturnvaluesIF::makeReturnCode(gpioRetvalId, 4); LinuxLibgpioIF(object_id_t objectId); virtual ~LinuxLibgpioIF(); - ReturnValue_t initialize(CookieIF * cookie) override; + ReturnValue_t addGpios(GpioCookie* gpioCookie) override; ReturnValue_t pullHigh(gpioId_t gpioId) override; ReturnValue_t pullLow(gpioId_t gpioId) override; ReturnValue_t readGpio(gpioId_t gpioId, int* gpioState) override; private: - - /*Holds the information and configuration of all used GPIOs */ + /* Holds the information and configuration of all used GPIOs */ GpioMap gpioMap; GpioMapIter gpioMapIter; @@ -40,8 +47,9 @@ private: * @param gpioId The GPIO ID of the GPIO to drive. * @param logiclevel The logic level to set. O or 1. */ - ReturnValue_t driveGpio(gpioId_t gpioId, - unsigned int logiclevel); + ReturnValue_t driveGpio(gpioId_t gpioId, GpiodRegular* regularGpio, unsigned int logiclevel); + + ReturnValue_t configureRegularGpio(gpioId_t gpioId, GpiodRegular* regularGpio); /** * @brief This function checks if GPIOs are already registered and whether @@ -52,12 +60,18 @@ private: * * @return RETURN_OK if successful, otherwise RETURN_FAILED */ - ReturnValue_t checkForConflicts(GpioMap mapToAdd); + ReturnValue_t checkForConflicts(GpioMap& mapToAdd); + + ReturnValue_t checkForConflictsRegularGpio(gpioId_t gpiodId, GpiodRegular* regularGpio, + GpioMap& mapToAdd); + ReturnValue_t checkForConflictsCallbackGpio(gpioId_t gpiodId, GpioCallback* regularGpio, + GpioMap& mapToAdd); /** * @brief Performs the initial configuration of all GPIOs specified in the GpioMap mapToAdd. */ - ReturnValue_t configureGpios(GpioMap* mapToAdd); + ReturnValue_t configureGpios(GpioMap& mapToAdd); + }; -#endif /* BSP_Q7S_GPIO_LINUXLIBGPIOIF_H_ */ +#endif /* LINUX_GPIO_LINUXLIBGPIOIF_H_ */ diff --git a/linux/gpio/gpioDefinitions.h b/linux/gpio/gpioDefinitions.h new file mode 100644 index 00000000..3b0f70fd --- /dev/null +++ b/linux/gpio/gpioDefinitions.h @@ -0,0 +1,92 @@ +#ifndef LINUX_GPIO_GPIODEFINITIONS_H_ +#define LINUX_GPIO_GPIODEFINITIONS_H_ + +#include +#include + +using gpioId_t = uint16_t; + +namespace gpio { +enum Direction { + IN = 0, + OUT = 1 +}; + +enum GpioOperation { + READ, + WRITE +}; + +enum GpioTypes { + NONE, + GPIOD_REGULAR, + CALLBACK +}; + +static constexpr gpioId_t NO_GPIO = -1; +} + +/** + * @brief Struct containing information about the GPIO to use. This is + * required by the libgpiod to access and drive a GPIO. + * @param chipname String of the chipname specifying the group which contains the GPIO to + * access. E.g. gpiochip0. To detect names of GPIO groups run gpiodetect on + * the linux command line. + * @param lineNum The offset of the GPIO within the GPIO group. + * @param consumer Name of the consumer. Simply a description of the GPIO configuration. + * @param direction Specifies whether the GPIO should be used as in- or output. + * @param initValue Defines the initial state of the GPIO when configured as output. + * Only required for output GPIOs. + * @param lineHandle The handle returned by gpiod_chip_get_line will be later written to this + * pointer. + */ +class GpioBase { +public: + + GpioBase() = default; + + GpioBase(gpio::GpioTypes gpioType, std::string consumer, gpio::Direction direction, + int initValue): + gpioType(gpioType), consumer(consumer),direction(direction), initValue(initValue) {} + + virtual~ GpioBase() {}; + + /* Can be used to cast GpioBase to a concrete child implementation */ + gpio::GpioTypes gpioType = gpio::GpioTypes::NONE; + std::string consumer; + gpio::Direction direction = gpio::Direction::IN; + int initValue = 0; +}; + +class GpiodRegular: public GpioBase { +public: + GpiodRegular(): GpioBase(gpio::GpioTypes::GPIOD_REGULAR, std::string(), + gpio::Direction::IN, 0) {}; + + GpiodRegular(std::string chipname_, int lineNum_, std::string consumer_, + gpio::Direction direction_, int initValue_): + GpioBase(gpio::GpioTypes::GPIOD_REGULAR, consumer_, direction_, initValue_), + chipname(chipname_), lineNum(lineNum_) {} + std::string chipname; + int lineNum = 0; + struct gpiod_line* lineHandle = nullptr; +}; + +class GpioCallback: public GpioBase { +public: + GpioCallback(std::string consumer, gpio::Direction direction_, int initValue_, + void (* callback) (gpioId_t gpioId, gpio::GpioOperation gpioOp, int value, void* args), + void* callbackArgs): + GpioBase(gpio::GpioTypes::CALLBACK, consumer, direction_, initValue_), + callback(callback), callbackArgs(callbackArgs) {} + + void (* callback) (gpioId_t gpioId, gpio::GpioOperation gpioOp, + int value, void* args) = nullptr; + void* callbackArgs = nullptr; +}; + + +using GpioMap = std::unordered_map; +using GpioMapIter = GpioMap::iterator; + +#endif /* LINUX_GPIO_GPIODEFINITIONS_H_ */ diff --git a/linux/i2c/I2cComIF.h b/linux/i2c/I2cComIF.h index 5e75a280..3529bde7 100644 --- a/linux/i2c/I2cComIF.h +++ b/linux/i2c/I2cComIF.h @@ -1,5 +1,5 @@ -#ifndef BSP_Q7S_COMIF_I2COMIF_H_ -#define BSP_Q7S_COMIF_I2COMIF_H_ +#ifndef LINUX_I2C_I2COMIF_H_ +#define LINUX_I2C_I2COMIF_H_ #include "I2cCookie.h" #include @@ -45,8 +45,8 @@ private: I2cDeviceMapIter i2cDeviceMapIter; /** - * @brief This function opens an i2c device and binds the opened file - * to a specific i2c address. + * @brief This function opens an I2C device and binds the opened file + * to a specific I2C address. * @param deviceFile The name of the device file. E.g. i2c-0 * @param i2cAddress The address of the i2c slave device. * @param fileDescriptor Pointer to device descriptor. @@ -56,4 +56,4 @@ private: address_t i2cAddress, int* fileDescriptor); }; -#endif /* BSP_Q7S_COMIF_I2COMIF_H_ */ +#endif /* LINUX_I2C_I2COMIF_H_ */ diff --git a/linux/i2c/I2cCookie.cpp b/linux/i2c/I2cCookie.cpp index 7f86bdc3..fe0f3f92 100644 --- a/linux/i2c/I2cCookie.cpp +++ b/linux/i2c/I2cCookie.cpp @@ -2,8 +2,7 @@ I2cCookie::I2cCookie(address_t i2cAddress_, size_t maxReplyLen_, std::string deviceFile_) : - i2cAddress(i2cAddress_), maxReplyLen(maxReplyLen_), deviceFile( - deviceFile_) { + i2cAddress(i2cAddress_), maxReplyLen(maxReplyLen_), deviceFile(deviceFile_) { } address_t I2cCookie::getAddress() const { diff --git a/linux/spi/CMakeLists.txt b/linux/spi/CMakeLists.txt index 45a7edcc..cb1c9277 100644 --- a/linux/spi/CMakeLists.txt +++ b/linux/spi/CMakeLists.txt @@ -1,4 +1,6 @@ target_sources(${TARGET_NAME} PUBLIC + SpiComIF.cpp + SpiCookie.cpp ) diff --git a/linux/spi/SpiComIF.cpp b/linux/spi/SpiComIF.cpp new file mode 100644 index 00000000..eef44126 --- /dev/null +++ b/linux/spi/SpiComIF.cpp @@ -0,0 +1,308 @@ +#include "SpiComIF.h" + +#include +#include + +#include +#include +#include + +#include +#include +#include +#include + +#include +#include + +SpiComIF::SpiComIF(object_id_t objectId, GpioIF* gpioComIF): SystemObject(objectId), + gpioComIF(gpioComIF) { + if(gpioComIF == nullptr) { +#if FSFW_VERBOSE_LEVEL >= 1 +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::error << "SpiComIF::SpiComIF: GPIO communication interface invalid!" << std::endl; +#else + sif::printError("SpiComIF::SpiComIF: GPIO communication interface invalid!\n"); +#endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ +#endif /* FSFW_VERBOSE_LEVEL >= 1 */ + } + + spiMutex = MutexFactory::instance()->createMutex(); +} + +ReturnValue_t SpiComIF::initializeInterface(CookieIF *cookie) { + int retval = 0; + SpiCookie* spiCookie = dynamic_cast(cookie); + if(spiCookie == nullptr) { + return NULLPOINTER; + } + + address_t spiAddress = spiCookie->getSpiAddress(); + + auto iter = spiDeviceMap.find(spiAddress); + if(iter == spiDeviceMap.end()) { + size_t bufferSize = spiCookie->getMaxBufferSize(); + SpiInstance spiInstance = {std::vector(bufferSize)}; + auto statusPair = spiDeviceMap.emplace(spiAddress, spiInstance); + if (not statusPair.second) { +#if FSFW_VERBOSE_LEVEL >= 1 +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::error << "SpiComIF::initializeInterface: Failed to insert device with address " << + spiAddress << "to SPI device map" << std::endl; +#else + sif::printError("SpiComIF::initializeInterface: Failed to insert device with address " + "%lu to SPI device map\n", static_cast(spiAddress)); +#endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ +#endif /* FSFW_VERBOSE_LEVEL >= 1 */ + return HasReturnvaluesIF::RETURN_FAILED; + } + /* Now we emplaced the read buffer in the map, we still need to assign that location + to the SPI driver transfer struct */ + spiCookie->assignReadBuffer(statusPair.first->second.replyBuffer.data()); + } + else { +#if FSFW_VERBOSE_LEVEL >= 1 +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::error << "SpiComIF::initializeInterface: SPI address already exists!" << std::endl; +#else + sif::printError("SpiComIF::initializeInterface: SPI address already exists!\n"); +#endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ +#endif /* FSFW_VERBOSE_LEVEL >= 1 */ + return HasReturnvaluesIF::RETURN_FAILED; + } + + /* Pull CS high in any case to be sure that device is inactive */ + gpioId_t gpioId = spiCookie->getChipSelectPin(); + if(gpioId != gpio::NO_GPIO) { + gpioComIF->pullHigh(gpioId); + } + + size_t spiSpeed = 0; + spi::SpiMode spiMode = spi::SpiMode::MODE_0; + + SpiCookie::UncommonParameters params; + spiCookie->getSpiParameters(spiMode, spiSpeed, ¶ms); + + int fileDescriptor = 0; + utility::UnixFileHelper fileHelper(spiCookie->getSpiDevice(), &fileDescriptor, O_RDWR, + "SpiComIF::initializeInterface: "); + if(fileHelper.getOpenResult() != HasReturnvaluesIF::RETURN_OK) { + return fileHelper.getOpenResult(); + } + + /* These flags are rather uncommon */ + if(params.threeWireSpi or params.noCs or params.csHigh) { + uint32_t currentMode = 0; + retval = ioctl(fileDescriptor, SPI_IOC_RD_MODE32, ¤tMode); + if(retval != 0) { + utility::handleIoctlError("SpiComIF::initialiezInterface: Could not read full mode!"); + } + + if(params.threeWireSpi) { + currentMode |= SPI_3WIRE; + } + if(params.noCs) { + /* Some drivers like the Raspberry Pi ignore this flag in any case */ + currentMode |= SPI_NO_CS; + } + if(params.csHigh) { + currentMode |= SPI_CS_HIGH; + } + /* Write adapted mode */ + retval = ioctl(fileDescriptor, SPI_IOC_WR_MODE32, ¤tMode); + if(retval != 0) { + utility::handleIoctlError("SpiComIF::initialiezInterface: Could not write full mode!"); + } + } + if(params.lsbFirst) { + retval = ioctl(fileDescriptor, SPI_IOC_WR_LSB_FIRST, ¶ms.lsbFirst); + if(retval != 0) { + utility::handleIoctlError("SpiComIF::initializeInterface: Setting LSB first failed"); + } + } + if(params.bitsPerWord != 8) { + retval = ioctl(fileDescriptor, SPI_IOC_WR_BITS_PER_WORD, ¶ms.bitsPerWord); + if(retval != 0) { + utility::handleIoctlError("SpiComIF::initializeInterface: " + "Could not write bits per word!"); + } + } + return HasReturnvaluesIF::RETURN_OK; +} + +ReturnValue_t SpiComIF::sendMessage(CookieIF *cookie, const uint8_t *sendData, size_t sendLen) { + SpiCookie* spiCookie = dynamic_cast(cookie); + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + int retval = 0; + + if(spiCookie == nullptr) { + return NULLPOINTER; + } + + if(sendLen > spiCookie->getMaxBufferSize()) { +#if FSFW_VERBOSE_LEVEL >= 1 +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::warning << "SpiComIF::sendMessage: Too much data sent, send length" << sendLen << + "larger than maximum buffer length" << spiCookie->getMaxBufferSize() << std::endl; +#else + sif::printWarning("SpiComIF::sendMessage: Too much data sent, send length %lu larger " + "than maximum buffer length %lu!\n", static_cast(sendLen), + static_cast(spiCookie->getMaxBufferSize())); +#endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ +#endif /* FSFW_VERBOSE_LEVEL >= 1 */ + return DeviceCommunicationIF::TOO_MUCH_DATA; + } + + + /* Prepare transfer */ + int fileDescriptor = 0; + std::string device = spiCookie->getSpiDevice(); + utility::UnixFileHelper fileHelper(device, &fileDescriptor, O_RDWR, + "SpiComIF::sendMessage: "); + if(fileHelper.getOpenResult() != HasReturnvaluesIF::RETURN_OK) { + return OPENING_FILE_FAILED; + } + spi::SpiMode spiMode = spi::SpiMode::MODE_0; + uint32_t spiSpeed = 0; + spiCookie->getSpiParameters(spiMode, spiSpeed, nullptr); + setSpiSpeedAndMode(fileDescriptor, spiMode, spiSpeed); + spiCookie->assignWriteBuffer(sendData); + spiCookie->assignTransferSize(sendLen); + + bool fullDuplex = spiCookie->isFullDuplex(); + gpioId_t gpioId = spiCookie->getChipSelectPin(); + + /* GPIO access is mutex protected */ + MutexHelper(spiMutex, timeoutType, timeoutMs); + + /* Pull SPI CS low. For now, no support for active high given */ + if(gpioId != gpio::NO_GPIO) { + gpioComIF->pullLow(gpioId); + } + + /* Execute transfer */ + if(fullDuplex) { + /* Initiate a full duplex SPI transfer. */ + retval = ioctl(fileDescriptor, SPI_IOC_MESSAGE(1), spiCookie->getTransferStructHandle()); + if(retval < 0) { + utility::handleIoctlError("SpiComIF::sendMessage: ioctl error."); + result = FULL_DUPLEX_TRANSFER_FAILED; + } + } + else { + /* We write with a blocking half-duplex transfer here */ + if (write(fileDescriptor, sendData, sendLen) != static_cast(sendLen)) { +#if FSFW_VERBOSE_LEVEL >= 1 +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::warning << "SpiComIF::sendMessage: Half-Duplex write operation failed!" << + std::endl; +#else + sif::printWarning("SpiComIF::sendMessage: Half-Duplex write operation failed!\n"); +#endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ +#endif /* FSFW_VERBOSE_LEVEL >= 1 */ + result = HALF_DUPLEX_TRANSFER_FAILED; + } + } + + if(gpioId != gpio::NO_GPIO) { + gpioComIF->pullHigh(gpioId); + } + return result; +} + +ReturnValue_t SpiComIF::getSendSuccess(CookieIF *cookie) { + return HasReturnvaluesIF::RETURN_OK; +} + +ReturnValue_t SpiComIF::requestReceiveMessage(CookieIF *cookie, size_t requestLen) { + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + SpiCookie* spiCookie = dynamic_cast(cookie); + if(spiCookie == nullptr) { + return NULLPOINTER; + } + + bool fullDuplex = spiCookie->isFullDuplex(); + if(fullDuplex) { + return HasReturnvaluesIF::RETURN_OK; + } + + std::string device = spiCookie->getSpiDevice(); + int fileDescriptor = 0; + utility::UnixFileHelper fileHelper(device, &fileDescriptor, O_RDWR, + "SpiComIF::requestReceiveMessage: "); + if(fileHelper.getOpenResult() != HasReturnvaluesIF::RETURN_OK) { + return OPENING_FILE_FAILED; + } + + uint8_t* rxBuf = nullptr; + size_t readSize = spiCookie->getCurrentTransferSize(); + result = getReadBuffer(spiCookie->getSpiAddress(), &rxBuf); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + + gpioId_t gpioId = spiCookie->getChipSelectPin(); + MutexHelper(spiMutex, timeoutType, timeoutMs); + if(gpioId != gpio::NO_GPIO) { + gpioComIF->pullLow(gpioId); + } + + if(read(fileDescriptor, rxBuf, readSize) != static_cast(readSize)) { +#if FSFW_VERBOSE_LEVEL >= 1 +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::warning << "SpiComIF::sendMessage: Half-Duplex read operation failed!" << std::endl; +#else + sif::printWarning("SpiComIF::sendMessage: Half-Duplex read operation failed!\n"); +#endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ +#endif /* FSFW_VERBOSE_LEVEL >= 1 */ + result = HALF_DUPLEX_TRANSFER_FAILED; + } + + if(gpioId != gpio::NO_GPIO) { + gpioComIF->pullHigh(gpioId); + } + + return HasReturnvaluesIF::RETURN_OK; +} + +ReturnValue_t SpiComIF::readReceivedMessage(CookieIF *cookie, uint8_t **buffer, size_t *size) { + SpiCookie* spiCookie = dynamic_cast(cookie); + if(spiCookie == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } + uint8_t* rxBuf = nullptr; + ReturnValue_t result = getReadBuffer(spiCookie->getSpiAddress(), &rxBuf); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + + *buffer = rxBuf; + *size = spiCookie->getCurrentTransferSize(); + return HasReturnvaluesIF::RETURN_OK; +} + +ReturnValue_t SpiComIF::getReadBuffer(address_t spiAddress, uint8_t** buffer) { + if(buffer == nullptr) { + return HasReturnvaluesIF::RETURN_FAILED; + } + + auto iter = spiDeviceMap.find(spiAddress); + if(iter == spiDeviceMap.end()) { + return HasReturnvaluesIF::RETURN_FAILED; + } + + *buffer = iter->second.replyBuffer.data(); + return HasReturnvaluesIF::RETURN_OK; +} + +void SpiComIF::setSpiSpeedAndMode(int spiFd, spi::SpiMode mode, uint32_t speed) { + int retval = ioctl(spiFd, SPI_IOC_WR_MODE, reinterpret_cast(&mode)); + if(retval != 0) { + utility::handleIoctlError("SpiTestClass::performRm3100Test: Setting SPI mode failed!"); + } + + retval = ioctl(spiFd, SPI_IOC_WR_MAX_SPEED_HZ, &speed); + if(retval != 0) { + utility::handleIoctlError("SpiTestClass::performRm3100Test: Setting SPI speed failed!"); + } +} diff --git a/linux/spi/SpiComIF.h b/linux/spi/SpiComIF.h new file mode 100644 index 00000000..cbcaa4e0 --- /dev/null +++ b/linux/spi/SpiComIF.h @@ -0,0 +1,63 @@ +#ifndef LINUX_SPI_SPICOMIF_H_ +#define LINUX_SPI_SPICOMIF_H_ + +#include +#include +#include +#include +#include + +#include +#include + +/** + * @brief Encapsulates access to linux SPI driver for FSFW objects + * @details + * Right now, only full-duplex SPI is supported. + * @author R. Mueller + */ +class SpiComIF: public DeviceCommunicationIF, public SystemObject { +public: + static constexpr uint8_t spiRetvalId = CLASS_ID::LINUX_SPI_COM_IF; + static constexpr ReturnValue_t OPENING_FILE_FAILED = + HasReturnvaluesIF::makeReturnCode(spiRetvalId, 0); + /* Full duplex (ioctl) transfer failure */ + static constexpr ReturnValue_t FULL_DUPLEX_TRANSFER_FAILED = + HasReturnvaluesIF::makeReturnCode(spiRetvalId, 1); + /* Half duplex (read/write) transfer failure */ + static constexpr ReturnValue_t HALF_DUPLEX_TRANSFER_FAILED = + HasReturnvaluesIF::makeReturnCode(spiRetvalId, 2); + + SpiComIF(object_id_t objectId, GpioIF* gpioComIF); + + ReturnValue_t initializeInterface(CookieIF * cookie) override; + ReturnValue_t sendMessage(CookieIF *cookie,const uint8_t *sendData, + size_t sendLen) override; + ReturnValue_t getSendSuccess(CookieIF *cookie) override; + ReturnValue_t requestReceiveMessage(CookieIF *cookie, + size_t requestLen) override; + ReturnValue_t readReceivedMessage(CookieIF *cookie, uint8_t **buffer, + size_t *size) override; +private: + + struct SpiInstance { + std::vector replyBuffer; + }; + + GpioIF* gpioComIF = nullptr; + + MutexIF* spiMutex = nullptr; + MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING; + uint32_t timeoutMs = 20; + + using SpiDeviceMap = std::unordered_map; + using SpiDeviceMapIter = SpiDeviceMap::iterator; + + SpiDeviceMap spiDeviceMap; + + + ReturnValue_t getReadBuffer(address_t spiAddress, uint8_t** buffer); + void setSpiSpeedAndMode(int spiFd, spi::SpiMode mode, uint32_t speed); +}; + +#endif /* LINUX_SPI_SPICOMIF_H_ */ diff --git a/linux/spi/SpiCookie.cpp b/linux/spi/SpiCookie.cpp new file mode 100644 index 00000000..f0b81f67 --- /dev/null +++ b/linux/spi/SpiCookie.cpp @@ -0,0 +1,99 @@ +#include "SpiCookie.h" + +SpiCookie::SpiCookie(address_t spiAddress, gpioId_t chipSelect, std::string spiDev, + const size_t maxSize, spi::SpiMode spiMode, uint32_t spiSpeed): spiAddress(spiAddress), + chipSelectPin(chipSelect), spiDevice(spiDev), maxSize(maxSize), spiMode(spiMode), + spiSpeed(spiSpeed) { +} + +SpiCookie::SpiCookie(address_t spiAddress, std::string spiDev, const size_t maxSize, + spi::SpiMode spiMode, uint32_t spiSpeed): + SpiCookie(spiAddress, gpio::NO_GPIO, spiDev, maxSize, spiMode, spiSpeed) { +} + +void SpiCookie::getSpiParameters(spi::SpiMode& spiMode, uint32_t& spiSpeed, + UncommonParameters* parameters) const { + spiMode = this->spiMode; + spiSpeed = this->spiSpeed; + + if(parameters != nullptr) { + parameters->threeWireSpi = uncommonParameters.threeWireSpi; + parameters->lsbFirst = uncommonParameters.lsbFirst; + parameters->noCs = uncommonParameters.noCs; + parameters->bitsPerWord = uncommonParameters.bitsPerWord; + parameters->csHigh = uncommonParameters.csHigh; + } +} + +gpioId_t SpiCookie::getChipSelectPin() const { + return chipSelectPin; +} + +size_t SpiCookie::getMaxBufferSize() const { + return maxSize; +} + +address_t SpiCookie::getSpiAddress() const { + return spiAddress; +} + +std::string SpiCookie::getSpiDevice() const { + return spiDevice; +} + +void SpiCookie::setThreeWireSpi(bool enable) { + uncommonParameters.threeWireSpi = enable; +} + +void SpiCookie::setLsbFirst(bool enable) { + uncommonParameters.lsbFirst = enable; +} + +void SpiCookie::setNoCs(bool enable) { + uncommonParameters.noCs = enable; +} + +void SpiCookie::setBitsPerWord(uint8_t bitsPerWord) { + uncommonParameters.bitsPerWord = bitsPerWord; +} + +void SpiCookie::setCsHigh(bool enable) { + uncommonParameters.csHigh = enable; +} + +void SpiCookie::activateCsDeselect(bool deselectCs, uint16_t delayUsecs) { + spiTransferStruct.cs_change = deselectCs; + spiTransferStruct.delay_usecs = delayUsecs; +} + +void SpiCookie::assignReadBuffer(uint8_t* rx) { + if(rx != nullptr) { + spiTransferStruct.rx_buf = reinterpret_cast<__u64>(rx); + } +} + +void SpiCookie::assignWriteBuffer(const uint8_t* tx) { + if(tx != nullptr) { + spiTransferStruct.tx_buf = reinterpret_cast<__u64>(tx); + } +} + +spi_ioc_transfer* SpiCookie::getTransferStructHandle() { + return &spiTransferStruct; +} + +void SpiCookie::setFullOrHalfDuplex(bool halfDuplex) { + this->halfDuplex = halfDuplex; +} + +bool SpiCookie::isFullDuplex() const { + return not this->halfDuplex; +} + +void SpiCookie::assignTransferSize(size_t transferSize) { + spiTransferStruct.len = transferSize; +} + +size_t SpiCookie::getCurrentTransferSize() const { + return spiTransferStruct.len; +} diff --git a/linux/spi/SpiCookie.h b/linux/spi/SpiCookie.h new file mode 100644 index 00000000..42004993 --- /dev/null +++ b/linux/spi/SpiCookie.h @@ -0,0 +1,113 @@ +#ifndef LINUX_SPI_SPICOOKIE_H_ +#define LINUX_SPI_SPICOOKIE_H_ + +#include "spiDefinitions.h" +#include +#include +#include + +class SpiCookie: public CookieIF { +public: + + /** + * Each SPI device will have a corresponding cookie. The cookie is used by the communication + * interface and contains device specific information like the largest expected size to be + * sent and received and the GPIO pin used to toggle the SPI slave select pin. + * @param spiAddress + * @param chipSelect Chip select. gpio::NO_GPIO can be used for hardware slave selects. + * @param spiDev + * @param maxSize + */ + SpiCookie(address_t spiAddress, gpioId_t chipSelect, std::string spiDev, + const size_t maxReplySize, spi::SpiMode spiMode, uint32_t spiSpeed); + + /** + * Like constructor above, but without a dedicated GPIO CS. Can be used for hardware + * slave select or if CS logic is performed with decoders. + */ + SpiCookie(address_t spiAddress, std::string spiDev, const size_t maxReplySize, + spi::SpiMode spiMode, uint32_t spiSpeed); + + address_t getSpiAddress() const; + std::string getSpiDevice() const; + gpioId_t getChipSelectPin() const; + size_t getMaxBufferSize() const; + /** + * True if SPI transfers should be performed in full duplex mode + * @return + */ + bool isFullDuplex() const; + + /** + * Set transfer type to full duplex or half duplex. Full duplex is the default setting, + * ressembling common SPI hardware implementation with shift registers, where read and writes + * happen simultaneosly. + * @param fullDuplex + */ + void setFullOrHalfDuplex(bool halfDuplex); + + /** + * This needs to be called to specify where the SPI driver writes to or reads from. + * @param readLocation + * @param writeLocation + */ + void assignReadBuffer(uint8_t* rx); + void assignWriteBuffer(const uint8_t* tx); + /** + * Assign size for the next transfer. + * @param transferSize + */ + void assignTransferSize(size_t transferSize); + size_t getCurrentTransferSize() const; + + struct UncommonParameters { + uint8_t bitsPerWord = 8; + bool noCs = false; + bool csHigh = false; + bool threeWireSpi = false; + /* MSB first is more common */ + bool lsbFirst = false; + }; + + /** + * Can be used to explicitely disable hardware chip select. + * Some drivers like the Raspberry Pi Linux driver will not use hardware chip select by default + * (see https://www.raspberrypi.org/documentation/hardware/raspberrypi/spi/README.md) + * @param enable + */ + void setNoCs(bool enable); + void setThreeWireSpi(bool enable); + void setLsbFirst(bool enable); + void setCsHigh(bool enable); + void setBitsPerWord(uint8_t bitsPerWord); + + void getSpiParameters(spi::SpiMode& spiMode, uint32_t& spiSpeed, + UncommonParameters* parameters = nullptr) const; + + /** + * See spidev.h cs_change and delay_usecs + * @param deselectCs + * @param delayUsecs + */ + void activateCsDeselect(bool deselectCs, uint16_t delayUsecs); + + spi_ioc_transfer* getTransferStructHandle(); +private: + size_t currentTransferSize = 0; + + address_t spiAddress; + gpioId_t chipSelectPin; + std::string spiDevice; + + const size_t maxSize; + spi::SpiMode spiMode; + uint32_t spiSpeed; + bool halfDuplex = false; + + struct spi_ioc_transfer spiTransferStruct = {}; + UncommonParameters uncommonParameters; +}; + + + +#endif /* LINUX_SPI_SPICOOKIE_H_ */ diff --git a/linux/spi/spiDefinitions.h b/linux/spi/spiDefinitions.h new file mode 100644 index 00000000..9c278a70 --- /dev/null +++ b/linux/spi/spiDefinitions.h @@ -0,0 +1,15 @@ +#ifndef LINUX_SPI_SPIDEFINITONS_H_ +#define LINUX_SPI_SPIDEFINITONS_H_ + +namespace spi { + +enum SpiMode { + MODE_0, + MODE_1, + MODE_2, + MODE_3 +}; + +} + +#endif /* LINUX_SPI_SPIDEFINITONS_H_ */ diff --git a/linux/utility/CMakeLists.txt b/linux/utility/CMakeLists.txt new file mode 100644 index 00000000..71151b6c --- /dev/null +++ b/linux/utility/CMakeLists.txt @@ -0,0 +1,7 @@ +target_sources(${TARGET_NAME} PUBLIC + Utility.cpp +) + + + + diff --git a/linux/utility/Utility.cpp b/linux/utility/Utility.cpp new file mode 100644 index 00000000..45c347db --- /dev/null +++ b/linux/utility/Utility.cpp @@ -0,0 +1,52 @@ +#include "Utility.h" + +void utility::handleIoctlError(const char* const customPrintout) { +#if FSFW_VERBOSE_LEVEL >= 1 +#if FSFW_CPP_OSTREAM_ENABLED == 1 + if(customPrintout != nullptr) { + sif::warning << customPrintout << std::endl; + } + sif::warning << "handleIoctlError: Error code " << errno << ", "<< strerror(errno) << + std::endl; +#else + if(customPrintout != nullptr) { + sif::printWarning("%s\n", customPrintout); + } + sif::printWarning("handleIoctlError: Error code %d, %s\n", errno, strerror(errno)); +#endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ +#endif /* FSFW_VERBOSE_LEVEL >= 1 */ + +} + +utility::UnixFileHelper::UnixFileHelper(std::string device, int* fileDescriptor, int flags, + std::string diagnosticPrefix): + fileDescriptor(fileDescriptor) { + if(fileDescriptor == nullptr) { + return; + } + *fileDescriptor = open(device.c_str(), flags); + if (*fileDescriptor < 0) { +#if FSFW_VERBOSE_LEVEL >= 1 +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::warning << diagnosticPrefix <<"Opening device failed with error code " << errno << + "." << std::endl; + sif::warning << "Error description: " << strerror(errno) << std::endl; +#else + sif::printError("%sOpening device failed with error code %d.\n", diagnosticPrefix); + sif::printWarning("Error description: %s\n", strerror(errno)); +#endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ +#endif /* FSFW_VERBOSE_LEVEL >= 1 */ + openStatus = OPEN_FILE_FAILED; + } +} + +utility::UnixFileHelper::~UnixFileHelper() { + if(fileDescriptor != nullptr) { + close(*fileDescriptor); + } +} + +ReturnValue_t utility::UnixFileHelper::getOpenResult() const { + return openStatus; +} + diff --git a/linux/utility/Utility.h b/linux/utility/Utility.h new file mode 100644 index 00000000..a93b4936 --- /dev/null +++ b/linux/utility/Utility.h @@ -0,0 +1,36 @@ +#ifndef LINUX_UTILITY_UTILITY_H_ +#define LINUX_UTILITY_UTILITY_H_ + +#include +#include +#include + +#include +#include + +namespace utility { + +void handleIoctlError(const char* const customPrintout); + +class UnixFileHelper { +public: + static constexpr int READ_WRITE_FLAG = O_RDWR; + static constexpr int READ_ONLY_FLAG = O_RDONLY; + static constexpr int NON_BLOCKING_IO_FLAG = O_NONBLOCK; + + static constexpr ReturnValue_t OPEN_FILE_FAILED = 1; + + UnixFileHelper(std::string device, int* fileDescriptor, int flags, + std::string diagnosticPrefix = ""); + + virtual~ UnixFileHelper(); + + ReturnValue_t getOpenResult() const; +private: + int* fileDescriptor = nullptr; + ReturnValue_t openStatus = HasReturnvaluesIF::RETURN_OK; +}; + +} + +#endif /* LINUX_UTILITY_UTILITY_H_ */ diff --git a/bsp_rpi/boardtest/RPiGPIO.cpp b/misc/archive/RPiGPIO.cpp similarity index 100% rename from bsp_rpi/boardtest/RPiGPIO.cpp rename to misc/archive/RPiGPIO.cpp diff --git a/bsp_rpi/boardtest/RPiGPIO.h b/misc/archive/RPiGPIO.h similarity index 100% rename from bsp_rpi/boardtest/RPiGPIO.h rename to misc/archive/RPiGPIO.h diff --git a/misc/eclipse/Host/eive-mingw-debug-cmake.launch b/misc/eclipse/Host/eive-mingw-debug-cmake.launch index 3552a26b..d31b97e9 100644 --- a/misc/eclipse/Host/eive-mingw-debug-cmake.launch +++ b/misc/eclipse/Host/eive-mingw-debug-cmake.launch @@ -4,7 +4,7 @@ - + @@ -18,7 +18,7 @@ - + diff --git a/mission/core/GenericFactory.cpp b/mission/core/GenericFactory.cpp index 2a254cf0..2fcb4450 100644 --- a/mission/core/GenericFactory.cpp +++ b/mission/core/GenericFactory.cpp @@ -11,6 +11,7 @@ #include #include #include +#include #include #include #include @@ -78,11 +79,13 @@ void ObjectFactory::produceGenericObjects() { apid::EIVE_OBSW, pus::PUS_SERVICE_9); new Service17Test(objects::PUS_SERVICE_17_TEST, apid::EIVE_OBSW, pus::PUS_SERVICE_17); + new Service20ParameterManagement(objects::PUS_SERVICE_20_PARAMETERS, apid::EIVE_OBSW, + pus::PUS_SERVICE_20); new CService200ModeCommanding(objects::PUS_SERVICE_200_MODE_MGMT, apid::EIVE_OBSW, pus::PUS_SERVICE_200); /* Test Device Handler */ #if OBSW_ADD_TEST_CODE == 1 - new TestTask(objects::TEST_TASK); + new TestTask(objects::TEST_TASK); #endif } diff --git a/mission/devices/MGMHandlerLIS3MDL.cpp b/mission/devices/MGMHandlerLIS3MDL.cpp index fad96f66..6eb7f5d4 100644 --- a/mission/devices/MGMHandlerLIS3MDL.cpp +++ b/mission/devices/MGMHandlerLIS3MDL.cpp @@ -1,19 +1,20 @@ +#include #include "MGMHandlerLIS3MDL.h" MGMHandlerLIS3MDL::MGMHandlerLIS3MDL(object_id_t objectId, - object_id_t deviceCommunication, CookieIF* comCookie): - DeviceHandlerBase(objectId, deviceCommunication, comCookie), - dataset(this) { + object_id_t deviceCommunication, CookieIF* comCookie): + DeviceHandlerBase(objectId, deviceCommunication, comCookie), + dataset(this) { #if OBSW_VERBOSE_LEVEL >= 1 - debugDivider = new PeriodicOperationDivider(10); + debugDivider = new PeriodicOperationDivider(10); #endif - // Set to default values right away. - registers[0] = MGMLIS3MDL::CTRL_REG1_DEFAULT; - registers[1] = MGMLIS3MDL::CTRL_REG2_DEFAULT; - registers[2] = MGMLIS3MDL::CTRL_REG3_DEFAULT; - registers[3] = MGMLIS3MDL::CTRL_REG4_DEFAULT; - registers[4] = MGMLIS3MDL::CTRL_REG5_DEFAULT; + /* Set to default values right away. */ + registers[0] = MGMLIS3MDL::CTRL_REG1_DEFAULT; + registers[1] = MGMLIS3MDL::CTRL_REG2_DEFAULT; + registers[2] = MGMLIS3MDL::CTRL_REG3_DEFAULT; + registers[3] = MGMLIS3MDL::CTRL_REG4_DEFAULT; + registers[4] = MGMLIS3MDL::CTRL_REG5_DEFAULT; } @@ -22,392 +23,435 @@ MGMHandlerLIS3MDL::~MGMHandlerLIS3MDL() { void MGMHandlerLIS3MDL::doStartUp() { - switch (internalState) { - case(InternalState::STATE_NONE): - internalState = InternalState::STATE_FIRST_CONTACT; - break; - - case(InternalState::STATE_FIRST_CONTACT): - internalState = InternalState::STATE_SETUP; - break; - - case(InternalState::STATE_SETUP): - internalState = InternalState::STATE_CHECK_REGISTERS; - break; - - case(InternalState::STATE_CHECK_REGISTERS): { - // Set up cached registers which will be used to configure the MGM. - if(commandExecuted) { - commandExecuted = false; - setMode(_MODE_TO_ON); - } - break; - } - default: - break; - } + switch (internalState) { + case(InternalState::STATE_NONE): { + internalState = InternalState::STATE_FIRST_CONTACT; + break; + } + case(InternalState::STATE_FIRST_CONTACT): { + /* Will be set by checking device ID (WHO AM I register) */ + if(commandExecuted) { + commandExecuted = false; + } + internalState = InternalState::STATE_SETUP; + break; + } + case(InternalState::STATE_SETUP): { + internalState = InternalState::STATE_CHECK_REGISTERS; + break; + } + case(InternalState::STATE_CHECK_REGISTERS): { + /* Set up cached registers which will be used to configure the MGM. */ + if(commandExecuted) { + commandExecuted = false; + /* Replace _MODE_TO_ON with MODE_NORMAL to jump to normal mode quickly */ + setMode(_MODE_TO_ON); + } + break; + } + default: + break; + } } void MGMHandlerLIS3MDL::doShutDown() { - setMode(_MODE_POWER_DOWN); + setMode(_MODE_POWER_DOWN); } ReturnValue_t MGMHandlerLIS3MDL::buildTransitionDeviceCommand( - DeviceCommandId_t *id) { - switch (internalState) { - case(InternalState::STATE_NONE): - case(InternalState::STATE_NORMAL): { - return HasReturnvaluesIF::RETURN_OK; - } - case(InternalState::STATE_FIRST_CONTACT): { - *id = MGMLIS3MDL::IDENTIFY_DEVICE; - break; - } - case(InternalState::STATE_SETUP): { - *id = MGMLIS3MDL::SETUP_MGM; - break; - } - case(InternalState::STATE_CHECK_REGISTERS): { - *id = MGMLIS3MDL::READ_CONFIG_AND_DATA; - break; - } - default: - // might be a configuration error. - sif::debug << "GyroHandler::buildTransitionDeviceCommand: Unknown " - << "internal state!" << std::endl; - return HasReturnvaluesIF::RETURN_OK; - } - return buildCommandFromCommand(*id, NULL, 0); + DeviceCommandId_t *id) { + switch (internalState) { + case(InternalState::STATE_NONE): + case(InternalState::STATE_NORMAL): { + return HasReturnvaluesIF::RETURN_OK; + } + case(InternalState::STATE_FIRST_CONTACT): { + *id = MGMLIS3MDL::IDENTIFY_DEVICE; + break; + } + case(InternalState::STATE_SETUP): { + *id = MGMLIS3MDL::SETUP_MGM; + break; + } + case(InternalState::STATE_CHECK_REGISTERS): { + *id = MGMLIS3MDL::READ_CONFIG_AND_DATA; + break; + } + default: { + /* might be a configuration error. */ +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::warning << "GyroHandler::buildTransitionDeviceCommand: Unknown internal state!" << + std::endl; +#else + sif::printWarning("GyroHandler::buildTransitionDeviceCommand: Unknown internal state!\n"); +#endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ + return HasReturnvaluesIF::RETURN_OK; + } + + } + return buildCommandFromCommand(*id, NULL, 0); } uint8_t MGMHandlerLIS3MDL::readCommand(uint8_t command, bool continuousCom) { - command |= (1 << MGMLIS3MDL::RW_BIT); - if (continuousCom == true) { - command |= (1 << MGMLIS3MDL::MS_BIT); - } - return command; + command |= (1 << MGMLIS3MDL::RW_BIT); + if (continuousCom == true) { + command |= (1 << MGMLIS3MDL::MS_BIT); + } + return command; } uint8_t MGMHandlerLIS3MDL::writeCommand(uint8_t command, bool continuousCom) { - command &= ~(1 << MGMLIS3MDL::RW_BIT); - if (continuousCom == true) { - command |= (1 << MGMLIS3MDL::MS_BIT); - } - return command; + command &= ~(1 << MGMLIS3MDL::RW_BIT); + if (continuousCom == true) { + command |= (1 << MGMLIS3MDL::MS_BIT); + } + return command; } void MGMHandlerLIS3MDL::setupMgm() { - registers[0] = MGMLIS3MDL::CTRL_REG1_DEFAULT; - registers[1] = MGMLIS3MDL::CTRL_REG2_DEFAULT; - registers[2] = MGMLIS3MDL::CTRL_REG3_DEFAULT; - registers[3] = MGMLIS3MDL::CTRL_REG4_DEFAULT; - registers[4] = MGMLIS3MDL::CTRL_REG5_DEFAULT; + registers[0] = MGMLIS3MDL::CTRL_REG1_DEFAULT; + registers[1] = MGMLIS3MDL::CTRL_REG2_DEFAULT; + registers[2] = MGMLIS3MDL::CTRL_REG3_DEFAULT; + registers[3] = MGMLIS3MDL::CTRL_REG4_DEFAULT; + registers[4] = MGMLIS3MDL::CTRL_REG5_DEFAULT; - prepareCtrlRegisterWrite(); + prepareCtrlRegisterWrite(); } ReturnValue_t MGMHandlerLIS3MDL::buildNormalDeviceCommand( - DeviceCommandId_t *id) { - // Data/config register will be read in an alternating manner. - if(communicationStep == CommunicationStep::DATA) { - *id = MGMLIS3MDL::READ_CONFIG_AND_DATA; - communicationStep = CommunicationStep::TEMPERATURE; - return buildCommandFromCommand(*id, NULL, 0); - } - else { - *id = MGMLIS3MDL::READ_TEMPERATURE; - communicationStep = CommunicationStep::DATA; - return buildCommandFromCommand(*id, NULL, 0); - } + DeviceCommandId_t *id) { + // Data/config register will be read in an alternating manner. + if(communicationStep == CommunicationStep::DATA) { + *id = MGMLIS3MDL::READ_CONFIG_AND_DATA; + communicationStep = CommunicationStep::TEMPERATURE; + return buildCommandFromCommand(*id, NULL, 0); + } + else { + *id = MGMLIS3MDL::READ_TEMPERATURE; + communicationStep = CommunicationStep::DATA; + return buildCommandFromCommand(*id, NULL, 0); + } } ReturnValue_t MGMHandlerLIS3MDL::buildCommandFromCommand( - DeviceCommandId_t deviceCommand, const uint8_t *commandData, - size_t commandDataLen) { - switch(deviceCommand) { - case(MGMLIS3MDL::READ_CONFIG_AND_DATA): { - std::memset(commandBuffer, 0, sizeof(commandBuffer)); - commandBuffer[0] = readCommand(MGMLIS3MDL::CTRL_REG1, true); + DeviceCommandId_t deviceCommand, const uint8_t *commandData, + size_t commandDataLen) { + switch(deviceCommand) { + case(MGMLIS3MDL::READ_CONFIG_AND_DATA): { + std::memset(commandBuffer, 0, sizeof(commandBuffer)); + commandBuffer[0] = readCommand(MGMLIS3MDL::CTRL_REG1, true); - rawPacket = commandBuffer; - rawPacketLen = MGMLIS3MDL::NR_OF_DATA_AND_CFG_REGISTERS + 1; - return RETURN_OK; - } - case(MGMLIS3MDL::READ_TEMPERATURE): { - std::memset(commandBuffer, 0, 3); - commandBuffer[0] = readCommand(MGMLIS3MDL::TEMP_LOWBYTE, true); + rawPacket = commandBuffer; + rawPacketLen = MGMLIS3MDL::NR_OF_DATA_AND_CFG_REGISTERS + 1; + return RETURN_OK; + } + case(MGMLIS3MDL::READ_TEMPERATURE): { + std::memset(commandBuffer, 0, 3); + commandBuffer[0] = readCommand(MGMLIS3MDL::TEMP_LOWBYTE, true); - rawPacket = commandBuffer; - rawPacketLen = 3; - return RETURN_OK; - } - case(MGMLIS3MDL::IDENTIFY_DEVICE): { - return identifyDevice(); - } - case(MGMLIS3MDL::TEMP_SENSOR_ENABLE): { - return enableTemperatureSensor(commandData, commandDataLen); - } - case(MGMLIS3MDL::SETUP_MGM): { - setupMgm(); - return HasReturnvaluesIF::RETURN_OK; - } - case(MGMLIS3MDL::ACCURACY_OP_MODE_SET): { - return setOperatingMode(commandData, commandDataLen); - } - default: - return DeviceHandlerIF::COMMAND_NOT_IMPLEMENTED; - } - return HasReturnvaluesIF::RETURN_FAILED; + rawPacket = commandBuffer; + rawPacketLen = 3; + return RETURN_OK; + } + case(MGMLIS3MDL::IDENTIFY_DEVICE): { + return identifyDevice(); + } + case(MGMLIS3MDL::TEMP_SENSOR_ENABLE): { + return enableTemperatureSensor(commandData, commandDataLen); + } + case(MGMLIS3MDL::SETUP_MGM): { + setupMgm(); + return HasReturnvaluesIF::RETURN_OK; + } + case(MGMLIS3MDL::ACCURACY_OP_MODE_SET): { + return setOperatingMode(commandData, commandDataLen); + } + default: + return DeviceHandlerIF::COMMAND_NOT_IMPLEMENTED; + } + return HasReturnvaluesIF::RETURN_FAILED; } ReturnValue_t MGMHandlerLIS3MDL::identifyDevice() { - uint32_t size = 2; - commandBuffer[0] = readCommand(MGMLIS3MDL::IDENTIFY_DEVICE_REG_ADDR); - commandBuffer[1] = 0x00; + uint32_t size = 2; + commandBuffer[0] = readCommand(MGMLIS3MDL::IDENTIFY_DEVICE_REG_ADDR); + commandBuffer[1] = 0x00; - rawPacket = commandBuffer; - rawPacketLen = size; + rawPacket = commandBuffer; + rawPacketLen = size; - return RETURN_OK; + return RETURN_OK; } ReturnValue_t MGMHandlerLIS3MDL::scanForReply(const uint8_t *start, - size_t len, DeviceCommandId_t *foundId, size_t *foundLen) { - *foundLen = len; - if (len == MGMLIS3MDL::NR_OF_DATA_AND_CFG_REGISTERS + 1) { - *foundLen = len; - *foundId = MGMLIS3MDL::READ_CONFIG_AND_DATA; - // Check validity by checking config registers - if (start[1] != registers[0] or start[2] != registers[1] or - start[3] != registers[2] or start[4] != registers[3] or - start[5] != registers[4]) { - return DeviceHandlerIF::INVALID_DATA; - } - if(mode == _MODE_START_UP) { - commandExecuted = true; - } + size_t len, DeviceCommandId_t *foundId, size_t *foundLen) { + *foundLen = len; + if (len == MGMLIS3MDL::NR_OF_DATA_AND_CFG_REGISTERS + 1) { + *foundLen = len; + *foundId = MGMLIS3MDL::READ_CONFIG_AND_DATA; + // Check validity by checking config registers + if (start[1] != registers[0] or start[2] != registers[1] or + start[3] != registers[2] or start[4] != registers[3] or + start[5] != registers[4]) { +#if OBSW_VERBOSE_LEVEL >= 1 +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::warning << "MGMHandlerLIS3MDL::scanForReply: Invalid registers!" << std::endl; +#else + sif::printWarning("MGMHandlerLIS3MDL::scanForReply: Invalid registers!\n"); +#endif +#endif + return DeviceHandlerIF::INVALID_DATA; + } + if(mode == _MODE_START_UP) { + commandExecuted = true; + } - } - else if(len == MGMLIS3MDL::TEMPERATURE_REPLY_LEN) { - *foundLen = len; - *foundId = MGMLIS3MDL::READ_TEMPERATURE; - } - else if (len == MGMLIS3MDL::SETUP_REPLY_LEN) { - *foundLen = len; - *foundId = MGMLIS3MDL::SETUP_MGM; - } - else if (len == SINGLE_COMMAND_ANSWER_LEN) { - *foundLen = len; - *foundId = getPendingCommand(); - } - else { - return DeviceHandlerIF::INVALID_DATA; - } + } + else if(len == MGMLIS3MDL::TEMPERATURE_REPLY_LEN) { + *foundLen = len; + *foundId = MGMLIS3MDL::READ_TEMPERATURE; + } + else if (len == MGMLIS3MDL::SETUP_REPLY_LEN) { + *foundLen = len; + *foundId = MGMLIS3MDL::SETUP_MGM; + } + else if (len == SINGLE_COMMAND_ANSWER_LEN) { + *foundLen = len; + *foundId = getPendingCommand(); + if(*foundId == MGMLIS3MDL::IDENTIFY_DEVICE) { + if(start[1] != MGMLIS3MDL::DEVICE_ID) { +#if OBSW_VERBOSE_LEVEL >= 1 +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::warning << "MGMHandlerLIS3MDL::scanForReply: Invalid registers!" << std::endl; +#else + sif::printWarning("MGMHandlerLIS3MDL::scanForReply: Invalid registers!\n"); +#endif +#endif + return DeviceHandlerIF::INVALID_DATA; + } - // Data with SPI Interface has always this answer - if (start[0] == 0b11111111) { - return RETURN_OK; - } - else { - return DeviceHandlerIF::INVALID_DATA; - } + if(mode == _MODE_START_UP) { + commandExecuted = true; + } + } + } + else { + return DeviceHandlerIF::INVALID_DATA; + } + + /* Data with SPI Interface always has this answer */ + if (start[0] == 0b11111111) { + return RETURN_OK; + } + else { + return DeviceHandlerIF::INVALID_DATA; + } } ReturnValue_t MGMHandlerLIS3MDL::interpretDeviceReply(DeviceCommandId_t id, - const uint8_t *packet) { + const uint8_t *packet) { - switch (id) { - case MGMLIS3MDL::IDENTIFY_DEVICE: { - break; - } - case MGMLIS3MDL::SETUP_MGM: { - break; - } - case MGMLIS3MDL::READ_CONFIG_AND_DATA: { - // TODO: Store configuration and sensor values in new local datasets. + switch (id) { + case MGMLIS3MDL::IDENTIFY_DEVICE: { + break; + } + case MGMLIS3MDL::SETUP_MGM: { + break; + } + case MGMLIS3MDL::READ_CONFIG_AND_DATA: { + // TODO: Store configuration in new local datasets. - uint8_t scale = getFullScale(registers[2]); - float sensitivityFactor = getSensitivityFactor(scale); + uint8_t scale = getFullScale(registers[2]); + float sensitivityFactor = getSensitivityFactor(scale); - int16_t mgmMeasurementRawX = packet[MGMLIS3MDL::X_HIGHBYTE_IDX] << 8 - | packet[MGMLIS3MDL::X_LOWBYTE_IDX] ; - int16_t mgmMeasurementRawY = packet[MGMLIS3MDL::Y_HIGHBYTE_IDX] << 8 - | packet[MGMLIS3MDL::Y_LOWBYTE_IDX] ; - int16_t mgmMeasurementRawZ = packet[MGMLIS3MDL::Z_HIGHBYTE_IDX] << 8 - | packet[MGMLIS3MDL::Z_LOWBYTE_IDX] ; + int16_t mgmMeasurementRawX = packet[MGMLIS3MDL::X_HIGHBYTE_IDX] << 8 + | packet[MGMLIS3MDL::X_LOWBYTE_IDX] ; + int16_t mgmMeasurementRawY = packet[MGMLIS3MDL::Y_HIGHBYTE_IDX] << 8 + | packet[MGMLIS3MDL::Y_LOWBYTE_IDX] ; + int16_t mgmMeasurementRawZ = packet[MGMLIS3MDL::Z_HIGHBYTE_IDX] << 8 + | packet[MGMLIS3MDL::Z_LOWBYTE_IDX] ; - // Target value in microtesla - float mgmX = static_cast(mgmMeasurementRawX) * sensitivityFactor - * MGMLIS3MDL::GAUSS_TO_MICROTESLA_FACTOR; - float mgmY = static_cast(mgmMeasurementRawY) * sensitivityFactor - * MGMLIS3MDL::GAUSS_TO_MICROTESLA_FACTOR; - float mgmZ = static_cast(mgmMeasurementRawZ) * sensitivityFactor - * MGMLIS3MDL::GAUSS_TO_MICROTESLA_FACTOR; + /* Target value in microtesla */ + float mgmX = static_cast(mgmMeasurementRawX) * sensitivityFactor + * MGMLIS3MDL::GAUSS_TO_MICROTESLA_FACTOR; + float mgmY = static_cast(mgmMeasurementRawY) * sensitivityFactor + * MGMLIS3MDL::GAUSS_TO_MICROTESLA_FACTOR; + float mgmZ = static_cast(mgmMeasurementRawZ) * sensitivityFactor + * MGMLIS3MDL::GAUSS_TO_MICROTESLA_FACTOR; #if OBSW_VERBOSE_LEVEL >= 1 - if(debugDivider->checkAndIncrement()) { - sif::info << "MGMHandlerLIS3: Magnetic field strength in" - " microtesla:" << std::endl; - // Set terminal to utf-8 if there is an issue with micro printout. - sif::info << "X: " << mgmX << " \xC2\xB5T" << std::endl; - sif::info << "Y: " << mgmY << " \xC2\xB5T" << std::endl; - sif::info << "Z: " << mgmZ << " \xC2\xB5T" << std::endl; - } + if(debugDivider->checkAndIncrement()) { + /* Set terminal to utf-8 if there is an issue with micro printout. */ +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::info << "MGMHandlerLIS3: Magnetic field strength in" + " microtesla:" << std::endl; + sif::info << "X: " << mgmX << " \xC2\xB5T" << std::endl; + sif::info << "Y: " << mgmY << " \xC2\xB5T" << std::endl; + sif::info << "Z: " << mgmZ << " \xC2\xB5T" << std::endl; +#else + sif::printInfo("MGMHandlerLIS3: Magnetic field strength in microtesla:\n"); + sif::printInfo("X: %f " "\xC2\xB5" "T\n", mgmX); + sif::printInfo("Y: %f " "\xC2\xB5" "T\n", mgmY); + sif::printInfo("Z: %f " "\xC2\xB5" "T\n", mgmZ); #endif - ReturnValue_t result = dataset.read(); - if(result == HasReturnvaluesIF::RETURN_OK) { - dataset.fieldStrengthX = mgmX; - dataset.fieldStrengthY = mgmY; - dataset.fieldStrengthZ = mgmZ; - dataset.setValidity(true, true); - dataset.commit(); - } - break; - } + } +#endif + PoolReadHelper readHelper(&dataset); + if(readHelper.getReadResult() == HasReturnvaluesIF::RETURN_OK) { + dataset.fieldStrengthX = mgmX; + dataset.fieldStrengthY = mgmY; + dataset.fieldStrengthZ = mgmZ; + dataset.setValidity(true, true); + } + break; + } - case MGMLIS3MDL::READ_TEMPERATURE: { - int16_t tempValueRaw = packet[2] << 8 | packet[1]; - float tempValue = 25.0 + ((static_cast(tempValueRaw)) / 8.0); + case MGMLIS3MDL::READ_TEMPERATURE: { + int16_t tempValueRaw = packet[2] << 8 | packet[1]; + float tempValue = 25.0 + ((static_cast(tempValueRaw)) / 8.0); #if OBSW_VERBOSE_LEVEL >= 1 - if(debugDivider->check()) { - // Set terminal to utf-8 if there is an issue with micro printout. - sif::info << "MGMHandlerLIS3: Temperature: " << tempValue<< " °C" - << std::endl; - } + if(debugDivider->check()) { + /* Set terminal to utf-8 if there is an issue with micro printout. */ +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::info << "MGMHandlerLIS3: Temperature: " << tempValue << " \xC2\xB0" << "C" << + std::endl; +#else + sif::printInfo("MGMHandlerLIS3: Temperature: %f" "\xC2\xB0" "C\n"); +#endif + } #endif ReturnValue_t result = dataset.read(); if(result == HasReturnvaluesIF::RETURN_OK) { dataset.temperature = tempValue; dataset.commit(); } - break; - } + break; + } - default: { - return DeviceHandlerIF::UNKNOWN_DEVICE_REPLY; - } + default: { + return DeviceHandlerIF::UNKNOWN_DEVICE_REPLY; + } - } - return RETURN_OK; + } + return RETURN_OK; } uint8_t MGMHandlerLIS3MDL::getFullScale(uint8_t ctrlRegister2) { - bool FS0 = false; - bool FS1 = false; - if ((ctrlRegister2 >> 5) == 1) - FS0 = true; - if ((ctrlRegister2 >> 6) == 1) - FS1 = true; - if ((FS0 == true) && (FS1 == true)) - return 16; - else if ((FS0 == false) && (FS1 == true)) - return 12; - else if ((FS0 == true) && (FS1 == false)) - return 8; - else - return 4; + bool FS0 = false; + bool FS1 = false; + if ((ctrlRegister2 >> 5) == 1) + FS0 = true; + if ((ctrlRegister2 >> 6) == 1) + FS1 = true; + if ((FS0 == true) && (FS1 == true)) + return 16; + else if ((FS0 == false) && (FS1 == true)) + return 12; + else if ((FS0 == true) && (FS1 == false)) + return 8; + else + return 4; } float MGMHandlerLIS3MDL::getSensitivityFactor(uint8_t scale) { - return (float) scale / (INT16_MAX); + return (float) scale / (INT16_MAX); } ReturnValue_t MGMHandlerLIS3MDL::enableTemperatureSensor( - const uint8_t *commandData, size_t commandDataLen) { - triggerEvent(CHANGE_OF_SETUP_PARAMETER); - uint32_t size = 2; - commandBuffer[0] = writeCommand(MGMLIS3MDL::CTRL_REG1); - if (commandDataLen > 1) { - return INVALID_NUMBER_OR_LENGTH_OF_PARAMETERS; - } - switch (*commandData) { - case (MGMLIS3MDL::ON): { - commandBuffer[1] = registers[0] | (1 << 7); - break; - } - case (MGMLIS3MDL::OFF): { - commandBuffer[1] = registers[0] & ~(1 << 7); - break; - } - default: - return INVALID_COMMAND_PARAMETER; - } - registers[0] = commandBuffer[1]; + const uint8_t *commandData, size_t commandDataLen) { + triggerEvent(CHANGE_OF_SETUP_PARAMETER); + uint32_t size = 2; + commandBuffer[0] = writeCommand(MGMLIS3MDL::CTRL_REG1); + if (commandDataLen > 1) { + return INVALID_NUMBER_OR_LENGTH_OF_PARAMETERS; + } + switch (*commandData) { + case (MGMLIS3MDL::ON): { + commandBuffer[1] = registers[0] | (1 << 7); + break; + } + case (MGMLIS3MDL::OFF): { + commandBuffer[1] = registers[0] & ~(1 << 7); + break; + } + default: + return INVALID_COMMAND_PARAMETER; + } + registers[0] = commandBuffer[1]; - rawPacket = commandBuffer; - rawPacketLen = size; + rawPacket = commandBuffer; + rawPacketLen = size; - return RETURN_OK; + return RETURN_OK; } ReturnValue_t MGMHandlerLIS3MDL::setOperatingMode(const uint8_t *commandData, - size_t commandDataLen) { - triggerEvent(CHANGE_OF_SETUP_PARAMETER); - if (commandDataLen != 1) { - return INVALID_NUMBER_OR_LENGTH_OF_PARAMETERS; - } + size_t commandDataLen) { + triggerEvent(CHANGE_OF_SETUP_PARAMETER); + if (commandDataLen != 1) { + return INVALID_NUMBER_OR_LENGTH_OF_PARAMETERS; + } - switch (commandData[0]) { - case MGMLIS3MDL::LOW: - registers[0] = (registers[0] & (~(1 << MGMLIS3MDL::OM1))) & (~(1 << MGMLIS3MDL::OM0)); - registers[3] = (registers[3] & (~(1 << MGMLIS3MDL::OMZ1))) & (~(1 << MGMLIS3MDL::OMZ0)); - break; - case MGMLIS3MDL::MEDIUM: - registers[0] = (registers[0] & (~(1 << MGMLIS3MDL::OM1))) | (1 << MGMLIS3MDL::OM0); - registers[3] = (registers[3] & (~(1 << MGMLIS3MDL::OMZ1))) | (1 << MGMLIS3MDL::OMZ0); - break; + switch (commandData[0]) { + case MGMLIS3MDL::LOW: + registers[0] = (registers[0] & (~(1 << MGMLIS3MDL::OM1))) & (~(1 << MGMLIS3MDL::OM0)); + registers[3] = (registers[3] & (~(1 << MGMLIS3MDL::OMZ1))) & (~(1 << MGMLIS3MDL::OMZ0)); + break; + case MGMLIS3MDL::MEDIUM: + registers[0] = (registers[0] & (~(1 << MGMLIS3MDL::OM1))) | (1 << MGMLIS3MDL::OM0); + registers[3] = (registers[3] & (~(1 << MGMLIS3MDL::OMZ1))) | (1 << MGMLIS3MDL::OMZ0); + break; - case MGMLIS3MDL::HIGH: - registers[0] = (registers[0] | (1 << MGMLIS3MDL::OM1)) & (~(1 << MGMLIS3MDL::OM0)); - registers[3] = (registers[3] | (1 << MGMLIS3MDL::OMZ1)) & (~(1 << MGMLIS3MDL::OMZ0)); - break; + case MGMLIS3MDL::HIGH: + registers[0] = (registers[0] | (1 << MGMLIS3MDL::OM1)) & (~(1 << MGMLIS3MDL::OM0)); + registers[3] = (registers[3] | (1 << MGMLIS3MDL::OMZ1)) & (~(1 << MGMLIS3MDL::OMZ0)); + break; - case MGMLIS3MDL::ULTRA: - registers[0] = (registers[0] | (1 << MGMLIS3MDL::OM1)) | (1 << MGMLIS3MDL::OM0); - registers[3] = (registers[3] | (1 << MGMLIS3MDL::OMZ1)) | (1 << MGMLIS3MDL::OMZ0); - break; - default: - break; - } + case MGMLIS3MDL::ULTRA: + registers[0] = (registers[0] | (1 << MGMLIS3MDL::OM1)) | (1 << MGMLIS3MDL::OM0); + registers[3] = (registers[3] | (1 << MGMLIS3MDL::OMZ1)) | (1 << MGMLIS3MDL::OMZ0); + break; + default: + break; + } - return prepareCtrlRegisterWrite(); + return prepareCtrlRegisterWrite(); } void MGMHandlerLIS3MDL::fillCommandAndReplyMap() { - /* - * Regarding ArduinoBoard: - * Actually SPI answers directly, but as commanding ArduinoBoard the - * communication could be delayed - * SPI always has to be triggered, so there could be no periodic answer of - * the device, the device has to asked with a command, so periodic is zero. - * - * We dont read single registers, we just expect special - * reply from he Readall_MGM - */ - insertInCommandAndReplyMap(MGMLIS3MDL::READ_CONFIG_AND_DATA, 1, &dataset); - insertInCommandAndReplyMap(MGMLIS3MDL::READ_TEMPERATURE, 1); - insertInCommandAndReplyMap(MGMLIS3MDL::SETUP_MGM, 1); - insertInCommandAndReplyMap(MGMLIS3MDL::IDENTIFY_DEVICE, 1); - insertInCommandAndReplyMap(MGMLIS3MDL::TEMP_SENSOR_ENABLE, 1); - insertInCommandAndReplyMap(MGMLIS3MDL::ACCURACY_OP_MODE_SET, 1); + /* + * Regarding ArduinoBoard: + * Actually SPI answers directly, but as commanding ArduinoBoard the + * communication could be delayed + * SPI always has to be triggered, so there could be no periodic answer of + * the device, the device has to asked with a command, so periodic is zero. + * + * We dont read single registers, we just expect special + * reply from he Readall_MGM + */ + insertInCommandAndReplyMap(MGMLIS3MDL::READ_CONFIG_AND_DATA, 1, &dataset); + insertInCommandAndReplyMap(MGMLIS3MDL::READ_TEMPERATURE, 1); + insertInCommandAndReplyMap(MGMLIS3MDL::SETUP_MGM, 1); + insertInCommandAndReplyMap(MGMLIS3MDL::IDENTIFY_DEVICE, 1); + insertInCommandAndReplyMap(MGMLIS3MDL::TEMP_SENSOR_ENABLE, 1); + insertInCommandAndReplyMap(MGMLIS3MDL::ACCURACY_OP_MODE_SET, 1); } ReturnValue_t MGMHandlerLIS3MDL::prepareCtrlRegisterWrite() { + commandBuffer[0] = writeCommand(MGMLIS3MDL::CTRL_REG1, true); - commandBuffer[0] = writeCommand(MGMLIS3MDL::CTRL_REG1, true); + for (size_t i = 0; i < MGMLIS3MDL::NR_OF_CTRL_REGISTERS; i++) { + commandBuffer[i + 1] = registers[i]; + } + rawPacket = commandBuffer; + rawPacketLen = MGMLIS3MDL::NR_OF_CTRL_REGISTERS + 1; - for (size_t i = 0; i < MGMLIS3MDL::NR_OF_CTRL_REGISTERS; i++) { - commandBuffer[i + 1] = registers[i]; - } - rawPacket = commandBuffer; - rawPacketLen = MGMLIS3MDL::NR_OF_CTRL_REGISTERS + 1; - - // We dont have to check if this is working because we just did it - return RETURN_OK; + /* We dont have to check if this is working because we just did it */ + return RETURN_OK; } void MGMHandlerLIS3MDL::doTransition(Mode_t modeFrom, Submode_t subModeFrom) { @@ -415,22 +459,25 @@ void MGMHandlerLIS3MDL::doTransition(Mode_t modeFrom, Submode_t subModeFrom) { } uint32_t MGMHandlerLIS3MDL::getTransitionDelayMs(Mode_t from, Mode_t to) { - return 5000; + return 30000; } void MGMHandlerLIS3MDL::modeChanged(void) { - internalState = InternalState::STATE_NONE; + internalState = InternalState::STATE_NONE; } ReturnValue_t MGMHandlerLIS3MDL::initializeLocalDataPool( - localpool::DataPool &localDataPoolMap, LocalDataPoolManager &poolManager) { - localDataPoolMap.emplace(MGMLIS3MDL::FIELD_STRENGTH_X, - new PoolEntry({0.0})); - localDataPoolMap.emplace(MGMLIS3MDL::FIELD_STRENGTH_Y, - new PoolEntry({0.0})); - localDataPoolMap.emplace(MGMLIS3MDL::FIELD_STRENGTH_Z, - new PoolEntry({0.0})); - localDataPoolMap.emplace(MGMLIS3MDL::TEMPERATURE_CELCIUS, - new PoolEntry({0.0})); - return HasReturnvaluesIF::RETURN_OK; + localpool::DataPool &localDataPoolMap, LocalDataPoolManager &poolManager) { + localDataPoolMap.emplace(MGMLIS3MDL::FIELD_STRENGTH_X, + new PoolEntry({0.0})); + localDataPoolMap.emplace(MGMLIS3MDL::FIELD_STRENGTH_Y, + new PoolEntry({0.0})); + localDataPoolMap.emplace(MGMLIS3MDL::FIELD_STRENGTH_Z, + new PoolEntry({0.0})); + localDataPoolMap.emplace(MGMLIS3MDL::TEMPERATURE_CELCIUS, + new PoolEntry({0.0})); + return HasReturnvaluesIF::RETURN_OK; +} + +void MGMHandlerLIS3MDL::performOperationHook() { } diff --git a/mission/devices/MGMHandlerLIS3MDL.h b/mission/devices/MGMHandlerLIS3MDL.h index 77874e33..fc998f46 100644 --- a/mission/devices/MGMHandlerLIS3MDL.h +++ b/mission/devices/MGMHandlerLIS3MDL.h @@ -18,149 +18,151 @@ */ class MGMHandlerLIS3MDL: public DeviceHandlerBase { public: - enum class CommunicationStep { - DATA, - TEMPERATURE - }; + enum class CommunicationStep { + DATA, + TEMPERATURE + }; - static const uint8_t INTERFACE_ID = CLASS_ID::MGM_LIS3MDL; - static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::MGM_LIS3MDL; - //Notifies a command to change the setup parameters - static const Event CHANGE_OF_SETUP_PARAMETER = MAKE_EVENT(0, severity::LOW); + static const uint8_t INTERFACE_ID = CLASS_ID::MGM_LIS3MDL; + static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::MGM_LIS3MDL; + //Notifies a command to change the setup parameters + static const Event CHANGE_OF_SETUP_PARAMETER = MAKE_EVENT(0, severity::LOW); - MGMHandlerLIS3MDL(uint32_t objectId, object_id_t deviceCommunication, - CookieIF* comCookie); - virtual ~MGMHandlerLIS3MDL(); + MGMHandlerLIS3MDL(uint32_t objectId, object_id_t deviceCommunication, + CookieIF* comCookie); + virtual ~MGMHandlerLIS3MDL(); protected: - /** DeviceHandlerBase overrides */ - void doShutDown() override; - void doStartUp() override; - void doTransition(Mode_t modeFrom, Submode_t subModeFrom) override; - uint32_t getTransitionDelayMs(Mode_t from, Mode_t to) override; - ReturnValue_t buildCommandFromCommand( - DeviceCommandId_t deviceCommand, const uint8_t *commandData, - size_t commandDataLen) override; - ReturnValue_t buildTransitionDeviceCommand( - DeviceCommandId_t *id) override; - ReturnValue_t buildNormalDeviceCommand( - DeviceCommandId_t *id) override; - ReturnValue_t scanForReply(const uint8_t *start, size_t len, - DeviceCommandId_t *foundId, size_t *foundLen) override; - ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, - const uint8_t *packet) override; - void fillCommandAndReplyMap() override; - void modeChanged(void) override; - ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap, - LocalDataPoolManager &poolManager) override; + /** DeviceHandlerBase overrides */ + void doShutDown() override; + void doStartUp() override; + void doTransition(Mode_t modeFrom, Submode_t subModeFrom) override; + uint32_t getTransitionDelayMs(Mode_t from, Mode_t to) override; + ReturnValue_t buildCommandFromCommand( + DeviceCommandId_t deviceCommand, const uint8_t *commandData, + size_t commandDataLen) override; + ReturnValue_t buildTransitionDeviceCommand( + DeviceCommandId_t *id) override; + ReturnValue_t buildNormalDeviceCommand( + DeviceCommandId_t *id) override; + ReturnValue_t scanForReply(const uint8_t *start, size_t len, + DeviceCommandId_t *foundId, size_t *foundLen) override; + ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, + const uint8_t *packet) override; + void fillCommandAndReplyMap() override; + void modeChanged(void) override; + ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap, + LocalDataPoolManager &poolManager) override; private: - MGMLIS3MDL::MgmPrimaryDataset dataset; + MGMLIS3MDL::MgmPrimaryDataset dataset; - /*------------------------------------------------------------------------*/ - /* Device specific commands and variables */ - /*------------------------------------------------------------------------*/ - /** - * Sets the read bit for the command - * @param single command to set the read-bit at - * @param boolean to select a continuous read bit, default = false - */ - uint8_t readCommand(uint8_t command, bool continuousCom = false); + /*------------------------------------------------------------------------*/ + /* Device specific commands and variables */ + /*------------------------------------------------------------------------*/ + /** + * Sets the read bit for the command + * @param single command to set the read-bit at + * @param boolean to select a continuous read bit, default = false + */ + uint8_t readCommand(uint8_t command, bool continuousCom = false); - /** - * Sets the write bit for the command - * @param single command to set the write-bit at - * @param boolean to select a continuous write bit, default = false - */ - uint8_t writeCommand(uint8_t command, bool continuousCom = false); + /** + * Sets the write bit for the command + * @param single command to set the write-bit at + * @param boolean to select a continuous write bit, default = false + */ + uint8_t writeCommand(uint8_t command, bool continuousCom = false); - /** - * This Method gets the full scale for the measurement range - * e.g.: +- 4 gauss. See p.25 datasheet. - * @return The ReturnValue does not contain the sign of the value - */ - uint8_t getFullScale(uint8_t ctrlReg2); + /** + * This Method gets the full scale for the measurement range + * e.g.: +- 4 gauss. See p.25 datasheet. + * @return The ReturnValue does not contain the sign of the value + */ + uint8_t getFullScale(uint8_t ctrlReg2); - /** - * The 16 bit value needs to be divided by the full range of a 16bit value - * and then multiplied with the current scale of the MGM. - * This factor returns the factor required to achieve this with - * one multiplication. - * - * @param scale is the return value of the getFulscale Method - * @return Multiplication factor to get the sensor value from raw data. - */ - float getSensitivityFactor(uint8_t scale); + /** + * The 16 bit value needs to be divided by the full range of a 16bit value + * and then multiplied with the current scale of the MGM. + * This factor returns the factor required to achieve this with + * one multiplication. + * + * @param scale is the return value of the getFulscale Method + * @return Multiplication factor to get the sensor value from raw data. + */ + float getSensitivityFactor(uint8_t scale); - /** - * This Command detects the device ID - */ - ReturnValue_t identifyDevice(); + /** + * This Command detects the device ID + */ + ReturnValue_t identifyDevice(); - virtual void setupMgm(); + virtual void setupMgm(); - /*------------------------------------------------------------------------*/ - /* Non normal commands */ - /*------------------------------------------------------------------------*/ - /** - * Enables/Disables the integrated Temperaturesensor - * @param commandData On or Off - * @param length of the commandData: has to be 1 - */ - virtual ReturnValue_t enableTemperatureSensor(const uint8_t *commandData, - size_t commandDataLen); + /*------------------------------------------------------------------------*/ + /* Non normal commands */ + /*------------------------------------------------------------------------*/ + /** + * Enables/Disables the integrated Temperaturesensor + * @param commandData On or Off + * @param length of the commandData: has to be 1 + */ + virtual ReturnValue_t enableTemperatureSensor(const uint8_t *commandData, + size_t commandDataLen); - /** - * Sets the accuracy of the measurement of the axis. The noise is changing. - * @param commandData LOW, MEDIUM, HIGH, ULTRA - * @param length of the command, has to be 1 - */ - virtual ReturnValue_t setOperatingMode(const uint8_t *commandData, - size_t commandDataLen); + /** + * Sets the accuracy of the measurement of the axis. The noise is changing. + * @param commandData LOW, MEDIUM, HIGH, ULTRA + * @param length of the command, has to be 1 + */ + virtual ReturnValue_t setOperatingMode(const uint8_t *commandData, + size_t commandDataLen); - //Length a sindgle command SPI answer - static const uint8_t SINGLE_COMMAND_ANSWER_LEN = 2; + //Length a sindgle command SPI answer + static const uint8_t SINGLE_COMMAND_ANSWER_LEN = 2; - //Single SPIcommand has 2 bytes, first for adress, second for content - size_t singleComandSize = 2; - //has the size for all adresses of the lis3mdl + the continous write bit - uint8_t commandBuffer[MGMLIS3MDL::NR_OF_DATA_AND_CFG_REGISTERS + 1]; + //Single SPIcommand has 2 bytes, first for adress, second for content + size_t singleComandSize = 2; + //has the size for all adresses of the lis3mdl + the continous write bit + uint8_t commandBuffer[MGMLIS3MDL::NR_OF_DATA_AND_CFG_REGISTERS + 1]; - /** - * We want to save the registers we set, so we dont have to read the - * registers when we want to change something. - * --> everytime we change set a register we have to save it - */ - uint8_t registers[MGMLIS3MDL::NR_OF_CTRL_REGISTERS]; + /** + * We want to save the registers we set, so we dont have to read the + * registers when we want to change something. + * --> everytime we change set a register we have to save it + */ + uint8_t registers[MGMLIS3MDL::NR_OF_CTRL_REGISTERS]; - uint8_t statusRegister = 0; + uint8_t statusRegister = 0; - /** - * We always update all registers together, so this method updates - * the rawpacket and rawpacketLen, so we just manipulate the local - * saved register - * - */ - ReturnValue_t prepareCtrlRegisterWrite(); + /** + * We always update all registers together, so this method updates + * the rawpacket and rawpacketLen, so we just manipulate the local + * saved register + * + */ + ReturnValue_t prepareCtrlRegisterWrite(); - enum class InternalState { - STATE_NONE, - STATE_FIRST_CONTACT, - STATE_SETUP, - STATE_CHECK_REGISTERS, - STATE_NORMAL - }; + enum class InternalState { + STATE_NONE, + STATE_FIRST_CONTACT, + STATE_SETUP, + STATE_CHECK_REGISTERS, + STATE_NORMAL + }; - InternalState internalState = InternalState::STATE_NONE; - CommunicationStep communicationStep = CommunicationStep::DATA; - bool commandExecuted = false; + InternalState internalState = InternalState::STATE_NONE; + CommunicationStep communicationStep = CommunicationStep::DATA; + bool commandExecuted = false; #if OBSW_VERBOSE_LEVEL >= 1 - PeriodicOperationDivider* debugDivider; + PeriodicOperationDivider* debugDivider; #endif + void performOperationHook() override; + }; #endif /* MISSION_DEVICES_MGMLIS3MDLHANDLER_H_ */ diff --git a/mission/devices/PCDUHandler.cpp b/mission/devices/PCDUHandler.cpp index 0b3b1459..8e2c1a39 100644 --- a/mission/devices/PCDUHandler.cpp +++ b/mission/devices/PCDUHandler.cpp @@ -1,9 +1,12 @@ #include "PCDUHandler.h" -#include +#include +#include + #include + #include #include -#include + PCDUHandler::PCDUHandler(object_id_t setObjectId, size_t cmdQueueSize) : SystemObject(setObjectId), poolManager(this, nullptr), pdu2HkTableDataset(this), pdu1HkTableDataset( diff --git a/mission/devices/PCDUHandler.h b/mission/devices/PCDUHandler.h index f6b49dc0..566e1d9c 100644 --- a/mission/devices/PCDUHandler.h +++ b/mission/devices/PCDUHandler.h @@ -1,6 +1,7 @@ #ifndef MISSION_DEVICES_PCDUHANDLER_H_ #define MISSION_DEVICES_PCDUHANDLER_H_ +#include #include #include #include @@ -9,7 +10,7 @@ #include #include #include -#include + /** * @brief The PCDUHandler provides a compact interface to handle all devices related to the diff --git a/mission/devices/PDU2Handler.cpp b/mission/devices/PDU2Handler.cpp index b442c12c..eaeb00bb 100644 --- a/mission/devices/PDU2Handler.cpp +++ b/mission/devices/PDU2Handler.cpp @@ -1,6 +1,6 @@ #include "PDU2Handler.h" #include -#include +#include PDU2Handler::PDU2Handler(object_id_t objectId, object_id_t comIF, CookieIF * comCookie) : GomspaceDeviceHandler(objectId, comIF, comCookie, PDU::MAX_CONFIGTABLE_ADDRESS, diff --git a/mission/devices/Tmp1075Handler.cpp b/mission/devices/Tmp1075Handler.cpp index f0d95a18..a84f5597 100644 --- a/mission/devices/Tmp1075Handler.cpp +++ b/mission/devices/Tmp1075Handler.cpp @@ -1,6 +1,6 @@ #include #include -#include +#include Tmp1075Handler::Tmp1075Handler(object_id_t objectId, object_id_t comIF, CookieIF * comCookie) : diff --git a/mission/devices/devicedefinitions/MGMHandlerLIS3Definitions.h b/mission/devices/devicedefinitions/MGMHandlerLIS3Definitions.h index 581e46e3..0d51cda1 100644 --- a/mission/devices/devicedefinitions/MGMHandlerLIS3Definitions.h +++ b/mission/devices/devicedefinitions/MGMHandlerLIS3Definitions.h @@ -24,11 +24,11 @@ static const DeviceCommandId_t IDENTIFY_DEVICE = 0x03; static const DeviceCommandId_t TEMP_SENSOR_ENABLE = 0x04; static const DeviceCommandId_t ACCURACY_OP_MODE_SET = 0x05; -//Number of all control registers +/* Number of all control registers */ static const uint8_t NR_OF_CTRL_REGISTERS = 5; -//Number of registers in the MGM +/* Number of registers in the MGM */ static const uint8_t NR_OF_REGISTERS = 19; -//Total number of adresses for all registers +/* Total number of adresses for all registers */ static const uint8_t TOTAL_NR_OF_ADRESSES = 52; static const uint8_t NR_OF_DATA_AND_CFG_REGISTERS = 14; static const uint8_t TEMPERATURE_REPLY_LEN = 3; @@ -37,47 +37,47 @@ static const uint8_t SETUP_REPLY_LEN = 6; /*------------------------------------------------------------------------*/ /* Register adresses */ /*------------------------------------------------------------------------*/ -// Register adress returns identifier of device with default 0b00111101 +/* Register adress returns identifier of device with default 0b00111101 */ static const uint8_t IDENTIFY_DEVICE_REG_ADDR = 0b00001111; static const uint8_t DEVICE_ID = 0b00111101; // Identifier for Device -//Register adress to access register 1 +/* Register adress to access register 1 */ static const uint8_t CTRL_REG1 = 0b00100000; -//Register adress to access register 2 +/* Register adress to access register 2 */ static const uint8_t CTRL_REG2 = 0b00100001; -//Register adress to access register 3 +/* Register adress to access register 3 */ static const uint8_t CTRL_REG3 = 0b00100010; -//Register adress to access register 4 +/* Register adress to access register 4 */ static const uint8_t CTRL_REG4 = 0b00100011; -//Register adress to access register 5 +/* Register adress to access register 5 */ static const uint8_t CTRL_REG5 = 0b00100100; -//Register adress to access status register +/* Register adress to access status register */ static const uint8_t STATUS_REG_IDX = 8; static const uint8_t STATUS_REG = 0b00100111; - //Register adress to access low byte of x-axis +/* Register adress to access low byte of x-axis */ static const uint8_t X_LOWBYTE_IDX = 9; static const uint8_t X_LOWBYTE = 0b00101000; -//Register adress to access high byte of x-axis +/* Register adress to access high byte of x-axis */ static const uint8_t X_HIGHBYTE_IDX = 10; static const uint8_t X_HIGHBYTE = 0b00101001; -//Register adress to access low byte of y-axis +/* Register adress to access low byte of y-axis */ static const uint8_t Y_LOWBYTE_IDX = 11; static const uint8_t Y_LOWBYTE = 0b00101010; -//Register adress to access high byte of y-axis +/* Register adress to access high byte of y-axis */ static const uint8_t Y_HIGHBYTE_IDX = 12; static const uint8_t Y_HIGHBYTE = 0b00101011; -//Register adress to access low byte of z-axis +/* Register adress to access low byte of z-axis */ static const uint8_t Z_LOWBYTE_IDX = 13; static const uint8_t Z_LOWBYTE = 0b00101100; -//Register adress to access high byte of z-axis +/* Register adress to access high byte of z-axis */ static const uint8_t Z_HIGHBYTE_IDX = 14; static const uint8_t Z_HIGHBYTE = 0b00101101; -//Register adress to access low byte of temperature sensor +/* Register adress to access low byte of temperature sensor */ static const uint8_t TEMP_LOWBYTE = 0b00101110; -//Register adress to access high byte of temperature sensor +/* Register adress to access high byte of temperature sensor */ static const uint8_t TEMP_HIGHBYTE = 0b00101111; /*------------------------------------------------------------------------*/ diff --git a/mission/utility/InitMission.h b/mission/utility/InitMission.h new file mode 100644 index 00000000..b4a83a1e --- /dev/null +++ b/mission/utility/InitMission.h @@ -0,0 +1,22 @@ +#ifndef MISSION_UTILITY_INITMISSION_H_ +#define MISSION_UTILITY_INITMISSION_H_ + +#include +#include + +namespace initmission { + +void printAddObjectError(const char* name, object_id_t objectId) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::error << "InitMission::printAddError: Adding object " << name << " with object ID 0x" + << std::hex << std::setfill('0') << std::setw(8) << objectId + << " failed!" << std::dec << std::endl; +#else + sif::printError("InitMission::printAddError: Adding object %s with object ID 0x%08x failed!\n" , + name, objectId); +#endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ +} + +} + +#endif /* MISSION_UTILITY_INITMISSION_H_ */ diff --git a/test/testtasks/TestTask.cpp b/test/testtasks/TestTask.cpp index e6fb8457..57abc758 100644 --- a/test/testtasks/TestTask.cpp +++ b/test/testtasks/TestTask.cpp @@ -1,4 +1,6 @@ -#include +#include "TestTask.h" +#include + #include #include #include @@ -8,65 +10,101 @@ #include #include -bool TestTask::oneShotAction = true; -MutexIF* TestTask::testLock = nullptr; TestTask::TestTask(object_id_t objectId_): - SystemObject(objectId_), testMode(testModes::A) { - if(testLock == nullptr) { - testLock = MutexFactory::instance()->createMutex(); - } - IPCStore = objectManager->get(objects::IPC_STORE); +SystemObject(objectId_), testMode(testModes::A) { + IPCStore = objectManager->get(objects::IPC_STORE); } TestTask::~TestTask() { } ReturnValue_t TestTask::performOperation(uint8_t operationCode) { - ReturnValue_t result = RETURN_OK; - sif::info << "Hallo EIVE!" << std::endl; - testLock ->lockMutex(MutexIF::TimeoutType::WAITING, 20); - if(oneShotAction) { - // Add code here which should only be run once - performOneShotAction(); - oneShotAction = false; - } - testLock->unlockMutex(); + ReturnValue_t result = RETURN_OK; - // Add code here which should only be run once per performOperation - performPeriodicAction(); + if(oneShotAction) { + /* Add code here which should only be run once */ + performOneShotAction(); + oneShotAction = false; + } - // Add code here which should only be run on alternating cycles. - if(testMode == testModes::A) { - performActionA(); - testMode = testModes::B; - } - else if(testMode == testModes::B) { - performActionB(); - testMode = testModes::A; - } - return result; + /* Add code here which should only be run once per performOperation */ + performPeriodicAction(); + + /* Add code here which should only be run on alternating cycles. */ + if(testMode == testModes::A) { + performActionA(); + testMode = testModes::B; + } + else if(testMode == testModes::B) { + performActionB(); + testMode = testModes::A; + } + return result; } +#include +#include + +/** + * @brief Dummy data from GPS receiver. Will be replaced witgh hyperion data later. + */ +const char +gps_rx_data[] = "" + "$GPRMC,183729,A,3907.356,N,12102.482,W,000.0,360.0,080301,015.5,E*6F\r\n" + "$GPRMB,A,,,,,,,,,,,,V*71\r\n" + "$GPGGA,183730,3907.356,N,12102.482,W,1,05,1.6,646.4,M,-24.1,M,,*75\r\n" + "$GPGSA,A,3,02,,,07,,09,24,26,,,,,1.6,1.6,1.0*3D\r\n" + "$GPGSV,2,1,08,02,43,088,38,04,42,145,00,05,11,291,00,07,60,043,35*71\r\n" + "$GPGSV,2,2,08,08,02,145,00,09,46,303,47,24,16,178,32,26,18,231,43*77\r\n" + "$PGRME,22.0,M,52.9,M,51.0,M*14\r\n" + "$GPGLL,3907.360,N,12102.481,W,183730,A*33\r\n" + "$PGRMZ,2062,f,3*2D\r\n" + "$PGRMM,WGS84*06\r\n" + "$GPBOD,,T,,M,,*47\r\n" + "$GPRTE,1,1,c,0*07\r\n" + "$GPRMC,183731,A,3907.482,N,12102.436,W,000.0,360.0,080301,015.5,E*67\r\n" + "$GPRMB,A,,,,,,,,,,,,V*71\r\n"; + ReturnValue_t TestTask::performOneShotAction() { - // Everything here will only be performed once. +#if OBSW_ADD_TEST_CODE == 1 + performLwgpsTest(); +#endif return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t TestTask::performPeriodicAction() { - ReturnValue_t result = RETURN_OK; - return result; + ReturnValue_t result = RETURN_OK; + return result; } ReturnValue_t TestTask::performActionA() { - ReturnValue_t result = RETURN_OK; - // Add periodically executed code here - return result; + ReturnValue_t result = RETURN_OK; + /* Add periodically executed code here */ + return result; } ReturnValue_t TestTask::performActionB() { - ReturnValue_t result = RETURN_OK; - // Add periodically executed code here - return result; + ReturnValue_t result = RETURN_OK; + /* Add periodically executed code here */ + return result; +} + +void TestTask::performLwgpsTest() { + /* Everything here will only be performed once. */ + etl::vector testVec; + + lwgps_t gpsStruct; + sif::info << "Size of GPS struct: " << sizeof(gpsStruct) << std::endl; + lwgps_init(&gpsStruct); + + /* Process all input data */ + lwgps_process(&gpsStruct, gps_rx_data, strlen(gps_rx_data)); + + /* Print messages */ + printf("Valid status: %d\r\n", gpsStruct.is_valid); + printf("Latitude: %f degrees\r\n", gpsStruct.latitude); + printf("Longitude: %f degrees\r\n", gpsStruct.longitude); + printf("Altitude: %f meters\r\n", gpsStruct.altitude); } diff --git a/test/testtasks/TestTask.h b/test/testtasks/TestTask.h index 24e62af1..e2e8db48 100644 --- a/test/testtasks/TestTask.h +++ b/test/testtasks/TestTask.h @@ -48,9 +48,10 @@ protected: private: // Actually, to be really thread-safe, a mutex should be used as well // Let's keep it simple for now. - static bool oneShotAction; - static MutexIF* testLock; + bool oneShotAction = true; StorageManagerIF* IPCStore; + + void performLwgpsTest(); }; diff --git a/thirdparty/libcsp/CMakeLists.txt b/thirdparty/libcsp/CMakeLists.txt new file mode 100644 index 00000000..5c9f7677 --- /dev/null +++ b/thirdparty/libcsp/CMakeLists.txt @@ -0,0 +1,12 @@ +cmake_minimum_required(VERSION 3.13) + +set(LIB_CSP_NAME libcsp) + +add_library(${LIB_CSP_NAME}) + +add_subdirectory(src) +add_subdirectory(include) + +target_include_directories(${LIB_CSP_NAME} PRIVATE + ${CMAKE_CURRENT_SOURCE_DIR} +) \ No newline at end of file diff --git a/thirdparty/libcsp/bindings/python/libcsp/__init__.py b/thirdparty/libcsp/bindings/python/libcsp/__init__.py new file mode 100644 index 00000000..39de36b5 --- /dev/null +++ b/thirdparty/libcsp/bindings/python/libcsp/__init__.py @@ -0,0 +1,6 @@ +import sys + +if sys.version_info >= (3, 0): + from libcsp_py3 import * +else: + from libcsp_py2 import * diff --git a/thirdparty/libcsp/doc/example.rst b/thirdparty/libcsp/doc/example.rst new file mode 100644 index 00000000..b82a055e --- /dev/null +++ b/thirdparty/libcsp/doc/example.rst @@ -0,0 +1,123 @@ +Client and server example +========================= + +The following examples show the initialization of the protocol stack and examples of client/server code. + +Initialization Sequence +----------------------- + +This code initializes the CSP buffer system, device drivers and router core. The example uses the CAN interface function csp_can_tx but the initialization is similar for other interfaces. The loopback interface does not require any explicit initialization. + +.. code-block:: c + + #include + #include + + /* CAN configuration struct for SocketCAN interface "can0" */ + struct csp_can_config can_conf = {.ifc = "can0"}; + + /* Init buffer system with 10 packets of maximum 320 bytes each */ + csp_buffer_init(10, 320); + + /* Init CSP with address 1 */ + csp_init(1); + + /* Init the CAN interface with hardware filtering */ + csp_can_init(CSP_CAN_MASKED, &can_conf) + + /* Setup default route to CAN interface */ + csp_route_set(CSP_DEFAULT_ROUTE, &csp_can_tx, CSP_HOST_MAC); + + /* Start router task with 500 word stack, OS task priority 1 */ + csp_route_start_task(500, 1); + +Server +------ + +This example shows how to create a server task that listens for incoming connections. CSP should be initialized before starting this task. Note the use of `csp_service_handler()` as the default branch in the port switch case. The service handler will automatically reply to ICMP-like requests, such as pings and buffer status requests. + +.. code-block:: c + + void csp_task(void *parameters) { + /* Create socket without any socket options */ + csp_socket_t *sock = csp_socket(CSP_SO_NONE); + + /* Bind all ports to socket */ + csp_bind(sock, CSP_ANY); + + /* Create 10 connections backlog queue */ + csp_listen(sock, 10); + + /* Pointer to current connection and packet */ + csp_conn_t *conn; + csp_packet_t *packet; + + /* Process incoming connections */ + while (1) { + /* Wait for connection, 10000 ms timeout */ + if ((conn = csp_accept(sock, 10000)) == NULL) + continue; + + /* Read packets. Timout is 1000 ms */ + while ((packet = csp_read(conn, 1000)) != NULL) { + switch (csp_conn_dport(conn)) { + case MY_PORT: + /* Process packet here */ + default: + /* Let the service handler reply pings, buffer use, etc. */ + csp_service_handler(conn, packet); + break; + } + } + + /* Close current connection, and handle next */ + csp_close(conn); + } + } + +Client +------ + +This example shows how to allocate a packet buffer, connect to another host and send the packet. CSP should be initialized before calling this function. RDP, XTEA, HMAC and CRC checksums can be enabled per connection, by setting the connection option to a bitwise OR of any combination of `CSP_O_RDP`, `CSP_O_XTEA`, `CSP_O_HMAC` and `CSP_O_CRC`. + +.. code-block:: c + + int send_packet(void) { + + /* Get packet buffer for data */ + csp_packet_t *packet = csp_buffer_get(data_size); + if (packet == NULL) { + /* Could not get buffer element */ + printf("Failed to get buffer element\\n"); + return -1; + } + + /* Connect to host HOST, port PORT with regular UDP-like protocol and 1000 ms timeout */ + csp_conn_t *conn = csp_connect(CSP_PRIO_NORM, HOST, PORT, 1000, CSP_O_NONE); + if (conn == NULL) { + /* Connect failed */ + printf("Connection failed\\n"); + /* Remember to free packet buffer */ + csp_buffer_free(packet); + return -1; + } + + /* Copy message to packet */ + char *msg = "HELLO"; + strcpy(packet->data, msg); + + /* Set packet length */ + packet->length = strlen(msg); + + /* Send packet */ + if (!csp_send(conn, packet, 1000)) { + /* Send failed */ + printf("Send failed\\n"); + csp_buffer_free(packet); + } + + /* Close connection */ + csp_close(conn); + + return 0 + } diff --git a/thirdparty/libcsp/doc/history.rst b/thirdparty/libcsp/doc/history.rst new file mode 100644 index 00000000..ad064873 --- /dev/null +++ b/thirdparty/libcsp/doc/history.rst @@ -0,0 +1,17 @@ +History +======= + +The idea was developed by a group of students from Aalborg University in 2008. In 2009 the main developer started working for GomSpace, and CSP became integrated into the GomSpace products. The protocol is based on a 32-bit header containing both transport, network and MAC-layer information. It's implementation is designed for, but not limited to, embedded systems such as the 8-bit AVR microprocessor and the 32-bit ARM and AVR from Atmel. The implementation is written in C and is currently ported to run on FreeRTOS and POSIX and pthreads based operating systems like Linux and BSD. The three letter acronym CSP was originally an abbreviation for CAN Space Protocol because the first MAC-layer driver was written for CAN-bus. Now the physical layer has extended to include spacelink, I2C and RS232, the name was therefore extended to the more general CubeSat Space Protocol without changing the abbreviation. + +Satellites using CSP +-------------------- + +This is the known list of satellites or organisations that uses CSP. + + * GomSpace GATOSS GOMX-1 + * AAUSAT-3 + * EgyCubeSat + * EuroLuna + * NUTS + * Hawaiian Space Flight Laboratory + * GomSpace GOMX-3 diff --git a/thirdparty/libcsp/doc/interfaces.rst b/thirdparty/libcsp/doc/interfaces.rst new file mode 100644 index 00000000..5a80325c --- /dev/null +++ b/thirdparty/libcsp/doc/interfaces.rst @@ -0,0 +1,95 @@ +CSP Interfaces +============== + +This is an example of how to implement a new layer-2 interface in CSP. The example is going to show how to create a `csp_if_fifo`, using a set of [named pipes](http://en.wikipedia.org/wiki/Named_pipe). The complete interface example code can be found in `examples/fifo.c`. For an example of a fragmenting interface, see the CAN interface in `src/interfaces/csp_if_can.c`. + +CSP interfaces are declared in a `csp_iface_t` structure, which sets the interface nexthop function and name. A maximum transmission unit can also be set, which forces CSP to drop outgoing packets above a certain size. The fifo interface is defined as: + +.. code-block:: c + + #include + #include + + csp_iface_t csp_if_fifo = { + .name = "fifo", + .nexthop = csp_fifo_tx, + .mtu = BUF_SIZE, + }; + +Outgoing traffic +---------------- + +The nexthop function takes a pointer to a CSP packet and a timeout as parameters. All outgoing packets that are routed to the interface are passed to this function: + +.. code-block:: c + + int csp_fifo_tx(csp_packet_t *packet, uint32_t timeout) { + write(tx_channel, &packet->length, packet->length + sizeof(uint32_t) + sizeof(uint16_t)); + csp_buffer_free(packet); + return 1; + } + +In the fifo interface, we simply transmit the header, length field and data using a write to the fifo. CSP does not dictate the wire format, so other interfaces may decide to e.g. ignore the length field if the physical layer provides start/stop flags. + +_Important notice: If the transmission succeeds, the interface must free the packet and return 1. If transmission fails, the nexthop function should return 0 and not free the packet, to allow retransmissions by the caller._ + +Incoming traffic +---------------- + +The interface also needs to receive incoming packets and pass it to the CSP protocol stack. In the fifo interface, this is handled by a thread that blocks on the incoming fifo and waits for packets: + +.. code-block:: c + + void * fifo_rx(void * parameters) { + csp_packet_t *buf = csp_buffer_get(BUF_SIZE); + /* Wait for packet on fifo */ + while (read(rx_channel, &buf->length, BUF_SIZE) > 0) { + csp_qfifo_write(buf, &csp_if_fifo, NULL); + buf = csp_buffer_get(BUF_SIZE); + } + } + +A new CSP buffer is preallocated with csp_buffer_get(). When data is received, the packet is passed to CSP using `csp_qfifo_write()` and a new buffer is allocated for the next packet. In addition to the received packet, `csp_qfifo_write()` takes two additional arguments: + +.. code-block:: c + + void csp_qfifo_write(csp_packet_t *packet, csp_iface_t *interface, CSP_BASE_TYPE *pxTaskWoken); + +The calling interface must be passed in `interface` to avoid routing loops. Furthermore, `pxTaskWoken` must be set to a non-NULL value if the packet is received in an interrupt service routine. If the packet is received in task context, NULL must be passed. 'pxTaskWoken' only applies to FreeRTOS systems, and POSIX system should always set the value to NULL. + +`csp_qfifo_write` will either accept the packet or free the packet buffer, so the interface must never free the packet after passing it to CSP. + +Initialization +-------------- + +In order to initialize the interface, and make it available to the router, use the following function found in `csp/csp_interface.h`: + +.. code-block:: c + + csp_route_add_if(&csp_if_fifo); + +This actually happens automatically if you try to call `csp_route_add()` with an interface that is unknown to the router. This may however be removed in the future, in order to ensure that all interfaces are initialised before configuring the routing table. The reason is, that some products released in the future may ship with an empty routing table, which is then configured by a routing protocol rather than a static configuration. + +In order to setup a manual static route, use the following example where the default route is set to the fifo interface: + +.. code-block:: c + + csp_route_set(CSP_DEFAULT_ROUTE, &csp_if_fifo, CSP_NODE_MAC); + +All outgoing traffic except loopback, is now passed to the fifo interface's nexthop function. + +Building the example +-------------------- + +The fifo examples can be compiled with: + +.. code-block:: bash + + % gcc csp_if_fifo.c -o csp_if_fifo -I/include -L/build -lcsp -lpthread -lrt + +The two named pipes are created with: + +.. code-block:: bash + + % mkfifo server_to_client client_to_server + diff --git a/thirdparty/libcsp/doc/libcsp.rst b/thirdparty/libcsp/doc/libcsp.rst new file mode 100644 index 00000000..f866015f --- /dev/null +++ b/thirdparty/libcsp/doc/libcsp.rst @@ -0,0 +1,21 @@ +.. CSP Documentation master file. + +.. _libcsp: + +********************** +CubeSat Space Protocol +********************** + +.. toctree:: + :maxdepth: 3 + + ../README + history + structure + interfaces + memory + protocolstack + topology + mtu + example + diff --git a/thirdparty/libcsp/doc/memory.rst b/thirdparty/libcsp/doc/memory.rst new file mode 100644 index 00000000..4e38d711 --- /dev/null +++ b/thirdparty/libcsp/doc/memory.rst @@ -0,0 +1,28 @@ +How CSP uses memory +=================== + +CSP has been written for small microprocessor systems. The way memory is handled is therefore a tradeoff between the amount used and the code efficiency. This section tries to give some answers to what the memory is used for and how it it used. The primary memory blocks in use by CSP is: + + * Routing table + * Ports table + * Connection table + * Buffer pool + * Interface list + +Tables +------ +The reason for using tables for the routes, ports and connections is speed. When a new packet arrives the core of CSP needs to do a quick lookup in the connection so see if it can find an existing connection to which the packet matches. If this is not found, it will take a lookup in the ports table to see if there are any applications listening on the incoming port number. Another argument of using tables are pre-allocation. The linker will reserve an area of the memory for which the routes and connections can be stored. This avoid an expensive `malloc()` call during initialization of CSP, and practically costs zero CPU instructions. The downside of using tables are the wasted memory used by unallocated ports and connections. For the routing table the argumentation is the same, pre-allocation is better than calling `malloc()`. + +Buffer Pool +----------- + +The buffer handling system can be compiled for either static allocation or a one-time dynamic allocation of the main memory block. After this, the buffer system is entirely self-contained. All allocated elements are of the same size, so the buffer size must be chosen to be able to handle the maximum possible packet length. The buffer pool uses a queue to store pointers to free buffer elements. First of all, this gives a very quick method to get the next free element since the dequeue is an O(1) operation. Furthermore, since the queue is a protected operating system primitive, it can be accessed from both task-context and interrupt-context. The `csp_buffer_get` version is for task-context and `csp_buffer_get_isr` is for interrupt-context. Using fixed size buffer elements that are preallocated is again a question of speed and safety. + + +A basic concept of the buffer system is called Zero-Copy. This means that from userspace to the kernel-driver, the buffer is never copied from one buffer to another. This is a big deal for a small microprocessor, where a call to `memcpy()` can be very expensive. In practice when data is inserted into a packet, it is shifted a certain number of bytes in order to allow for a packet header to be prepended at the lower layers. This also means that there is a strict contract between the layers, which data can be modified and where. The buffer object is normally casted to a `csp_packet_t`, but when its given to an interface on the MAC layer it's casted to a `csp_i2c_frame_t` for example. + +Interface list +-------------- + +The interface list is a simple single-ended linked list of references to the interface specification structures. These structures are static const and allocated by the linker. The pointer to this data is inserted into the list one time during setup of the interface. Each entry in the routing table has a direct pointer to the interface element, thereby avoiding list lookup, but the list is needed in order for the dynamic route configuration to know which interfaces are available. + diff --git a/thirdparty/libcsp/doc/mtu.rst b/thirdparty/libcsp/doc/mtu.rst new file mode 100644 index 00000000..27753300 --- /dev/null +++ b/thirdparty/libcsp/doc/mtu.rst @@ -0,0 +1,19 @@ +Maximum Transfer Unit +===================== + +There are two things limiting the MTU of CSP. + + 1. The pre-allocated buffer pool’s allocation size + 2. The link layer protocol. + +So let’s assume that you have made a protocol called KISS with a MTU of 256. The 256 is the total amount of data that you can put into the CSP-packet. However, you need to take the overhead of the link layer into account. Typically this could consist of a length field and/or a start/stop flag. So the actual frame size on the link layer would for example be 256 bytes of data + 2 bytes sync flag + 2 bytes length field. + +This requires a buffer allocation of at lest 256 + 2 + 2. However, the CSP packet itself has some reserved bytes in the beginning of the packet (which you can see in csp.h) - so the recommended buffer allocation size is MAX MTU + 16 bytes. In this case the max MTU would be 256. + +If you try to pass data which is longer than the MTU, the chance is that you will also make a buffer overflow in the CSP buffer pool. However, lets assume that you have two interfaces one with an MTU of 200 bytes and another with an MTU of 100 bytes. In this case you might successfully transfer 150 bytes over the first interface, but the packet will be rejected once it comes to the second interface. + +If you want to increase your MTU of a specific link layer, it is up to the link layer protocol to implement its own fragmentation protocol. A good example is CAN-bus which only allows a frame size of 8 bytes. libcsp have a small protocol for this called the “CAN fragmentation protocol" or CFP for short. This allows data of much larger size to be transferred over the CAN bus. + +Okay, but what if you want to transfer 1000 bytes, and the network maximum MTU is 256? Well, since CSP does not include streaming sockets, only packet’s. Somebody will have to split that data up into chunks. It might be that you application have special knowledge about the datatype you are transmitting, and that it makes sense to split the 1000 byte content into 10 chunks of 100 byte status messages. This, application layer delimitation might be good if you have a situation with packet loss, because your receiver could still make good usage of the partially delivered chunks. + +But, what if you just want 1000 bytes transmitted, and you don’t care about the fragmentation unit, and also don’t want the hassle of writing the fragmentation code yourself? - In this case, libcsp now features a new (still experimental) feature called SFP (small fragmentation protocol) designed to work on the application layer. For this purpose you will not use csp_send and csp_recv, but csp_sfp_send and csp_sfp_recv. This will split your data into chunks of a certain size, enumerate them and transfer over a given connection. If a chunk is missing the SFP client will abort the reception, because SFP does not provide retransmission. If you wish to also have retransmission and orderly delivery you will have to open an RDP connection and send your SFP message to that connection. diff --git a/thirdparty/libcsp/doc/protocolstack.rst b/thirdparty/libcsp/doc/protocolstack.rst new file mode 100644 index 00000000..365aabbe --- /dev/null +++ b/thirdparty/libcsp/doc/protocolstack.rst @@ -0,0 +1,54 @@ +The Protocol Stack +================== + +The CSP protocol stack includes functionality on all layers of the TCP/IP model: + +Layer 1: Drivers +---------------- + +Lib CSP is not designed for any specific processor or hardware peripheral, but yet these drivers are required in order to work. The intention of LibCSP is not to provide CAN, I2C or UART drivers for all platforms, however some drivers has been included for some platforms. If you do not find your platform supported, it is quite simple to add a driver that conforms to the CSP interfaces. For example the I2C driver just requires three functions: `init`, `send` and `recv`. For good stability and performance interrupt driven drivers are preferred in favor of polled drivers. Where applicable also DMA usage is recommended. + +Layer 2: MAC interfaces +----------------------- + +CSP has interfaces for I2C, CAN, RS232 (KISS) and Loopback. The layer 2 protocol software defines a frame-format that is suitable for the media. CSP can be easily extended with implementations for even more links. For example a radio-link and IP-networks. The file `csp_interface.h` declares the rx and tx functions needed in order to define a network interface in CSP. During initialisation of CSP each interface will be inserted into a linked list of interfaces that is available to the router. In cases where link-layer addresses are required, such as I2C, the routing table supports specifying next-hop link-layer address directly. This avoids the need to implement an address resolution protocol to translate CSP addresses to I2C addresses. + +Layer 3: Network Router +----------------------- + +The router core is the backbone of the CSP implementation. The router works by looking at a 32-bit CSP header which contains the delivery and source address together with port numbers for the connection. Each router supports both local delivery and forwarding of frames to another destination. Frames will never exit the router on the same interface that they arrives at, this concept is called split horizon, and helps prevent routing loops. + +The main purpose of the router is to accept incoming packets and deliver them to the right message queue. Therefore, in order to listen on a port-number on the network, a task must create a socket and call the accept() call. This will make the task block and wait for incoming traffic, just like a web-server or similar. When an incoming connection is opened, the task is woken. Depending on the task-priority, the task can even preempt another task and start execution immediately. + +There is no routing protocol for automatic route discovery, all routing tables are pre-programmed into the subsystems. The table itself contains a separate route to each of the possible 32 nodes in the network and the additional default route. This means that the overall topology must be decided before putting sub-systems together, as explained in the `topology.md` file. However CSP has an extension on port zero CMP (CSP management protocol), which allows for over-the-network routing table configuration. This has the advantage that default routes could be changed if for example the primary radio fails, and the secondary should be used instead. + +Layer 4: Transport Layer +------------------------ + +LibCSP implements two different Transport Layer protocols, they are called UDP (unreliable datagram protocol) and RDP (reliable datagram protocol). The name UDP has not been chosen to be an exact replica of the UDP (user datagram protocol) known from the TCP/IP model, but they have certain similarities. + +The most important thing to notice is that CSP is entirely a datagram service. There is no stream based service like TCP. A datagram is defined a block of data with a specified size and structure. This block enters the transport layer as a single datagram and exits the transport layer in the other end as a single datagram. CSP preserves this structure all the way to the physical layer for I2C, KISS and Loopback interfaces are used. The CAN-bus interface has to fragment the datagram into CAN-frames of 8 bytes, however only a fully completed datagram will arrive at the receiver. + +UDP +^^^ + +UDP uses a simple transmission model without implicit hand-shaking dialogues for guaranteeing reliability, ordering, or data integrity. Thus, UDP provides an unreliable service and datagrams may arrive out of order, appear duplicated, or go missing without notice. UDP assumes that error checking and correction is either not necessary or performed in the application, avoiding the overhead of such processing at the network interface level. Time-sensitive applications often use UDP because dropping packets is preferable to waiting for delayed packets, which may not be an option in a real-time system. + +UDP is very practical to implement request/reply based communication where a single packet forms the request and a single packet forms the reply. In this case a typical request and wait protocol is used between the client and server, which will simply return an error if a reply is not received within a specified time limit. An error would normally lead to a retransmission of the request from the user or operator which sent the request. + +While UDP is very simple, it also has some limitations. Normally a human in the loop is a good thing when operating the satellite over UDP. But when it comes to larger file transfers, the human becomes the bottleneck. When a high-speed file transfer is initiated data acknowledgment should be done automatically in order to speed up the transfer. This is where the RDP protocol can help. + +RDP +^^^ +CSP provides a transport layer extension called RDP (reliable datagram protocol) which is an implementation of RFC908 and RFC1151. RDP provides a few additional features: + + * Three-way handshake + * Flow Control + * Data-buffering + * Packet re-ordering + * Retransmission + * Windowing + * Extended Acknowledgment + +For more information on this, please refer to RFC908. + diff --git a/thirdparty/libcsp/doc/structure.rst b/thirdparty/libcsp/doc/structure.rst new file mode 100644 index 00000000..4c9b515c --- /dev/null +++ b/thirdparty/libcsp/doc/structure.rst @@ -0,0 +1,27 @@ +Structure +========= +The Cubesat Space Protocol library is structured as shown in the following table: + +============================= ========================================================================= +**Folder** **Description** +============================= ========================================================================= +libcsp/include/csp Main include files +libcsp/include/csp/arch Architecture include files +libcsp/include/csp/interfaces Interface include files +libcsp/include/csp/drivers Drivers include files +libcsp/src Main modules for CSP: io, router, connections, services +libcsp/src/interfaces Interface modules for CAN, I2C, KISS, LOOP and ZMQHUB +libcsp/src/drivers/can Driver for CAN +libcsp/src/drivers/usart Driver for USART +libcsp/src/arch/freertos FreeRTOS architecture module +libcsp/src/arch/macosx Mac OS X architecture module +libcsp/src/arch/posix Posix architecture module +libcsp/src/arch/windows Windows architecture module +libcsp/src/rtable Routing table module +libcsp/transport Transport module, UDP and RDP +libcsp/crypto Crypto module +libcsp/utils Utilities +libcsp/bindings/python Python wrapper for libcsp +libcsp/examples CSP examples (source code) +libasf/doc The doc folder contains the source code for this documentation +============================= ========================================================================= diff --git a/thirdparty/libcsp/doc/topology.rst b/thirdparty/libcsp/doc/topology.rst new file mode 100644 index 00000000..e629c29e --- /dev/null +++ b/thirdparty/libcsp/doc/topology.rst @@ -0,0 +1,26 @@ +Network Topology +================ + +CSP uses a network oriented terminology similar to what is known from the Internet and the TCP/IP model. A CSP network can be configured for several different topologies. The most common topology is to create two segments, one for the Satellite and one for the Ground-Station. + +.. code-block:: none + + I2C BUS + _______________________________ + / | | | \ + +---+ +---+ +---+ +---+ +---+ + |OBC| |COM| |EPS| |PL1| |PL2| Nodes 0 - 7 (Space segment) + +---+ +---+ +---+ +---+ +---+ + ^ + | Radio + v + +---+ +----+ + |TNC| ------- | PC | Nodes 8 - 15 (Ground segment) + +---+ USB +----+ + + Node 9 Node 10 + +The address range, from 0 to 15, has been segmented into two equal size segments. This allows for easy routing in the network. All addresses starting with binary 1 is on the ground-segment, and all addresses starting with 0 is on the space segment. From CSP v1.0 the address space has been increased to 32 addresses, 0 to 31. But for legacy purposes, the old 0 to 15 is still used in most products. + +The network is configured using static routes initialised at boot-up of each sub-system. This means that the basic routing table must be assigned compile-time of each subsystem. However each node supports assigning an individual route to every single node in the network and can be changed run-time. This means that the network topology can be easily reconfigured after startup. + diff --git a/thirdparty/libcsp/examples/csp_if_fifo.c b/thirdparty/libcsp/examples/csp_if_fifo.c new file mode 100644 index 00000000..136fc3aa --- /dev/null +++ b/thirdparty/libcsp/examples/csp_if_fifo.c @@ -0,0 +1,165 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include +#include +#include +#include +#include +#include + +#include +#include + +#define TYPE_SERVER 1 +#define TYPE_CLIENT 2 +#define PORT 10 +#define BUF_SIZE 250 + +pthread_t rx_thread; +int rx_channel, tx_channel; + +int csp_fifo_tx(csp_iface_t *ifc, csp_packet_t *packet, uint32_t timeout); + +csp_iface_t csp_if_fifo = { + .name = "fifo", + .nexthop = csp_fifo_tx, + .mtu = BUF_SIZE, +}; + +int csp_fifo_tx(csp_iface_t *ifc, csp_packet_t *packet, uint32_t timeout) { + /* Write packet to fifo */ + if (write(tx_channel, &packet->length, packet->length + sizeof(uint32_t) + sizeof(uint16_t)) < 0) + printf("Failed to write frame\r\n"); + csp_buffer_free(packet); + return CSP_ERR_NONE; +} + +void * fifo_rx(void * parameters) { + csp_packet_t *buf = csp_buffer_get(BUF_SIZE); + /* Wait for packet on fifo */ + while (read(rx_channel, &buf->length, BUF_SIZE) > 0) { + csp_qfifo_write(buf, &csp_if_fifo, NULL); + buf = csp_buffer_get(BUF_SIZE); + } + + return NULL; +} + +int main(int argc, char **argv) { + + int me, other, type; + const char *message = "Testing CSP"; + const char *rx_channel_name; + const char *tx_channel_name; + csp_socket_t *sock; + csp_conn_t *conn; + csp_packet_t *packet; + + /* Run as either server or client */ + if (argc != 2) { + printf("usage: %s \r\n", argv[0]); + return -1; + } + + /* Set type */ + if (strcmp(argv[1], "server") == 0) { + me = 1; + other = 2; + tx_channel_name = "server_to_client"; + rx_channel_name = "client_to_server"; + type = TYPE_SERVER; + } else if (strcmp(argv[1], "client") == 0) { + me = 2; + other = 1; + tx_channel_name = "client_to_server"; + rx_channel_name = "server_to_client"; + type = TYPE_CLIENT; + } else { + printf("Invalid type. Must be either 'server' or 'client'\r\n"); + return -1; + } + + /* Init CSP and CSP buffer system */ + if (csp_init(me) != CSP_ERR_NONE || csp_buffer_init(10, 300) != CSP_ERR_NONE) { + printf("Failed to init CSP\r\n"); + return -1; + } + + tx_channel = open(tx_channel_name, O_RDWR); + if (tx_channel < 0) { + printf("Failed to open TX channel\r\n"); + return -1; + } + + rx_channel = open(rx_channel_name, O_RDWR); + if (rx_channel < 0) { + printf("Failed to open RX channel\r\n"); + return -1; + } + + /* Start fifo RX task */ + pthread_create(&rx_thread, NULL, fifo_rx, NULL); + + /* Set default route and start router */ + csp_route_set(CSP_DEFAULT_ROUTE, &csp_if_fifo, CSP_NODE_MAC); + csp_route_start_task(0, 0); + + /* Create socket and listen for incoming connections */ + if (type == TYPE_SERVER) { + sock = csp_socket(CSP_SO_NONE); + csp_bind(sock, PORT); + csp_listen(sock, 5); + } + + /* Super loop */ + while (1) { + if (type == TYPE_SERVER) { + /* Process incoming packet */ + conn = csp_accept(sock, 1000); + if (conn) { + packet = csp_read(conn, 0); + if (packet) + printf("Received: %s\r\n", packet->data); + csp_buffer_free(packet); + csp_close(conn); + } + } else { + /* Send a new packet */ + packet = csp_buffer_get(strlen(message)); + if (packet) { + strcpy((char *) packet->data, message); + packet->length = strlen(message); + + conn = csp_connect(CSP_PRIO_NORM, other, PORT, 1000, CSP_O_NONE); + printf("Sending: %s\r\n", message); + if (!conn || !csp_send(conn, packet, 1000)) + return -1; + csp_close(conn); + } + sleep(1); + } + } + + close(rx_channel); + close(tx_channel); + + return 0; +} diff --git a/thirdparty/libcsp/examples/csp_if_fifo_windows.c b/thirdparty/libcsp/examples/csp_if_fifo_windows.c new file mode 100644 index 00000000..5b360709 --- /dev/null +++ b/thirdparty/libcsp/examples/csp_if_fifo_windows.c @@ -0,0 +1,225 @@ +#include +#include +#include +#include +#include +#undef interface + +#include +#include + +#define PIPE_BUFSIZE 1024 + +#define TYPE_SERVER 1 +#define TYPE_CLIENT 2 +#define PORT 10 +#define BUF_SIZE 250 + + +static LPCTSTR pipeName = TEXT("\\\\.\\pipe\\CSP_Pipe"); + +static HANDLE pipe = INVALID_HANDLE_VALUE; + +unsigned WINAPI fifo_rx(void *); +unsigned WINAPI pipe_listener(void *); + +void printError(void); + +int csp_fifo_tx(csp_packet_t *packet, uint32_t timeout); + +csp_iface_t csp_if_fifo = { + .name = "fifo", + .nexthop = csp_fifo_tx, + .mtu = BUF_SIZE, +}; + +int csp_fifo_tx(csp_packet_t *packet, uint32_t timeout) { + printf("csp_fifo_tx tid: %lu\n", GetCurrentThreadId()); + DWORD expectedSent = packet->length + sizeof(uint32_t) + sizeof(uint16_t); + DWORD actualSent; + /* Write packet to fifo */ + if( !WriteFile(pipe, &packet->length, expectedSent, &actualSent, NULL) + || actualSent != expectedSent ) { + printError(); + } + + csp_buffer_free(packet); + return CSP_ERR_NONE; +} + + +int main(int argc, char *argv[]) { + int me, other, type; + char *message = "Testing CSP"; + csp_socket_t *sock = NULL; + csp_conn_t *conn = NULL; + csp_packet_t *packet = NULL; + + /* Run as either server or client */ + if (argc != 2) { + printf("usage: server \r\n"); + return -1; + } + + /* Set type */ + if (strcmp(argv[1], "server") == 0) { + me = 1; + other = 2; + type = TYPE_SERVER; + } else if (strcmp(argv[1], "client") == 0) { + me = 2; + other = 1; + type = TYPE_CLIENT; + } else { + printf("Invalid type. Must be either 'server' or 'client'\r\n"); + return -1; + } + + /* Init CSP and CSP buffer system */ + if (csp_init(me) != CSP_ERR_NONE || csp_buffer_init(10, 300) != CSP_ERR_NONE) { + printf("Failed to init CSP\r\n"); + return -1; + } + + if( type == TYPE_SERVER ) { + _beginthreadex(NULL, 0, pipe_listener, NULL, 0, 0); + } else { + pipe = CreateFile( + pipeName, + GENERIC_READ | GENERIC_WRITE, + 0, + NULL, + OPEN_EXISTING, + 0, + NULL); + if( pipe == INVALID_HANDLE_VALUE ) { + printError(); + return -1; + } + } + + /* Set default route and start router */ + csp_route_set(CSP_DEFAULT_ROUTE, &csp_if_fifo, CSP_NODE_MAC); + csp_route_start_task(0, 0); + + /* Create socket and listen for incoming connections */ + if (type == TYPE_SERVER) { + sock = csp_socket(CSP_SO_NONE); + csp_bind(sock, PORT); + csp_listen(sock, 5); + } + + /* Super loop */ + while (1) { + if (type == TYPE_SERVER) { + /* Process incoming packet */ + conn = csp_accept(sock, 1000); + if (conn) { + packet = csp_read(conn, 0); + if (packet) + printf("Received: %s\r\n", packet->data); + csp_buffer_free(packet); + csp_close(conn); + } + } else { + /* Send a new packet */ + packet = csp_buffer_get(strlen(message)); + if (packet) { + strcpy((char *) packet->data, message); + packet->length = strlen(message); + + conn = csp_connect(CSP_PRIO_NORM, other, PORT, 1000, CSP_O_NONE); + printf("Sending: %s\r\n", message); + if (!conn || !csp_send(conn, packet, 1000)) + return -1; + csp_close(conn); + Sleep(1000); + } + } + } + + return 0; +} + +void printError(void) { + LPTSTR messageBuffer = NULL; + DWORD errorCode = GetLastError(); + DWORD formatMessageRet; + formatMessageRet = FormatMessage( + FORMAT_MESSAGE_ALLOCATE_BUFFER | + FORMAT_MESSAGE_FROM_SYSTEM | + FORMAT_MESSAGE_IGNORE_INSERTS, + NULL, + errorCode, + MAKELANGID(LANG_NEUTRAL, SUBLANG_DEFAULT), + (LPTSTR)&messageBuffer, + 0, + NULL); + + if( !formatMessageRet ) { + wprintf(L"FormatMessage error, code: %lu\n", GetLastError()); + return; + } + + printf("%s\n", messageBuffer); + LocalFree(messageBuffer); +} + +unsigned WINAPI pipe_listener(void *parameters) { + while(1) { + HANDLE pipe = CreateNamedPipe( + pipeName, + PIPE_ACCESS_DUPLEX, + PIPE_TYPE_MESSAGE | PIPE_READMODE_MESSAGE | PIPE_WAIT, + PIPE_UNLIMITED_INSTANCES, + PIPE_BUFSIZE, + PIPE_BUFSIZE, + 0, + NULL); + BOOL clientConnected; + if( pipe == INVALID_HANDLE_VALUE ) { + printf("Error creating named pipe. Code %lu\n", GetLastError()); + return -1; + } + + // True if client connects *after* server called ConnectNamedPipe + // or *between* CreateNamedPipe and ConnectNamedPipe + clientConnected = + ConnectNamedPipe(pipe, NULL) ? TRUE : GetLastError()==ERROR_PIPE_CONNECTED; + printf("Client connected!\n"); + + if( !clientConnected ) { + printf("Failure while listening for clients. Code %lu\n", GetLastError()); + CloseHandle(pipe); + return -1; + } + printf("Create client thread\n"); + _beginthreadex(NULL, 0, fifo_rx, (PVOID)pipe, 0, 0); + } + + return 0; +} + +unsigned WINAPI fifo_rx(void *handle) { + printf("fifo_rx tid: %lu\n", GetCurrentThreadId()); + HANDLE pipe = (HANDLE) handle; + csp_packet_t *buf = csp_buffer_get(BUF_SIZE); + DWORD bytesRead; + BOOL readSuccess; + + while(1) { + readSuccess = + ReadFile(pipe, &buf->length, BUF_SIZE, &bytesRead, NULL); + if( !readSuccess || bytesRead == 0 ) { + csp_buffer_free(buf); + printError(); + break; + } + csp_qfifo_write(buf, &csp_if_fifo, NULL); + buf = csp_buffer_get(BUF_SIZE); + } + printf("Closing pipe to client\n"); + CloseHandle(pipe); + + return 0; +} diff --git a/thirdparty/libcsp/examples/kiss.c b/thirdparty/libcsp/examples/kiss.c new file mode 100644 index 00000000..c95eb2aa --- /dev/null +++ b/thirdparty/libcsp/examples/kiss.c @@ -0,0 +1,151 @@ +/** + * Build this example on linux with: + * ./waf configure --enable-examples --enable-if-kiss --with-driver-usart=linux --enable-crc32 clean build + */ + +#include +#include +#include + +#include +#include + +#define PORT 10 +#define MY_ADDRESS 1 + +#define SERVER_TIDX 0 +#define CLIENT_TIDX 1 +#define USART_HANDLE 0 + +CSP_DEFINE_TASK(task_server) { + int running = 1; + csp_socket_t *socket = csp_socket(CSP_SO_NONE); + csp_conn_t *conn; + csp_packet_t *packet; + csp_packet_t *response; + + response = csp_buffer_get(sizeof(csp_packet_t) + 2); + if( response == NULL ) { + fprintf(stderr, "Could not allocate memory for response packet!\n"); + return CSP_TASK_RETURN; + } + response->data[0] = 'O'; + response->data[1] = 'K'; + response->length = 2; + + csp_bind(socket, CSP_ANY); + csp_listen(socket, 5); + + printf("Server task started\r\n"); + + while(running) { + if( (conn = csp_accept(socket, 10000)) == NULL ) { + continue; + } + + while( (packet = csp_read(conn, 100)) != NULL ) { + switch( csp_conn_dport(conn) ) { + case PORT: + if( packet->data[0] == 'q' ) + running = 0; + csp_buffer_free(packet); + csp_send(conn, response, 1000); + break; + default: + csp_service_handler(conn, packet); + break; + } + } + + csp_close(conn); + } + + csp_buffer_free(response); + + return CSP_TASK_RETURN; +} + +CSP_DEFINE_TASK(task_client) { + + char outbuf = 'q'; + char inbuf[3] = {0}; + int pingResult; + + for(int i = 50; i <= 200; i+= 50) { + pingResult = csp_ping(MY_ADDRESS, 1000, 100, CSP_O_NONE); + printf("Ping with payload of %d bytes, took %d ms\n", i, pingResult); + csp_sleep_ms(1000); + } + csp_ps(MY_ADDRESS, 1000); + csp_sleep_ms(1000); + csp_memfree(MY_ADDRESS, 1000); + csp_sleep_ms(1000); + csp_buf_free(MY_ADDRESS, 1000); + csp_sleep_ms(1000); + csp_uptime(MY_ADDRESS, 1000); + csp_sleep_ms(1000); + + csp_transaction(0, MY_ADDRESS, PORT, 1000, &outbuf, 1, inbuf, 2); + printf("Quit response from server: %s\n", inbuf); + + return CSP_TASK_RETURN; +} + +int main(int argc, char **argv) { + csp_debug_toggle_level(CSP_PACKET); + csp_debug_toggle_level(CSP_INFO); + + csp_buffer_init(10, 300); + csp_init(MY_ADDRESS); + + struct usart_conf conf; + +#if defined(CSP_WINDOWS) + conf.device = argc != 2 ? "COM4" : argv[1]; + conf.baudrate = CBR_9600; + conf.databits = 8; + conf.paritysetting = NOPARITY; + conf.stopbits = ONESTOPBIT; + conf.checkparity = FALSE; +#elif defined(CSP_POSIX) + conf.device = argc != 2 ? "/dev/ttyUSB0" : argv[1]; + conf.baudrate = 500000; +#elif defined(CSP_MACOSX) + conf.device = argc != 2 ? "/dev/tty.usbserial-FTSM9EGE" : argv[1]; + conf.baudrate = 115200; +#endif + + /* Run USART init */ + usart_init(&conf); + + /* Setup CSP interface */ + static csp_iface_t csp_if_kiss; + static csp_kiss_handle_t csp_kiss_driver; + csp_kiss_init(&csp_if_kiss, &csp_kiss_driver, usart_putc, usart_insert, "KISS"); + + /* Setup callback from USART RX to KISS RS */ + void my_usart_rx(uint8_t * buf, int len, void * pxTaskWoken) { + csp_kiss_rx(&csp_if_kiss, buf, len, pxTaskWoken); + } + usart_set_callback(my_usart_rx); + + csp_route_set(MY_ADDRESS, &csp_if_kiss, CSP_NODE_MAC); + csp_route_start_task(0, 0); + + csp_conn_print_table(); + csp_route_print_table(); + csp_route_print_interfaces(); + + csp_thread_handle_t handle_server; + csp_thread_create(task_server, "SERVER", 1000, NULL, 0, &handle_server); + csp_thread_handle_t handle_client; + csp_thread_create(task_client, "CLIENT", 1000, NULL, 0, &handle_client); + + /* Wait for program to terminate (ctrl + c) */ + while(1) { + csp_sleep_ms(1000000); + } + + return 0; + +} diff --git a/thirdparty/libcsp/examples/python_bindings_example_client.py b/thirdparty/libcsp/examples/python_bindings_example_client.py new file mode 100644 index 00000000..123ce36e --- /dev/null +++ b/thirdparty/libcsp/examples/python_bindings_example_client.py @@ -0,0 +1,42 @@ +#!/usr/bin/python + +# libcsp must be build with at least these options to run this example client: +# ./waf distclean configure build --enable-bindings --enable-crc32 --enable-rdp --enable-if-zmq --with-driver-usart=linux --enable-if-kiss --enable-xtea --enable-if-can --enable-can-socketcan --enable-hmac --enable-examples + +# Can be run from root of libcsp like this: +# LD_LIBRARY_PATH=build PYTHONPATH=bindings/python:build python examples/python_bindings_example_client.py +# + +import os +import time +import libcsp as csp + + +if __name__ == "__main__": + + csp.buffer_init(10, 300) + csp.init(28) + csp.zmqhub_init(28, "localhost") + csp.rtable_set(27, 5, "ZMQHUB") + csp.route_start_task() + + ## allow router task startup + time.sleep(1) + + ## cmp_ident + (rc, host, model, rev, date, time) = csp.cmp_ident(27) + if rc == csp.CSP_ERR_NONE: + print (host, model, rev, date, time) + else: + print ("error in cmp_ident, rc=%i" % (rc)) + + ## transaction + outbuf = bytearray().fromhex('01') + inbuf = bytearray(1) + print ("using csp_transaction to send a single byte") + if csp.transaction(0, 27, 10, 1000, outbuf, inbuf) < 1: + print ("csp_transaction failed") + else: + print ("got reply, data=" + ''.join('{:02x}'.format(x) for x in inbuf)) + + diff --git a/thirdparty/libcsp/examples/python_bindings_example_client_can.py b/thirdparty/libcsp/examples/python_bindings_example_client_can.py new file mode 100644 index 00000000..ec796572 --- /dev/null +++ b/thirdparty/libcsp/examples/python_bindings_example_client_can.py @@ -0,0 +1,30 @@ +#!/usr/bin/python + +# libcsp must be build with at least these options to run this example client: +# ./waf distclean configure build --enable-bindings --enable-crc32 --enable-rdp --enable-if-zmq --with-driver-usart=linux --enable-if-kiss --enable-xtea --enable-if-can --enable-can-socketcan --enable-hmac --enable-examples + +# Can be run from root of libcsp like this: +# LD_LIBRARY_PATH=build PYTHONPATH=bindings/python:build python examples/python_bindings_example_client.py +# + +import os +import time +import libcsp as csp + + +if __name__ == "__main__": + + csp.buffer_init(10, 300) + csp.init(28) + csp.can_socketcan_init("can0") + csp.rtable_set(4, 5, "CAN") + csp.route_start_task() + + ## allow router task startup + time.sleep(1) + + + node = 4 + if csp.ping(node) < 0: + print ("Unable to ping node %d"%(node)) + diff --git a/thirdparty/libcsp/examples/python_bindings_example_server.py b/thirdparty/libcsp/examples/python_bindings_example_server.py new file mode 100644 index 00000000..3cf3f5da --- /dev/null +++ b/thirdparty/libcsp/examples/python_bindings_example_server.py @@ -0,0 +1,72 @@ +#!/usr/bin/python + +# libcsp must be build with at least these options to run this example server: +# ./waf distclean configure build --enable-bindings --enable-crc32 --enable-rdp --enable-if-zmq --with-driver-usart=linux --enable-if-kiss --enable-xtea --enable-if-can --enable-can-socketcan --enable-hmac --enable-examples + +# Can be run from root of libcsp like this: +# LD_LIBRARY_PATH=build PYTHONPATH=bindings/python:build python examples/python_bindings_example_server.py +# + +import os +import time +import sys +import libcsp as csp +import subprocess + +if __name__ == "__main__": + + # start a zmqproxy to transport messages to and from the client + zmqp = subprocess.Popen('build/zmqproxy') + + # init csp + csp.buffer_init(10, 300) + csp.init(27) + csp.zmqhub_init(27, "localhost") + csp.rtable_set(28, 5, "ZMQHUB") + csp.route_start_task() + + # set identity + csp.set_hostname("test_service") + csp.set_model("bindings") + csp.set_revision("1.2.3") + + # and read it back + print (csp.get_hostname()) + print (csp.get_model()) + print (csp.get_revision()) + + # start listening for packets... + sock = csp.socket() + csp.bind(sock, csp.CSP_ANY) + csp.listen(sock) + while True: + conn = csp.accept(sock) + if not conn: + continue + + print ("connection: source=%i:%i, dest=%i:%i" % (csp.conn_src(conn), + csp.conn_sport(conn), + csp.conn_dst(conn), + csp.conn_dport(conn))) + + while True: + packet = csp.read(conn) + if not packet: + break + + if csp.conn_dport(conn) == 10: + data = bytearray(csp.packet_get_data(packet)) + length = csp.packet_get_length(packet) + print ("got packet, len=" + str(length) + ", data=" + ''.join('{:02x}'.format(x) for x in data)) + + data[0] = data[0] + 1 + reply_packet = csp.buffer_get(1) + if reply_packet: + csp.packet_set_data(reply_packet, data) + csp.sendto_reply(packet, reply_packet, csp.CSP_O_NONE) + + csp.buffer_free(packet) + else: + csp.service_handler(conn, packet) + csp.close(conn) + diff --git a/thirdparty/libcsp/examples/simple.c b/thirdparty/libcsp/examples/simple.c new file mode 100644 index 00000000..b996f8c1 --- /dev/null +++ b/thirdparty/libcsp/examples/simple.c @@ -0,0 +1,200 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include +#include +#include + +#include + +/* Using un-exported header file. + * This is allowed since we are still in libcsp */ +#include + +/** Example defines */ +#define MY_ADDRESS 1 // Address of local CSP node +#define MY_PORT 10 // Port to send test traffic to + +CSP_DEFINE_TASK(task_server) { + + /* Create socket without any socket options */ + csp_socket_t *sock = csp_socket(CSP_SO_NONE); + + /* Bind all ports to socket */ + csp_bind(sock, CSP_ANY); + + /* Create 10 connections backlog queue */ + csp_listen(sock, 10); + + /* Pointer to current connection and packet */ + csp_conn_t *conn; + csp_packet_t *packet; + + /* Process incoming connections */ + while (1) { + + /* Wait for connection, 10000 ms timeout */ + if ((conn = csp_accept(sock, 10000)) == NULL) + continue; + + /* Read packets. Timout is 100 ms */ + while ((packet = csp_read(conn, 100)) != NULL) { + switch (csp_conn_dport(conn)) { + case MY_PORT: + /* Process packet here */ + printf("Packet received on MY_PORT: %s\r\n", (char *) packet->data); + csp_buffer_free(packet); + break; + + default: + /* Let the service handler reply pings, buffer use, etc. */ + csp_service_handler(conn, packet); + break; + } + } + + /* Close current connection, and handle next */ + csp_close(conn); + + } + + return CSP_TASK_RETURN; + +} + +CSP_DEFINE_TASK(task_client) { + + csp_packet_t * packet; + csp_conn_t * conn; + + while (1) { + + /** + * Try ping + */ + + csp_sleep_ms(1000); + + int result = csp_ping(MY_ADDRESS, 100, 100, CSP_O_NONE); + printf("Ping result %d [ms]\r\n", result); + + csp_sleep_ms(1000); + + /** + * Try data packet to server + */ + + /* Get packet buffer for data */ + packet = csp_buffer_get(100); + if (packet == NULL) { + /* Could not get buffer element */ + printf("Failed to get buffer element\n"); + return CSP_TASK_RETURN; + } + + /* Connect to host HOST, port PORT with regular UDP-like protocol and 1000 ms timeout */ + conn = csp_connect(CSP_PRIO_NORM, MY_ADDRESS, MY_PORT, 1000, CSP_O_NONE); + if (conn == NULL) { + /* Connect failed */ + printf("Connection failed\n"); + /* Remember to free packet buffer */ + csp_buffer_free(packet); + return CSP_TASK_RETURN; + } + + /* Copy dummy data to packet */ + const char *msg = "Hello World"; + strcpy((char *) packet->data, msg); + + /* Set packet length */ + packet->length = strlen(msg); + + /* Send packet */ + if (!csp_send(conn, packet, 1000)) { + /* Send failed */ + printf("Send failed\n"); + csp_buffer_free(packet); + } + + /* Close connection */ + csp_close(conn); + + } + + return CSP_TASK_RETURN; +} + +int main(int argc, char * argv[]) { + + /** + * Initialise CSP, + * No physical interfaces are initialised in this example, + * so only the loopback interface is registered. + */ + + /* Init buffer system with 10 packets of maximum 300 bytes each */ + printf("Initialising CSP\r\n"); + csp_buffer_init(5, 300); + + /* Init CSP with address MY_ADDRESS */ + csp_init(MY_ADDRESS); + + /* Start router task with 500 word stack, OS task priority 1 */ + csp_route_start_task(500, 1); + + /* Enable debug output from CSP */ + if ((argc > 1) && (strcmp(argv[1], "-v") == 0)) { + printf("Debug enabed\r\n"); + csp_debug_toggle_level(3); + csp_debug_toggle_level(4); + + printf("Conn table\r\n"); + csp_conn_print_table(); + + printf("Route table\r\n"); + csp_route_print_table(); + + printf("Interfaces\r\n"); + csp_route_print_interfaces(); + + } + + /** + * Initialise example threads, using pthreads. + */ + + /* Server */ + printf("Starting Server task\r\n"); + csp_thread_handle_t handle_server; + csp_thread_create(task_server, "SERVER", 1000, NULL, 0, &handle_server); + + /* Client */ + printf("Starting Client task\r\n"); + csp_thread_handle_t handle_client; + csp_thread_create(task_client, "SERVER", 1000, NULL, 0, &handle_client); + + /* Wait for execution to end (ctrl+c) */ + while(1) { + csp_sleep_ms(100000); + } + + return 0; + +} diff --git a/thirdparty/libcsp/examples/zmqproxy.c b/thirdparty/libcsp/examples/zmqproxy.c new file mode 100644 index 00000000..5e259579 --- /dev/null +++ b/thirdparty/libcsp/examples/zmqproxy.c @@ -0,0 +1,82 @@ +#include +#include +#include +#include +#include +#include +#include + +static void * task_capture(void *ctx) { + + /* Subscriber (RX) */ + void *subscriber = zmq_socket(ctx, ZMQ_SUB); + assert(zmq_connect(subscriber, "tcp://localhost:7000") == 0); + assert(zmq_setsockopt(subscriber, ZMQ_SUBSCRIBE, "", 0) == 0); + + while (1) { + zmq_msg_t msg; + zmq_msg_init_size(&msg, 1024); + + /* Receive data */ + if (zmq_msg_recv(&msg, subscriber, 0) < 0) { + zmq_msg_close(&msg); + csp_log_error("ZMQ: %s\r\n", zmq_strerror(zmq_errno())); + continue; + } + + int datalen = zmq_msg_size(&msg); + if (datalen < 5) { + csp_log_warn("ZMQ: Too short datalen: %u\r\n", datalen); + while(zmq_msg_recv(&msg, subscriber, ZMQ_NOBLOCK) > 0) + zmq_msg_close(&msg); + continue; + } + + /* Create new csp packet */ + csp_packet_t * packet = malloc(1024); + if (packet == NULL) { + zmq_msg_close(&msg); + continue; + } + + /* Copy the data from zmq to csp */ + char * satidptr = ((char *) &packet->id) - 1; + memcpy(satidptr, zmq_msg_data(&msg), datalen); + packet->length = datalen - 4 - 1; + + printf("Input: Src %u, Dst %u, Dport %u, Sport %u, Pri %u, Flags 0x%02X, Size %"PRIu16"\r\n", + packet->id.src, packet->id.dst, packet->id.dport, + packet->id.sport, packet->id.pri, packet->id.flags, packet->length); + + free(packet); + zmq_msg_close(&msg); + } +} + +int main(int argc, char ** argv) { + + /** + * ZMQ PROXY + */ + void * ctx = zmq_ctx_new(); + assert(ctx); + + void *frontend = zmq_socket(ctx, ZMQ_XSUB); + assert(frontend); + assert(zmq_bind (frontend, "tcp://*:6000") == 0); + + void *backend = zmq_socket(ctx, ZMQ_XPUB); + assert(backend); + assert(zmq_bind(backend, "tcp://*:7000") == 0); + + pthread_t capworker; + pthread_create(&capworker, NULL, task_capture, ctx); + + printf("Starting ZMQproxy\r\n"); + zmq_proxy(frontend, backend, NULL); + + printf("Closing ZMQproxy\r\n"); + zmq_ctx_destroy(ctx); + return 0; + +} diff --git a/thirdparty/libcsp/include/CMakeLists.txt b/thirdparty/libcsp/include/CMakeLists.txt new file mode 100644 index 00000000..196e26f3 --- /dev/null +++ b/thirdparty/libcsp/include/CMakeLists.txt @@ -0,0 +1,9 @@ +target_include_directories(${LIB_CSP_NAME} PRIVATE + ${CMAKE_CURRENT_SOURCE_DIR} +) + +target_include_directories(${LIB_CSP_NAME} INTERFACE + ${CMAKE_CURRENT_SOURCE_DIR} +) + + diff --git a/thirdparty/libcsp/include/csp/arch/csp_clock.h b/thirdparty/libcsp/include/csp/arch/csp_clock.h new file mode 100644 index 00000000..3c19c887 --- /dev/null +++ b/thirdparty/libcsp/include/csp/arch/csp_clock.h @@ -0,0 +1,60 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef _CSP_CLOCK_H_ +#define _CSP_CLOCK_H_ + +/** + @file + + Clock API. +*/ + +#ifdef __cplusplus +extern "C" { +#endif + +#include + +/** + Cross-platform timestamp. +*/ +typedef struct { + //! Seconds + uint32_t tv_sec; + //! Nano-seconds. + uint32_t tv_nsec; +} csp_timestamp_t; + +/** + Get time - must be implemented by the user. +*/ +__attribute__((weak)) extern void clock_get_time(csp_timestamp_t * time); + +/** + Set time - must be implemented by the user. +*/ +__attribute__((weak)) extern void clock_set_time(csp_timestamp_t * time); + +#ifdef __cplusplus +} /* extern "C" */ +#endif + +#endif // _CSP_CLOCK_H_ diff --git a/thirdparty/libcsp/include/csp/arch/csp_malloc.h b/thirdparty/libcsp/include/csp/arch/csp_malloc.h new file mode 100644 index 00000000..12602d1b --- /dev/null +++ b/thirdparty/libcsp/include/csp/arch/csp_malloc.h @@ -0,0 +1,39 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef _CSP_MALLOC_H_ +#define _CSP_MALLOC_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +#include +#include +#include + +void * csp_malloc(size_t size); +void csp_free(void * ptr); + +#ifdef __cplusplus +} /* extern "C" */ +#endif + +#endif // _CSP_MALLOC_H_ diff --git a/thirdparty/libcsp/include/csp/arch/csp_queue.h b/thirdparty/libcsp/include/csp/arch/csp_queue.h new file mode 100644 index 00000000..3156c05e --- /dev/null +++ b/thirdparty/libcsp/include/csp/arch/csp_queue.h @@ -0,0 +1,49 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef _CSP_QUEUE_H_ +#define _CSP_QUEUE_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +#define CSP_QUEUE_FULL 0 +#define CSP_QUEUE_ERROR 0 +#define CSP_QUEUE_OK 1 +typedef void * csp_queue_handle_t; + +#include +#include + +csp_queue_handle_t csp_queue_create(int length, size_t item_size); +void csp_queue_remove(csp_queue_handle_t queue); +int csp_queue_enqueue(csp_queue_handle_t handle, void *value, uint32_t timeout); +int csp_queue_enqueue_isr(csp_queue_handle_t handle, void * value, CSP_BASE_TYPE * task_woken); +int csp_queue_dequeue(csp_queue_handle_t handle, void *buf, uint32_t timeout); +int csp_queue_dequeue_isr(csp_queue_handle_t handle, void * buf, CSP_BASE_TYPE * task_woken); +int csp_queue_size(csp_queue_handle_t handle); +int csp_queue_size_isr(csp_queue_handle_t handle); + +#ifdef __cplusplus +} /* extern "C" */ +#endif + +#endif // _CSP_QUEUE_H_ diff --git a/thirdparty/libcsp/include/csp/arch/csp_semaphore.h b/thirdparty/libcsp/include/csp/arch/csp_semaphore.h new file mode 100644 index 00000000..c8068da2 --- /dev/null +++ b/thirdparty/libcsp/include/csp/arch/csp_semaphore.h @@ -0,0 +1,109 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef _CSP_SEMAPHORE_H_ +#define _CSP_SEMAPHORE_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +#include + +#include + +/* POSIX interface */ +#if defined(CSP_POSIX) + +#include +#include + +#define CSP_SEMAPHORE_OK 1 +#define CSP_SEMAPHORE_ERROR 2 +#define CSP_MUTEX_OK CSP_SEMAPHORE_OK +#define CSP_MUTEX_ERROR CSP_SEMAPHORE_ERROR + +typedef sem_t csp_bin_sem_handle_t; +typedef pthread_mutex_t csp_mutex_t; + +#endif // CSP_POSIX + +/* MAC OS X interface */ +#if defined(CSP_MACOSX) + +#include +#include "posix/pthread_queue.h" + +#define CSP_SEMAPHORE_OK PTHREAD_QUEUE_OK +#define CSP_SEMAPHORE_ERROR PTHREAD_QUEUE_EMPTY +#define CSP_MUTEX_OK CSP_SEMAPHORE_OK +#define CSP_MUTEX_ERROR CSP_SEMAPHORE_ERROR + +typedef pthread_queue_t * csp_bin_sem_handle_t; +typedef pthread_queue_t * csp_mutex_t; + +#endif // CSP_MACOSX + +#if defined(CSP_WINDOWS) + +#include +#undef interface + +#define CSP_SEMAPHORE_OK 1 +#define CSP_SEMAPHORE_ERROR 2 +#define CSP_MUTEX_OK CSP_SEMAPHORE_OK +#define CSP_MUTEX_ERROR CSP_SEMAPHORE_ERROR + +typedef HANDLE csp_bin_sem_handle_t; +typedef HANDLE csp_mutex_t; + +#endif + +/* FreeRTOS interface */ +#if defined(CSP_FREERTOS) + +#include +#include + +#define CSP_SEMAPHORE_OK pdPASS +#define CSP_SEMAPHORE_ERROR pdFAIL +#define CSP_MUTEX_OK CSP_SEMAPHORE_OK +#define CSP_MUTEX_ERROR CSP_SEMAPHORE_ERROR + +typedef xSemaphoreHandle csp_bin_sem_handle_t; +typedef xSemaphoreHandle csp_mutex_t; + +#endif // CSP_FREERTOS + +int csp_mutex_create(csp_mutex_t * mutex); +int csp_mutex_remove(csp_mutex_t * mutex); +int csp_mutex_lock(csp_mutex_t * mutex, uint32_t timeout); +int csp_mutex_unlock(csp_mutex_t * mutex); +int csp_bin_sem_create(csp_bin_sem_handle_t * sem); +int csp_bin_sem_remove(csp_bin_sem_handle_t * sem); +int csp_bin_sem_wait(csp_bin_sem_handle_t * sem, uint32_t timeout); +int csp_bin_sem_post(csp_bin_sem_handle_t * sem); +int csp_bin_sem_post_isr(csp_bin_sem_handle_t * sem, CSP_BASE_TYPE * task_woken); + +#ifdef __cplusplus +} /* extern "C" */ +#endif + +#endif // _CSP_SEMAPHORE_H_ diff --git a/thirdparty/libcsp/include/csp/arch/csp_system.h b/thirdparty/libcsp/include/csp/arch/csp_system.h new file mode 100644 index 00000000..c6c0e5af --- /dev/null +++ b/thirdparty/libcsp/include/csp/arch/csp_system.h @@ -0,0 +1,74 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef _CSP_SYSTEM_H_ +#define _CSP_SYSTEM_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +#include + +#define COLOR_MASK_COLOR 0x0F +#define COLOR_MASK_MODIFIER 0xF0 + +typedef enum { + /* Colors */ + COLOR_RESET = 0xF0, + COLOR_BLACK = 0x01, + COLOR_RED = 0x02, + COLOR_GREEN = 0x03, + COLOR_YELLOW = 0x04, + COLOR_BLUE = 0x05, + COLOR_MAGENTA = 0x06, + COLOR_CYAN = 0x07, + COLOR_WHITE = 0x08, + /* Modifiers */ + COLOR_NORMAL = 0x0F, + COLOR_BOLD = 0x10, + COLOR_UNDERLINE = 0x20, + COLOR_BLINK = 0x30, + COLOR_HIDE = 0x40, +} csp_color_t; + +/** + * Writes out a task list into a pre-allocate buffer, + * use csp_sys_tasklist_size to get sizeof buffer to allocate + * @param out pointer to output buffer + * @return + */ +int csp_sys_tasklist(char * out); + +/** + * @return Size of tasklist buffer to allocate for the csp_sys_tasklist call + */ +int csp_sys_tasklist_size(void); + +uint32_t csp_sys_memfree(void); +int csp_sys_reboot(void); +int csp_sys_shutdown(void); +void csp_sys_set_color(csp_color_t color); + +#ifdef __cplusplus +} /* extern "C" */ +#endif + +#endif // _CSP_SYSTEM_H_ diff --git a/thirdparty/libcsp/include/csp/arch/csp_thread.h b/thirdparty/libcsp/include/csp/arch/csp_thread.h new file mode 100644 index 00000000..3c6ea171 --- /dev/null +++ b/thirdparty/libcsp/include/csp/arch/csp_thread.h @@ -0,0 +1,100 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef _CSP_THREAD_H_ +#define _CSP_THREAD_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +#include +#include + +/* POSIX interface */ +#if defined(CSP_POSIX) || defined(CSP_MACOSX) + +#include +#include + +#define csp_thread_exit() pthread_exit(NULL) + +typedef pthread_t csp_thread_handle_t; +typedef void * csp_thread_return_t; + +#define CSP_DEFINE_TASK(task_name) csp_thread_return_t task_name(void * param) +#define CSP_TASK_RETURN NULL + +#define csp_sleep_ms(time_ms) usleep(time_ms * 1000); + +#endif // CSP_POSIX + +/* Windows interface */ +#if defined(CSP_WINDOWS) + +#include +#undef interface +#include + +#define csp_thread_exit() _endthreadex(0) + +typedef HANDLE csp_thread_handle_t; +typedef unsigned int csp_thread_return_t; + +#define CSP_DEFINE_TASK(task_name) csp_thread_return_t __attribute__((stdcall)) task_name(void * param) +#define CSP_TASK_RETURN 0 + +#define csp_sleep_ms(time_ms) Sleep(time_ms); + +#endif // CSP_WINDOWS + +/* FreeRTOS interface */ +#if defined(CSP_FREERTOS) + +#include +#include + +#if INCLUDE_vTaskDelete +#define csp_thread_exit() vTaskDelete(NULL) +#else +#define csp_thread_exit() +#endif + +typedef xTaskHandle csp_thread_handle_t; +typedef void csp_thread_return_t; + +#define CSP_DEFINE_TASK(task_name) csp_thread_return_t task_name(void * param) +#define CSP_TASK_RETURN + +#define csp_sleep_ms(time_ms) vTaskDelay(time_ms / portTICK_RATE_MS); + +#endif // CSP_FREERTOS + +#ifndef CSP_WINDOWS +int csp_thread_create(csp_thread_return_t (* routine)(void *), const char * const thread_name, unsigned short stack_depth, void * parameters, unsigned int priority, csp_thread_handle_t * handle); +#else +int csp_thread_create(csp_thread_return_t (* routine)(void *)__attribute__((stdcall)), const char * const thread_name, unsigned short stack_depth, void * parameters, unsigned int priority, csp_thread_handle_t * handle); +#endif + +#ifdef __cplusplus +} /* extern "C" */ +#endif + +#endif // _CSP_THREAD_H_ diff --git a/thirdparty/libcsp/include/csp/arch/csp_time.h b/thirdparty/libcsp/include/csp/arch/csp_time.h new file mode 100644 index 00000000..aa72ab8f --- /dev/null +++ b/thirdparty/libcsp/include/csp/arch/csp_time.h @@ -0,0 +1,57 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef _CSP_TIME_H_ +#define _CSP_TIME_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +#include +#include + +/* Blackfin/x86 on Linux */ +#if defined(CSP_POSIX) + +#include +#include +#include + +#endif // CSP_POSIX + +/* AVR/ARM on FreeRTOS */ +#if defined(CSP_FREERTOS) + +#include +#include + +#endif // CSP_FREERTOS + +uint32_t csp_get_ms(void); +uint32_t csp_get_ms_isr(void); +uint32_t csp_get_s(void); +uint32_t csp_get_s_isr(void); + +#ifdef __cplusplus +} /* extern "C" */ +#endif + +#endif // _CSP_TIME_H_ diff --git a/thirdparty/libcsp/include/csp/arch/posix/pthread_queue.h b/thirdparty/libcsp/include/csp/arch/posix/pthread_queue.h new file mode 100644 index 00000000..44ef596e --- /dev/null +++ b/thirdparty/libcsp/include/csp/arch/posix/pthread_queue.h @@ -0,0 +1,118 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef _PTHREAD_QUEUE_H_ +#define _PTHREAD_QUEUE_H_ + +/** + @file + + Queue implemented using pthread locks and conds. + + Inspired by c-pthread-queue by Matthew Dickinson: http://code.google.com/p/c-pthread-queue/ +*/ + +#ifdef __cplusplus +extern "C" { +#endif + +#include +#include +#include + +#include + +/** + Queue error codes. + @{ +*/ +/** + General error code - something went wrong. +*/ +#define PTHREAD_QUEUE_ERROR CSP_QUEUE_ERROR +/** + Queue is empty - cannot extract element. +*/ +#define PTHREAD_QUEUE_EMPTY CSP_QUEUE_ERROR +/** + Queue is full - cannot insert element. +*/ +#define PTHREAD_QUEUE_FULL CSP_QUEUE_ERROR +/** + Ok - no error. +*/ +#define PTHREAD_QUEUE_OK CSP_QUEUE_OK +/** @{ */ + +/** + Queue handle. +*/ +typedef struct pthread_queue_s { + //! Memory area. + void * buffer; + //! Memory size. + int size; + //! Item/element size. + int item_size; + //! Items/elements in queue. + int items; + //! Insert point. + int in; + //! Extract point. + int out; + //! Lock. + pthread_mutex_t mutex; + //! Wait because queue is full (insert). + pthread_cond_t cond_full; + //! Wait because queue is empty (extract). + pthread_cond_t cond_empty; +} pthread_queue_t; + +/** + Create queue. +*/ +pthread_queue_t * pthread_queue_create(int length, size_t item_size); + +/** + Delete queue. +*/ +void pthread_queue_delete(pthread_queue_t * q); + +/** + Enqueue/insert element. +*/ +int pthread_queue_enqueue(pthread_queue_t * queue, void * value, uint32_t timeout); + +/** + Dequeue/extract element. +*/ +int pthread_queue_dequeue(pthread_queue_t * queue, void * buf, uint32_t timeout); + +/** + Return number of elements in the queue. +*/ +int pthread_queue_items(pthread_queue_t * queue); + +#ifdef __cplusplus +} /* extern "C" */ +#endif + +#endif // _PTHREAD_QUEUE_H_ + diff --git a/thirdparty/libcsp/include/csp/crypto/csp_hmac.h b/thirdparty/libcsp/include/csp/crypto/csp_hmac.h new file mode 100644 index 00000000..8c3f5d6a --- /dev/null +++ b/thirdparty/libcsp/include/csp/crypto/csp_hmac.h @@ -0,0 +1,73 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef _CSP_HMAC_H_ +#define _CSP_HMAC_H_ + +#include + +#ifdef __cplusplus +extern "C" { +#endif + +#define CSP_HMAC_LENGTH 4 + +/** + * Append HMAC to packet + * @param packet Pointer to packet + * @param include_header use header in hmac calculation (this will not modify the flags field) + * @return 0 on success, negative on failure + */ +int csp_hmac_append(csp_packet_t * packet, bool include_header); + +/** + * Verify HMAC of packet + * @param packet Pointer to packet + * @param include_header use header in hmac calculation (this will not modify the flags field) + * @return 0 on success, negative on failure + */ +int csp_hmac_verify(csp_packet_t * packet, bool include_header); + +/** + * Calculate HMAC on buffer + * + * This function is used by append/verify but cal also be called separately. + * @param key HMAC key + * @param keylen HMAC key length + * @param data pointer to data + * @param datalen lehgth of data + * @param hmac output HMAC calculation (CSP_HMAC_LENGTH) + * @return 0 on success, negative on failure + */ +int csp_hmac_memory(const uint8_t * key, uint32_t keylen, const uint8_t * data, uint32_t datalen, uint8_t * hmac); + +/** + * Save a copy of the key string for use by the append/verify functions + * @param key HMAC key + * @param keylen HMAC key length + * @return Always returns 0 + */ +int csp_hmac_set_key(char * key, uint32_t keylen); + +#ifdef __cplusplus +} /* extern "C" */ +#endif + +#endif // _CSP_HMAC_H_ diff --git a/thirdparty/libcsp/include/csp/crypto/csp_sha1.h b/thirdparty/libcsp/include/csp/crypto/csp_sha1.h new file mode 100644 index 00000000..aa7e7a0d --- /dev/null +++ b/thirdparty/libcsp/include/csp/crypto/csp_sha1.h @@ -0,0 +1,81 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef _CSP_SHA1_H_ +#define _CSP_SHA1_H_ + +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/* The SHA1 block and message digest size in bytes */ +#define SHA1_BLOCKSIZE 64 +#define SHA1_DIGESTSIZE 20 + +/** + SHA1 state structure +*/ +typedef struct { + //! Internal SHA1 state. + uint64_t length; + //! Internal SHA1 state. + uint32_t state[5]; + //! Internal SHA1 state. + uint32_t curlen; + //! Internal SHA1 state. + uint8_t buf[SHA1_BLOCKSIZE]; +} csp_sha1_state; + +/** + * Initialize the hash state + * @param sha1 The hash state you wish to initialize + */ +void csp_sha1_init(csp_sha1_state * sha1); + +/** + * Process a block of memory though the hash + * @param sha1 The hash state + * @param in The data to hash + * @param inlen The length of the data (octets) + */ +void csp_sha1_process(csp_sha1_state * sha1, const uint8_t * in, uint32_t inlen); + +/** + * Terminate the hash to get the digest + * @param sha1 The hash state + * @param out [out] The destination of the hash (20 bytes) + */ +void csp_sha1_done(csp_sha1_state * sha1, uint8_t * out); + +/** + * Calculate SHA1 hash of block of memory. + * @param msg Pointer to message buffer + * @param len Length of message + * @param sha1 Pointer to SHA1 output buffer. Must be 20 bytes or more! + */ +void csp_sha1_memory(const uint8_t * msg, uint32_t len, uint8_t * hash); + +#ifdef __cplusplus +} /* extern "C" */ +#endif + +#endif // _CSP_SHA1_H_ diff --git a/thirdparty/libcsp/include/csp/crypto/csp_xtea.h b/thirdparty/libcsp/include/csp/crypto/csp_xtea.h new file mode 100644 index 00000000..f740b8d5 --- /dev/null +++ b/thirdparty/libcsp/include/csp/crypto/csp_xtea.h @@ -0,0 +1,52 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef _CSP_XTEA_H_ +#define _CSP_XTEA_H_ + +#include + +#ifdef __cplusplus +extern "C" { +#endif + +#define CSP_XTEA_IV_LENGTH 8 + +/** + * XTEA encrypt byte array + * @param plain Pointer to plain text + * @param len Length of plain text + * @param iv Initialization vector + */ +int csp_xtea_encrypt(uint8_t * plain, const uint32_t len, uint32_t iv[2]); + +/** + * Decrypt XTEA encrypted byte array + * @param cipher Pointer to cipher text + * @param len Length of plain text + * @param iv Initialization vector + */ +int csp_xtea_decrypt(uint8_t * cipher, const uint32_t len, uint32_t iv[2]); + +#ifdef __cplusplus +} /* extern "C" */ +#endif + +#endif // _CSP_XTEA_H_ diff --git a/thirdparty/libcsp/include/csp/csp.h b/thirdparty/libcsp/include/csp/csp.h new file mode 100644 index 00000000..6962195b --- /dev/null +++ b/thirdparty/libcsp/include/csp/csp.h @@ -0,0 +1,545 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef _CSP_H_ +#define _CSP_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +/* Includes */ +#include + +#include + +/* CSP includes */ +#include "csp_types.h" +#include "csp_platform.h" +#include "csp_error.h" +#include "csp_debug.h" +#include "csp_buffer.h" +#include "csp_rtable.h" +#include "csp_iflist.h" + +/** csp_init + * Start up the can-space protocol + * @param my_node_address The CSP node address + */ +int csp_init(uint8_t my_node_address); + +/** csp_set_address + * Set the systems own address + * @param addr The new address of the system + */ +void csp_set_address(uint8_t addr); + +/** csp_get_address + * Get the systems own address + * @return The current address of the system + */ +uint8_t csp_get_address(void); + +/** csp_set_hostname + * Set subsystem hostname. + * This function takes a pointer to a string, which should remain static + * @param hostname Hostname to set + */ +void csp_set_hostname(const char *hostname); + +/** csp_get_hostname + * Get current subsystem hostname. + * @return Pointer to char array with current hostname. + */ +const char *csp_get_hostname(void); + +/** csp_set_model + * Set subsystem model name. + * This function takes a pointer to a string, which should remain static + * @param model Model name to set + */ +void csp_set_model(const char *model); + +/** csp_get_model + * Get current model name. + * @return Pointer to char array with current model name. + */ +const char *csp_get_model(void); + +/** csp_set_revision + * Set subsystem revision. This can be used to override the CMP revision field. + * This function takes a pointer to a string, which should remain static + * @param revision Revision name to set + */ +void csp_set_revision(const char *revision); + +/** csp_get_revision + * Get subsystem revision. + * @return Pointer to char array with software revision. + */ +const char *csp_get_revision(void); + +/** csp_socket + * Create CSP socket endpoint + * @param opts Socket options + * @return Pointer to socket on success, NULL on failure + */ +csp_socket_t *csp_socket(uint32_t opts); + +/** + * Wait for a new connection on a socket created by csp_socket + * @param socket Socket to accept connections on + * @param timeout use CSP_MAX_DELAY for infinite timeout + * @return Return pointer to csp_conn_t or NULL if timeout was reached + */ +csp_conn_t *csp_accept(csp_socket_t *socket, uint32_t timeout); + +/** + * Read data from a connection + * This fuction uses the RX queue of a connection to receive a packet + * If no packet is available and a timeout has been specified + * The call will block. + * Do NOT call this from ISR + * @param conn pointer to connection + * @param timeout timeout in ms, use CSP_MAX_DELAY for infinite blocking time + * @return Returns pointer to csp_packet_t, which you MUST free yourself, either by calling csp_buffer_free() or reusing the buffer for a new csp_send. + */ +csp_packet_t *csp_read(csp_conn_t *conn, uint32_t timeout); + +/** + * Send a packet on an already established connection + * @param conn pointer to connection + * @param packet pointer to packet, + * @param timeout a timeout to wait for TX to complete. NOTE: not all underlying drivers supports flow-control. + * @return returns 1 if successful and 0 otherwise. you MUST free the frame yourself if the transmission was not successful. + */ +int csp_send(csp_conn_t *conn, csp_packet_t *packet, uint32_t timeout); + +/** + * Send a packet on an already established connection, and change the default priority of the connection + * + * @note When using this function, the priority of the connection will change. If you need to change it back + * use another call to csp_send_prio, or ensure that all packets sent on a given connection is using send_prio call. + * + * @param prio csp priority + * @param conn pointer to connection + * @param packet pointer to packet, + * @param timeout a timeout to wait for TX to complete. NOTE: not all underlying drivers supports flow-control. + * @return returns 1 if successful and 0 otherwise. you MUST free the frame yourself if the transmission was not successful. + */ +int csp_send_prio(uint8_t prio, csp_conn_t *conn, csp_packet_t *packet, uint32_t timeout); + +/** + * Perform an entire request/reply transaction + * Copies both input buffer and reply to output buffeer. + * Also makes the connection and closes it again + * @param prio CSP Prio + * @param dest CSP Dest + * @param port CSP Port + * @param timeout timeout in ms + * @param outbuf pointer to outgoing data buffer + * @param outlen length of request to send + * @param inbuf pointer to incoming data buffer + * @param inlen length of expected reply, -1 for unknown size (note inbuf MUST be large enough) + * @return Return 1 or reply size if successful, 0 if error or incoming length does not match or -1 if timeout was reached + */ +int csp_transaction(uint8_t prio, uint8_t dest, uint8_t port, uint32_t timeout, void *outbuf, int outlen, void *inbuf, int inlen); + +/** + * Perform an entire request/reply transaction + * Copies both input buffer and reply to output buffeer. + * Also makes the connection and closes it again + * @param prio CSP Prio + * @param dest CSP Dest + * @param port CSP Port + * @param timeout timeout in ms + * @param outbuf pointer to outgoing data buffer + * @param outlen length of request to send + * @param inbuf pointer to incoming data buffer + * @param inlen length of expected reply, -1 for unknown size (note inbuf MUST be large enough) + * @param opts Connection options. + * @return Return 1 or reply size if successful, 0 if error or incoming length does not match or -1 if timeout was reached + */ +int csp_transaction2(uint8_t prio, uint8_t dest, uint8_t port, uint32_t timeout, void *outbuf, int outlen, void *inbuf, int inlen, uint32_t opts); + +/** + * Use an existing connection to perform a transaction, + * This is only possible if the next packet is on the same port and destination! + * @param conn pointer to connection structure + * @param timeout timeout in ms + * @param outbuf pointer to outgoing data buffer + * @param outlen length of request to send + * @param inbuf pointer to incoming data buffer + * @param inlen length of expected reply, -1 for unknown size (note inbuf MUST be large enough) + * @return + */ +int csp_transaction_persistent(csp_conn_t *conn, uint32_t timeout, void *outbuf, int outlen, void *inbuf, int inlen); + +/** + * Read data from a connection-less server socket + * This fuction uses the socket directly to receive a frame + * If no packet is available and a timeout has been specified the call will block. + * Do NOT call this from ISR + * @return Returns pointer to csp_packet_t, which you MUST free yourself, either by calling csp_buffer_free() or reusing the buffer for a new csp_send. + */ +csp_packet_t *csp_recvfrom(csp_socket_t *socket, uint32_t timeout); + +/** + * Send a packet without previously opening a connection + * @param prio CSP_PRIO_x + * @param dest destination node + * @param dport destination port + * @param src_port source port + * @param opts CSP_O_x + * @param packet pointer to packet + * @param timeout timeout used by interfaces with blocking send + * @return -1 if error (you must free packet), 0 if OK (you must discard pointer) + */ +int csp_sendto(uint8_t prio, uint8_t dest, uint8_t dport, uint8_t src_port, uint32_t opts, csp_packet_t *packet, uint32_t timeout); + +/** + * Send a packet as a direct reply to the source of an incoming packet, + * but still without holding an entire connection + * @param request_packet pointer to packet to reply to + * @param reply_packet actual reply data + * @param opts CSP_O_x + * @param timeout timeout used by interfaces with blocking send + * @return -1 if error (you must free packet), 0 if OK (you must discard pointer) + */ +int csp_sendto_reply(csp_packet_t * request_packet, csp_packet_t * reply_packet, uint32_t opts, uint32_t timeout); + +/** csp_connect + * Used to establish outgoing connections + * This function searches the port table for free slots and finds an unused + * connection from the connection pool + * There is no handshake in the CSP protocol + * @param prio Connection priority. + * @param dest Destination address. + * @param dport Destination port. + * @param timeout Timeout in ms. + * @param opts Connection options. + * @return a pointer to a new connection or NULL + */ +csp_conn_t *csp_connect(uint8_t prio, uint8_t dest, uint8_t dport, uint32_t timeout, uint32_t opts); + +/** csp_close + * Closes a given connection and frees buffers used. + * @param conn pointer to connection structure + * @return CSP_ERR_NONE if connection was closed. Otherwise, an err code is returned. + */ +int csp_close(csp_conn_t *conn); + +/** + * @param conn pointer to connection structure + * @return destination port of an incoming connection + */ +int csp_conn_dport(csp_conn_t *conn); + +/** + * @param conn pointer to connection structure + * @return source port of an incoming connection + */ +int csp_conn_sport(csp_conn_t *conn); + +/** + * @param conn pointer to connection structure + * @return destination address of an incoming connection + */ +int csp_conn_dst(csp_conn_t *conn); + +/** + * @param conn pointer to connection structure + * @return source address of an incoming connection + */ +int csp_conn_src(csp_conn_t *conn); + +/** + * @param conn pointer to connection structure + * @return flags field of an incoming connection + */ +int csp_conn_flags(csp_conn_t *conn); + +/** + * Set socket to listen for incoming connections + * @param socket Socket to enable listening on + * @param conn_queue_length Lenght of backlog connection queue + * @return 0 on success, -1 on error. + */ +int csp_listen(csp_socket_t *socket, size_t conn_queue_length); + +/** + * Bind port to socket + * @param socket Socket to bind port to + * @param port Port number to bind + * @return 0 on success, -1 on error. + */ +int csp_bind(csp_socket_t *socket, uint8_t port); + +/** + * Start the router task. + * @param task_stack_size The number of portStackType to allocate. This only affects FreeRTOS systems. + * @param priority The OS task priority of the router + */ +int csp_route_start_task(unsigned int task_stack_size, unsigned int priority); + +/** + * Call the router worker function manually (without the router task) + * This must be run inside a loop or called periodically for the csp router to work. + * Use this function instead of calling and starting the router task. + * @param timeout max blocking time + * @return -1 if no packet was processed, 0 otherwise + */ +int csp_route_work(uint32_t timeout); + +/** + * Start the bridge task. + * @param task_stack_size The number of portStackType to allocate. This only affects FreeRTOS systems. + * @param priority The OS task priority of the router + * @param _if_a pointer to first side + * @param _if_b pointer to second side + * @return CSP_ERR type + */ +int csp_bridge_start(unsigned int task_stack_size, unsigned int task_priority, csp_iface_t * _if_a, csp_iface_t * _if_b); + +/** + * Enable promiscuous mode packet queue + * This function is used to enable promiscuous mode for the router. + * If enabled, a copy of all incoming packets are placed in a queue + * that can be read with csp_promisc_get(). Not all interface drivers + * support promiscuous mode. + * + * @param buf_size Size of buffer for incoming packets + */ +int csp_promisc_enable(unsigned int buf_size); + +/** + * Disable promiscuous mode. + * If the queue was initialised prior to this, it can be re-enabled + * by calling promisc_enable(0) + */ +void csp_promisc_disable(void); + +/** + * Get packet from promiscuous mode packet queue + * Returns the first packet from the promiscuous mode packet queue. + * The queue is FIFO, so the returned packet is the oldest one + * in the queue. + * + * @param timeout Timeout in ms to wait for a new packet + */ +csp_packet_t *csp_promisc_read(uint32_t timeout); + +/** + * Send multiple packets using the simple fragmentation protocol + * CSP will add total size and offset to all packets + * This can be read by the client using the csp_sfp_recv, if the CSP_FFRAG flag is set + * @param conn pointer to connection + * @param data pointer to data to send + * @param totalsize size of data to send + * @param mtu maximum transfer unit + * @param timeout timeout in ms to wait for csp_send() + * @return 0 if OK, -1 if ERR + */ +int csp_sfp_send(csp_conn_t * conn, const void * data, int totalsize, int mtu, uint32_t timeout); + +/** + * Same as csp_sfp_send but with option to supply your own memcpy function. + * This is usefull if you wish to send data stored in flash memory or another location + * @param conn pointer to connection + * @param data pointer to data to send + * @param totalsize size of data to send + * @param mtu maximum transfer unit + * @param timeout timeout in ms to wait for csp_send() + * @param memcpyfcn, pointer to memcpy function + * @return 0 if OK, -1 if ERR + */ +int csp_sfp_send_own_memcpy(csp_conn_t * conn, const void * data, int totalsize, int mtu, uint32_t timeout, void * (*memcpyfcn)(void *, const void *, size_t)); + +/** + * This is the counterpart to the csp_sfp_send function + * @param conn pointer to active conn, on which you expect to receive sfp packed data + * @param dataout pointer to NULL pointer, whill be overwritten with malloc pointer + * @param datasize actual size of received data + * @param timeout timeout in ms to wait for csp_recv() + * @return 0 if OK, -1 if ERR + */ +int csp_sfp_recv(csp_conn_t * conn, void ** dataout, int * datasize, uint32_t timeout); + +/** + * This is the counterpart to the csp_sfp_send function + * @param conn pointer to active conn, on which you expect to receive sfp packed data + * @param dataout pointer to NULL pointer, whill be overwritten with malloc pointer + * @param datasize actual size of received data + * @param timeout timeout in ms to wait for csp_recv() + * @param first_packet This is a pointer to the first SFP packet (previously received with csp_read) + * @return 0 if OK, -1 if ERR + */ +int csp_sfp_recv_fp(csp_conn_t * conn, void ** dataout, int * datasize, uint32_t timeout, csp_packet_t * first_packet); + +/** + * If the given packet is a service-request (that is uses one of the csp service ports) + * it will be handled according to the CSP service handler. + * This function will either use the packet buffer or delete it, + * so this function is typically called in the last "default" clause of + * a switch/case statement in a csp_listener task. + * In order to listen to csp service ports, bind your listener to the CSP_ANY port. + * This function may only be called from task context. + * @param conn Pointer to the new connection + * @param packet Pointer to the first packet, obtained by using csp_read() + */ +void csp_service_handler(csp_conn_t *conn, csp_packet_t *packet); + +/** + * Send a single ping/echo packet + * @param node node id + * @param timeout timeout in ms + * @param size size of packet to transmit + * @param conn_options csp connection options + * @return >0 = Echo time in ms, -1 = ERR + */ +int csp_ping(uint8_t node, uint32_t timeout, unsigned int size, uint8_t conn_options); + +/** + * Send a single ping/echo packet without waiting for reply + * @param node node id + */ +void csp_ping_noreply(uint8_t node); + +/** + * Request process list. + * @note This is only available for FreeRTOS systems + * @param node node id + * @param timeout timeout in ms + */ +void csp_ps(uint8_t node, uint32_t timeout); + +/** + * Request amount of free memory + * @param node node id + * @param timeout timeout in ms + */ +void csp_memfree(uint8_t node, uint32_t timeout); + +/** + * Request number of free buffer elements + * @param node node id + * @param timeout timeout in ms + */ +void csp_buf_free(uint8_t node, uint32_t timeout); + +/** + * Reboot subsystem + * @param node node id + */ +void csp_reboot(uint8_t node); + +/** + * Shutdown subsystem + * @param node node id + */ +void csp_shutdown(uint8_t node); + +/** + * Request subsystem uptime + * @param node node id + * @param timeout timeout in ms + */ +void csp_uptime(uint8_t node, uint32_t timeout); + +/** + * Set RDP options + * @param window_size Window size + * @param conn_timeout_ms Connection timeout in ms + * @param packet_timeout_ms Packet timeout in ms + * @param delayed_acks Enable/disable delayed acknowledgements + * @param ack_timeout Acknowledgement timeout when delayed ACKs is enabled + * @param ack_delay_count Send acknowledgement for every ack_delay_count packets + */ +void csp_rdp_set_opt(unsigned int window_size, unsigned int conn_timeout_ms, + unsigned int packet_timeout_ms, unsigned int delayed_acks, + unsigned int ack_timeout, unsigned int ack_delay_count); + +/** + * Get RDP options + * @param window_size Window size + * @param conn_timeout_ms Connection timeout in ms + * @param packet_timeout_ms Packet timeout in ms + * @param delayed_acks Enable/disable delayed acknowledgements + * @param ack_timeout Acknowledgement timeout when delayed ACKs is enabled + * @param ack_delay_count Send acknowledgement for every ack_delay_count packets + */ +void csp_rdp_get_opt(unsigned int *window_size, unsigned int *conn_timeout_ms, + unsigned int *packet_timeout_ms, unsigned int *delayed_acks, + unsigned int *ack_timeout, unsigned int *ack_delay_count); + +/** + * Set XTEA key + * @param key Pointer to key array + * @param keylen Length of key + * @return 0 if key was successfully set, -1 otherwise + */ +int csp_xtea_set_key(char *key, uint32_t keylen); + +/** + * Set HMAC key + * @param key Pointer to key array + * @param keylen Length of key + * @return 0 if key was successfully set, -1 otherwise + */ +int csp_hmac_set_key(char *key, uint32_t keylen); + +/** + * Print connection table + */ +void csp_conn_print_table(void); +int csp_conn_print_table_str(char * str_buf, int str_size); + +/** + * Print buffer usage table + */ +void csp_buffer_print_table(void); + +/** + * Hex dump to stdout + */ +void csp_hex_dump(const char *desc, void *addr, int len); + +#ifdef __AVR__ +typedef uint32_t csp_memptr_t; +#else +typedef void * csp_memptr_t; +#endif + +typedef csp_memptr_t (*csp_memcpy_fnc_t)(csp_memptr_t, const csp_memptr_t, size_t); +void csp_cmp_set_memcpy(csp_memcpy_fnc_t fnc); + +/** + * Set csp_debug hook function + * @param f Hook function + */ +#include +typedef void (*csp_debug_hook_func_t)(csp_debug_level_t level, const char *format, va_list args); +void csp_debug_hook_set(csp_debug_hook_func_t f); + +#ifdef __cplusplus +} /* extern "C" */ +#endif + +#endif // _CSP_H_ diff --git a/thirdparty/libcsp/include/csp/csp_autoconfig.h b/thirdparty/libcsp/include/csp/csp_autoconfig.h new file mode 100644 index 00000000..703f3754 --- /dev/null +++ b/thirdparty/libcsp/include/csp/csp_autoconfig.h @@ -0,0 +1,48 @@ +/* + * csp_autoconfig.h + * + * Created on: 20.11.2020 + * Author: jakob + */ + +#ifndef GOMSPACE_LIBCSP_INCLUDE_CSP_CSP_AUTOCONFIG_H_ +#define GOMSPACE_LIBCSP_INCLUDE_CSP_CSP_AUTOCONFIG_H_ + +#define ENABLE_NANOPOWER2_CLIENT 1 +#define GIT_REV "unknown" +/* #undef CSP_FREERTOS */ +#define CSP_POSIX 1 +/* #undef CSP_WINDOWS */ +/* #undef CSP_MACOSX */ +#define HAVE_LIBZMQ 1 +#define CSP_DEBUG 1 +#define CSP_USE_RDP 1 +#define CSP_USE_CRC32 1 +#define CSP_USE_HMAC 1 +#define CSP_USE_XTEA 1 +#define CSP_USE_PROMISC 1 +#define CSP_USE_QOS 1 +/* #undef CSP_USE_DEDUP */ +/* #undef CSP_USE_INIT_SHUTDOWN */ +#define CSP_USE_CAN 1 +/* #define CSP_USE_I2C 1 */ +/* #define CSP_USE_KISS 1 */ +/* #define CSP_USE_ZMQHUB 1 */ +#define CSP_CONN_MAX 10 +#define CSP_CONN_QUEUE_LENGTH 100 +#define CSP_FIFO_INPUT 100 +#define CSP_MAX_BIND_PORT 31 +#define CSP_RDP_MAX_WINDOW 20 +#define CSP_PADDING_BYTES 8 +#define CSP_CONNECTION_SO 64 +#define CSP_LOG_LEVEL_DEBUG 1 +#define CSP_LOG_LEVEL_INFO 1 +#define CSP_LOG_LEVEL_WARN 1 +#define CSP_LOG_LEVEL_ERROR 1 +#define CSP_LITTLE_ENDIAN 1 +/* #undef CSP_BIG_ENDIAN */ +#define CSP_HAVE_STDBOOL_H 1 +/* #define CSP_HAVE_LIBSOCKETCAN 1 */ +#define LIBCSP_VERSION "1.5" + +#endif /* GOMSPACE_LIBCSP_INCLUDE_CSP_CSP_AUTOCONFIG_H_ */ diff --git a/thirdparty/libcsp/include/csp/csp_buffer.h b/thirdparty/libcsp/include/csp/csp_buffer.h new file mode 100644 index 00000000..9ed6df77 --- /dev/null +++ b/thirdparty/libcsp/include/csp/csp_buffer.h @@ -0,0 +1,92 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef _CSP_BUFFER_H_ +#define _CSP_BUFFER_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * Start the buffer handling system + * You must specify the number for buffers and the size. All buffers are fixed + * size so you must specify the size of your largest buffer. + * + * @param count Number of buffers to allocate + * @param size Buffer size in bytes. + * + * @return CSP_ERR_NONE if malloc() succeeded, CSP_ERR message otherwise. + */ +int csp_buffer_init(int count, int size); + +/** + * Get a reference to a free buffer. This function can only be called + * from task context. + * + * @param size Specify what data-size you will put in the buffer + * @return pointer to a free csp_packet_t or NULL if out of memory + */ +void * csp_buffer_get(size_t size); + +/** + * Get a reference to a free buffer. This function can only be called + * from interrupt context. + * + * @param buf_size Specify what data-size you will put in the buffer + * @return pointer to a free csp_packet_t or NULL if out of memory + */ +void * csp_buffer_get_isr(size_t buf_size); + +/** + * Free a buffer after use. + * @param packet pointer to memory area, must be acquired by csp_buffer_get(). + */ +void csp_buffer_free(void *packet); + +/** + * Free a buffer after use in ISR context. + * @param packet pointer to memory area, must be acquired by csp_buffer_get(). + */ +void csp_buffer_free_isr(void *packet); + +/** + * Clone an existing packet and increase/decrease cloned packet size. + * @param buffer Existing buffer to clone. + */ +void * csp_buffer_clone(void *buffer); + +/** + * Return how many buffers that are currently free. + * @return number of free buffers + */ +int csp_buffer_remaining(void); + +/** + * Return the size of the CSP buffers + * @return size of CSP buffers + */ +int csp_buffer_size(void); + +#ifdef __cplusplus +} /* extern "C" */ +#endif + +#endif /* _CSP_BUFFER_H_ */ diff --git a/thirdparty/libcsp/include/csp/csp_cmp.h b/thirdparty/libcsp/include/csp/csp_cmp.h new file mode 100644 index 00000000..114a8eab --- /dev/null +++ b/thirdparty/libcsp/include/csp/csp_cmp.h @@ -0,0 +1,189 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef _CSP_CMP_H_ +#define _CSP_CMP_H_ + +/** + @file + CSP management protocol (CMP). +*/ + +#ifdef __cplusplus +extern "C" { +#endif + +#include +#include +#include + +/** + CMP type. + @{ +*/ +/** + CMP request. +*/ +#define CSP_CMP_REQUEST 0x00 +/** + CMP reply. +*/ +#define CSP_CMP_REPLY 0xff +/**@}*/ + +/** + CMP requests. + @{ +*/ +/** + CMP request codes. +*/ +/** + Request identification, compile time, revision, name. +*/ +#define CSP_CMP_IDENT 1 +/** + Set/configure routing. +*/ +#define CSP_CMP_ROUTE_SET 2 +/** + Request interface statistics. +*/ +#define CSP_CMP_IF_STATS 3 +/** + Peek/read data from memory. +*/ +#define CSP_CMP_PEEK 4 +/** + Poke/write data from memory. +*/ +#define CSP_CMP_POKE 5 +/** + Get/set clock. +*/ +#define CSP_CMP_CLOCK 6 +/**@}*/ + +/** + CMP identification - max revision length. +*/ +#define CSP_CMP_IDENT_REV_LEN 20 +/** + CMP identification - max date length. +*/ +#define CSP_CMP_IDENT_DATE_LEN 12 +/** + CMP identification - max time length. +*/ +#define CSP_CMP_IDENT_TIME_LEN 9 + +/** + CMP interface statistics - max interface name length. +*/ +#define CSP_CMP_ROUTE_IFACE_LEN 11 + +/** + CMP peek/read memeory - max read length. +*/ +#define CSP_CMP_PEEK_MAX_LEN 200 + +/** + CMP poke/write memeory - max write length. +*/ +#define CSP_CMP_POKE_MAX_LEN 200 + +/** + CSP management protocol description. +*/ +struct csp_cmp_message { + //! CMP request type. + uint8_t type; + //! CMP request code. + uint8_t code; + union { + struct { + char hostname[CSP_HOSTNAME_LEN]; + char model[CSP_MODEL_LEN]; + char revision[CSP_CMP_IDENT_REV_LEN]; + char date[CSP_CMP_IDENT_DATE_LEN]; + char time[CSP_CMP_IDENT_TIME_LEN]; + } ident; + struct { + uint8_t dest_node; + uint8_t next_hop_mac; + char interface[CSP_CMP_ROUTE_IFACE_LEN]; + } route_set; + struct __attribute__((__packed__)) { + char interface[CSP_CMP_ROUTE_IFACE_LEN]; + uint32_t tx; + uint32_t rx; + uint32_t tx_error; + uint32_t rx_error; + uint32_t drop; + uint32_t autherr; + uint32_t frame; + uint32_t txbytes; + uint32_t rxbytes; + uint32_t irq; + } if_stats; + struct { + uint32_t addr; + uint8_t len; + char data[CSP_CMP_PEEK_MAX_LEN]; + } peek; + struct { + uint32_t addr; + uint8_t len; + char data[CSP_CMP_POKE_MAX_LEN]; + } poke; + csp_timestamp_t clock; + }; +} __attribute__ ((packed)); + +/** + Macro for calculating size of management message. +*/ +#define CMP_SIZE(_memb) (sizeof(((struct csp_cmp_message *)0)->_memb) + sizeof(uint8_t) + sizeof(uint8_t)) + +/** + Generic send management message request. +*/ +int csp_cmp(uint8_t node, uint32_t timeout, uint8_t code, int membsize, struct csp_cmp_message *msg); + +/** + Macro for defining management handling function. +*/ +#define CMP_MESSAGE(_code, _memb) \ +static inline int csp_cmp_##_memb(uint8_t node, uint32_t timeout, struct csp_cmp_message *msg) { \ + return csp_cmp(node, timeout, _code, CMP_SIZE(_memb), msg); \ +} + +CMP_MESSAGE(CSP_CMP_IDENT, ident) +CMP_MESSAGE(CSP_CMP_ROUTE_SET, route_set) +CMP_MESSAGE(CSP_CMP_IF_STATS, if_stats) +CMP_MESSAGE(CSP_CMP_PEEK, peek) +CMP_MESSAGE(CSP_CMP_POKE, poke) +CMP_MESSAGE(CSP_CMP_CLOCK, clock) + +#ifdef __cplusplus +} /* extern "C" */ +#endif + +#endif // _CSP_CMP_H_ diff --git a/thirdparty/libcsp/include/csp/csp_crc32.h b/thirdparty/libcsp/include/csp/csp_crc32.h new file mode 100644 index 00000000..a474eaf8 --- /dev/null +++ b/thirdparty/libcsp/include/csp/csp_crc32.h @@ -0,0 +1,63 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef _CSP_CRC32_H_ +#define _CSP_CRC32_H_ + +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * Generate precomputed CRC32 table + */ +void csp_crc32_gentab(void); + +/** + * Append CRC32 checksum to packet + * @param packet Packet to append checksum + * @param include_header use header in calculation (this will not modify the flags field) + * @return 0 on success, -1 on error + */ +int csp_crc32_append(csp_packet_t * packet, bool include_header); + +/** + * Verify CRC32 checksum on packet + * @param packet Packet to verify + * @param include_header use header in calculation (this will not modify the flags field) + * @return 0 if checksum is valid, -1 otherwise + */ +int csp_crc32_verify(csp_packet_t * packet, bool include_header); + +/** + * Calculate checksum for a given memory area + * @param data pointer to memory + * @param length length of memory to do checksum on + * @return return uint32_t checksum + */ +uint32_t csp_crc32_memory(const uint8_t * data, uint32_t length); + +#ifdef __cplusplus +} /* extern "C" */ +#endif + +#endif /* _CSP_CRC32_H_ */ diff --git a/thirdparty/libcsp/include/csp/csp_debug.h b/thirdparty/libcsp/include/csp/csp_debug.h new file mode 100644 index 00000000..64429d49 --- /dev/null +++ b/thirdparty/libcsp/include/csp/csp_debug.h @@ -0,0 +1,150 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef _CSP_DEBUG_H_ +#define _CSP_DEBUG_H_ + +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/** Debug levels */ +typedef enum { + CSP_ERROR = 0, + CSP_WARN = 1, + CSP_INFO = 2, + CSP_BUFFER = 3, + CSP_PACKET = 4, + CSP_PROTOCOL = 5, + CSP_LOCK = 6, +} csp_debug_level_t; + +/* Extract filename component from path */ +#define BASENAME(_file) ((strrchr(_file, '/') ? : (strrchr(_file, '\\') ? : _file)) + 1) + +/* Implement csp_assert_fail_action to override default failure action */ +extern void __attribute__((weak)) csp_assert_fail_action(const char *assertion, const char *file, int line); + +#ifndef NDEBUG + #define csp_assert(exp) \ + do { \ + if (!(exp)) { \ + const char *assertion = #exp; \ + const char *file = BASENAME(__FILE__); \ + int line = __LINE__; \ + printf("\E[1;31m[%02" PRIu8 "] Assertion \'%s\' failed in %s:%d\E[0m\r\n", \ + csp_get_address(), assertion, file, line); \ + if (csp_assert_fail_action) \ + csp_assert_fail_action(assertion, file, line); \ + } \ + } while (0) +#else + #define csp_assert(...) do {} while (0) +#endif + +#ifdef __AVR__ + #include + #include + #define CONSTSTR(data) PSTR(data) + #undef printf + #undef sscanf + #undef scanf + #undef sprintf + #undef snprintf + #define printf(s, ...) printf_P(PSTR(s), ## __VA_ARGS__) + #define sscanf(buf, s, ...) sscanf_P(buf, PSTR(s), ## __VA_ARGS__) + #define scanf(s, ...) scanf_P(PSTR(s), ## __VA_ARGS__) + #define sprintf(buf, s, ...) sprintf_P(buf, PSTR(s), ## __VA_ARGS__) + #define snprintf(buf, size, s, ...) snprintf_P(buf, size, PSTR(s), ## __VA_ARGS__) +#else + #define CONSTSTR(data) data +#endif + +#ifdef CSP_DEBUG + #define csp_debug(level, format, ...) do { do_csp_debug(level, CONSTSTR(format), ##__VA_ARGS__); } while(0) +#else + #define csp_debug(...) do {} while (0) +#endif + +#ifdef CSP_LOG_LEVEL_ERROR + #define csp_log_error(format, ...) csp_debug(CSP_ERROR, format, ##__VA_ARGS__) +#else + #define csp_log_error(...) do {} while (0) +#endif + +#ifdef CSP_LOG_LEVEL_WARN + #define csp_log_warn(format, ...) csp_debug(CSP_WARN, format, ##__VA_ARGS__) +#else + #define csp_log_warn(...) do {} while (0) +#endif + +#ifdef CSP_LOG_LEVEL_INFO + #define csp_log_info(format, ...) csp_debug(CSP_INFO, format, ##__VA_ARGS__) +#else + #define csp_log_info(...) do {} while (0) +#endif + +#ifdef CSP_LOG_LEVEL_DEBUG + #define csp_log_buffer(format, ...) csp_debug(CSP_BUFFER, format, ##__VA_ARGS__) + #define csp_log_packet(format, ...) csp_debug(CSP_PACKET, format, ##__VA_ARGS__) + #define csp_log_protocol(format, ...) csp_debug(CSP_PROTOCOL, format, ##__VA_ARGS__) + #define csp_log_lock(format, ...) csp_debug(CSP_LOCK, format, ##__VA_ARGS__) +#else + #define csp_log_buffer(...) do {} while (0) + #define csp_log_packet(...) do {} while (0) + #define csp_log_protocol(...) do {} while (0) + #define csp_log_lock(...) do {} while (0) +#endif + +/** + * This function should not be used directly, use csp_log_() macro instead + * @param level + * @param format + */ +void do_csp_debug(csp_debug_level_t level, const char *format, ...); + +/** + * Toggle debug level on/off + * @param level Level to toggle + */ +void csp_debug_toggle_level(csp_debug_level_t level); + +/** + * Set debug level + * @param level Level to set + * @param value New level value + */ +void csp_debug_set_level(csp_debug_level_t level, bool value); + +/** + * Get current debug level value + * @param level Level value to get + * @return Level value + */ +int csp_debug_get_level(csp_debug_level_t level); + +#ifdef __cplusplus +} /* extern "C" */ +#endif + +#endif // _CSP_DEBUG_H_ diff --git a/thirdparty/libcsp/include/csp/csp_endian.h b/thirdparty/libcsp/include/csp/csp_endian.h new file mode 100644 index 00000000..e63a73c2 --- /dev/null +++ b/thirdparty/libcsp/include/csp/csp_endian.h @@ -0,0 +1,170 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef _CSP_ENDIAN_H_ +#define _CSP_ENDIAN_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +#include + +/** + * Convert 16-bit integer from host byte order to network byte order + * @param h16 Host byte order 16-bit integer + */ +uint16_t csp_hton16(uint16_t h16); + +/** + * Convert 16-bit integer from host byte order to host byte order + * @param n16 Network byte order 16-bit integer + */ +uint16_t csp_ntoh16(uint16_t n16); + +/** + * Convert 32-bit integer from host byte order to network byte order + * @param h32 Host byte order 32-bit integer + */ +uint32_t csp_hton32(uint32_t h32); + +/** + * Convert 32-bit integer from host byte order to host byte order + * @param n32 Network byte order 32-bit integer + */ +uint32_t csp_ntoh32(uint32_t n32); + +/** + * Convert 64-bit integer from host byte order to network byte order + * @param h64 Host byte order 64-bit integer + */ +uint64_t csp_hton64(uint64_t h64); + +/** + * Convert 64-bit integer from host byte order to host byte order + * @param n64 Network byte order 64-bit integer + */ +uint64_t csp_ntoh64(uint64_t n64); + +/** + * Convert 16-bit integer from host byte order to big endian byte order + * @param h16 Host byte order 16-bit integer + */ +uint16_t csp_htobe16(uint16_t h16); + +/** + * Convert 16-bit integer from host byte order to little endian byte order + * @param h16 Host byte order 16-bit integer + */ +uint16_t csp_htole16(uint16_t h16); + +/** + * Convert 16-bit integer from big endian byte order to little endian byte order + * @param be16 Big endian byte order 16-bit integer + */ +uint16_t csp_betoh16(uint16_t be16); + +/** + * Convert 16-bit integer from little endian byte order to host byte order + * @param le16 Little endian byte order 16-bit integer + */ +uint16_t csp_letoh16(uint16_t le16); + +/** + * Convert 32-bit integer from host byte order to big endian byte order + * @param h32 Host byte order 32-bit integer + */ +uint32_t csp_htobe32(uint32_t h32); + +/** + * Convert 32-bit integer from little endian byte order to host byte order + * @param h32 Host byte order 32-bit integer + */ +uint32_t csp_htole32(uint32_t h32); + +/** + * Convert 32-bit integer from big endian byte order to host byte order + * @param be32 Big endian byte order 32-bit integer + */ +uint32_t csp_betoh32(uint32_t be32); + +/** + * Convert 32-bit integer from little endian byte order to host byte order + * @param le32 Little endian byte order 32-bit integer + */ +uint32_t csp_letoh32(uint32_t le32); + +/** + * Convert 64-bit integer from host byte order to big endian byte order + * @param h64 Host byte order 64-bit integer + */ +uint64_t csp_htobe64(uint64_t h64); + +/** + * Convert 64-bit integer from host byte order to little endian byte order + * @param h64 Host byte order 64-bit integer + */ +uint64_t csp_htole64(uint64_t h64); + +/** + * Convert 64-bit integer from big endian byte order to host byte order + * @param be64 Big endian byte order 64-bit integer + */ +uint64_t csp_betoh64(uint64_t be64); + +/** + * Convert 64-bit integer from little endian byte order to host byte order + * @param le64 Little endian byte order 64-bit integer + */ +uint64_t csp_letoh64(uint64_t le64); + +/** + * Convert float from host to network byte order + * @param f Float in host order + * @return Float in network order + */ +float csp_htonflt(float f); + +/** + * Convert float from network to host byte order + * @param f Float in network order + * @return Float in host order + */ +float csp_ntohflt(float f); + +/** + * Convert double from host to network byte order + * @param d Double in host order + * @return Double in network order + */ +double csp_htondbl(double d); + +/** + * Convert double from network to host order + * @param d Double in network order + * @return Double in host order + */ +double csp_ntohdbl(double d); + +#ifdef __cplusplus +} /* extern "C" */ +#endif + +#endif // _CSP_ENDIAN_H_ diff --git a/thirdparty/libcsp/include/csp/csp_error.h b/thirdparty/libcsp/include/csp/csp_error.h new file mode 100644 index 00000000..31866607 --- /dev/null +++ b/thirdparty/libcsp/include/csp/csp_error.h @@ -0,0 +1,50 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef _CSP_ERROR_H_ +#define _CSP_ERROR_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +#define CSP_ERR_NONE 0 /* No error */ +#define CSP_ERR_NOMEM -1 /* Not enough memory */ +#define CSP_ERR_INVAL -2 /* Invalid argument */ +#define CSP_ERR_TIMEDOUT -3 /* Operation timed out */ +#define CSP_ERR_USED -4 /* Resource already in use */ +#define CSP_ERR_NOTSUP -5 /* Operation not supported */ +#define CSP_ERR_BUSY -6 /* Device or resource busy */ +#define CSP_ERR_ALREADY -7 /* Connection already in progress */ +#define CSP_ERR_RESET -8 /* Connection reset */ +#define CSP_ERR_NOBUFS -9 /* No more buffer space available */ +#define CSP_ERR_TX -10 /* Transmission failed */ +#define CSP_ERR_DRIVER -11 /* Error in driver layer */ +#define CSP_ERR_AGAIN -12 /* Resource temporarily unavailable */ + +#define CSP_ERR_HMAC -100 /* HMAC failed */ +#define CSP_ERR_XTEA -101 /* XTEA failed */ +#define CSP_ERR_CRC32 -102 /* CRC32 failed */ + +#ifdef __cplusplus +} /* extern "C" */ +#endif + +#endif // _CSP_ERROR_H_ diff --git a/thirdparty/libcsp/include/csp/csp_iflist.h b/thirdparty/libcsp/include/csp/csp_iflist.h new file mode 100644 index 00000000..55875657 --- /dev/null +++ b/thirdparty/libcsp/include/csp/csp_iflist.h @@ -0,0 +1,56 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef CSP_IFLIST_H_ +#define CSP_IFLIST_H_ + +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * Add interface to list + * @param ifc Pointer to interface to add + */ +void csp_iflist_add(csp_iface_t *ifc); + +/** + * Lookup interface by name + * @param name String with interface name + * @return Pointer to interface or NULL if not found + */ +csp_iface_t * csp_iflist_get_by_name(const char *name); + +/** + * Print list of interfaces to stdout + */ +void csp_iflist_print(void); + +/** + * Return list of registered interfaces. + */ +csp_iface_t * csp_iflist_get(void); + +#ifdef __cplusplus +} +#endif +#endif /* CSP_IFLIST_H_ */ diff --git a/thirdparty/libcsp/include/csp/csp_interface.h b/thirdparty/libcsp/include/csp/csp_interface.h new file mode 100644 index 00000000..8f04bee3 --- /dev/null +++ b/thirdparty/libcsp/include/csp/csp_interface.h @@ -0,0 +1,54 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef _CSP_INTERFACE_H_ +#define _CSP_INTERFACE_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +#include + +/** + * Inputs a new packet into the system + * This function is called from interface drivers ISR to route and accept packets. + * But it can also be called from a task, provided that the pxTaskWoken parameter is NULL! + * + * EXTREMELY IMPORTANT: + * pxTaskWoken arg must ALWAYS be NULL if called from task, + * and ALWAYS be NON NULL if called from ISR! + * If this condition is met, this call is completely thread-safe + * + * This function is fire and forget, it returns void, meaning + * that a packet will always be either accepted or dropped + * so the memory will always be freed. + * + * @param packet A pointer to the incoming packet + * @param interface A pointer to the incoming interface TX function. + * @param pxTaskWoken This must be a pointer a valid variable if called from ISR or NULL otherwise! + */ +void csp_qfifo_write(csp_packet_t *packet, csp_iface_t *interface, CSP_BASE_TYPE *pxTaskWoken); + +#ifdef __cplusplus +} /* extern "C" */ +#endif + +#endif // _CSP_INTERFACE_H_ diff --git a/thirdparty/libcsp/include/csp/csp_platform.h b/thirdparty/libcsp/include/csp/csp_platform.h new file mode 100644 index 00000000..b33292e9 --- /dev/null +++ b/thirdparty/libcsp/include/csp/csp_platform.h @@ -0,0 +1,56 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef _CSP_PLATFORM_H_ +#define _CSP_PLATFORM_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +#include + +/* Set OS */ +#if defined(CSP_POSIX) || defined(CSP_WINDOWS) || defined(CSP_MACOSX) + #define CSP_BASE_TYPE int + #define CSP_MAX_DELAY (UINT32_MAX) + #define CSP_INFINITY (UINT32_MAX) + #define CSP_DEFINE_CRITICAL(lock) static csp_bin_sem_handle_t lock + #define CSP_INIT_CRITICAL(lock) ({(csp_bin_sem_create(&lock) == CSP_SEMAPHORE_OK) ? CSP_ERR_NONE : CSP_ERR_NOMEM;}) + #define CSP_ENTER_CRITICAL(lock) do { csp_bin_sem_wait(&lock, CSP_MAX_DELAY); } while(0) + #define CSP_EXIT_CRITICAL(lock) do { csp_bin_sem_post(&lock); } while(0) +#elif defined(CSP_FREERTOS) + #include "FreeRTOS.h" + #define CSP_BASE_TYPE portBASE_TYPE + #define CSP_MAX_DELAY portMAX_DELAY + #define CSP_INFINITY portMAX_DELAY + #define CSP_DEFINE_CRITICAL(lock) + #define CSP_INIT_CRITICAL(lock) ({CSP_ERR_NONE;}) + #define CSP_ENTER_CRITICAL(lock) do { portENTER_CRITICAL(); } while (0) + #define CSP_EXIT_CRITICAL(lock) do { portEXIT_CRITICAL(); } while (0) +#else + #error "OS must be either CSP_POSIX, CSP_MACOSX, CSP_FREERTOS OR CSP_WINDOWS" +#endif + +#ifdef __cplusplus +} /* extern "C" */ +#endif + +#endif // _CSP_PLATFORM_H_ diff --git a/thirdparty/libcsp/include/csp/csp_rtable.h b/thirdparty/libcsp/include/csp/csp_rtable.h new file mode 100644 index 00000000..34cd18e2 --- /dev/null +++ b/thirdparty/libcsp/include/csp/csp_rtable.h @@ -0,0 +1,149 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef CSP_RTABLE_H_ +#define CSP_RTABLE_H_ + +#include + +#ifdef __cplusplus +extern "C" { +#endif + +#define CSP_NODE_MAC 0xFF +#define CSP_ROUTE_COUNT (CSP_ID_HOST_MAX + 2) +#define CSP_ROUTE_TABLE_SIZE 5 * CSP_ROUTE_COUNT + +/** + * Find outgoing interface in routing table + * @param id Destination node + * @return pointer to outgoing interface or NULL + */ +csp_iface_t * csp_rtable_find_iface(uint8_t id); + +/** + * Find MAC address associated with node + * @param id Destination node + * @return MAC address + */ +uint8_t csp_rtable_find_mac(uint8_t id); + +/** + * Setup routing entry + * @param node Host + * @param mask Number of bits in netmask + * @param ifc Interface + * @param mac MAC address + * @return CSP error type + */ +int csp_rtable_set(uint8_t node, uint8_t mask, csp_iface_t *ifc, uint8_t mac); + +/** + * Print routing table to stdout + */ +void csp_rtable_print(void); + + +/** + * Load the routing table from a buffer + * (deprecated, please use new csp_rtable_load) + * + * Warning: + * The table will be RAW from memory and contains direct pointers, not interface names. + * Therefore it's very important that a saved routing table is deleted after a firmware update + * + * @param route_table_in pointer to routing table buffer + */ +void csp_route_table_load(uint8_t route_table_in[CSP_ROUTE_TABLE_SIZE]); + +/** + * Save the routing table to a buffer + * (deprecated, please use new csp_rtable_save) + * + * Warning: + * The table will be RAW from memory and contains direct pointers, not interface names. + * Therefore it's very important that a saved routing table is deleted after a firmware update + * + * @param route_table_out pointer to routing table buffer + */ +void csp_route_table_save(uint8_t route_table_out[CSP_ROUTE_TABLE_SIZE]); + +/** + * Save routing table as a string to a buffer, which can be parsed + * again by csp_rtable_load. + * @param buffer pointer to buffer + * @param maxlen length of buffer + * @return length of saved string + */ +int csp_rtable_save(char * buffer, int maxlen); + +/** + * Load routing table from a string in the format + * %u/%u %s %u + * - Address + * - Netmask + * - Ifname + * - Mac Address (this field is optional) + * An example routing string is "0/0 I2C, 8/2 KISS" + * The string must be \0 null terminated + * @param buffer Pointer to string + */ +void csp_rtable_load(const char * buffer); + +/** + * Check string for valid routing table + * @param buffer Pointer to string + * @return number of valid entries found + */ +int csp_rtable_check(const char * buffer); + +/** + * Clear routing table: + * This could be done before load to ensure an entire clean table is loaded. + */ +void csp_rtable_clear(void); + +/** + * Setup routing entry to single node + * (deprecated, please use csp_rtable_set) + * + * @param node Host + * @param ifc Interface + * @param mac MAC address + * @return CSP error type + */ +#define csp_route_set(node, ifc, mac) csp_rtable_set(node, CSP_ID_HOST_SIZE, ifc, mac) + +/** + * Print routing table + * (deprecated, please use csp_rtable_print) + */ +#define csp_route_print_table() csp_rtable_print(); + +/** + * Print list of interfaces + * (deprecated, please use csp_iflist_print) + */ +#define csp_route_print_interfaces() csp_iflist_print(); + +#ifdef __cplusplus +} +#endif +#endif /* CSP_RTABLE_H_ */ diff --git a/thirdparty/libcsp/include/csp/csp_types.h b/thirdparty/libcsp/include/csp/csp_types.h new file mode 100644 index 00000000..a9cc28cd --- /dev/null +++ b/thirdparty/libcsp/include/csp/csp_types.h @@ -0,0 +1,235 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef CSP_TYPES_H_ +#define CSP_TYPES_H_ + +#include +#include // -> CSP_HAVE_X defines +#ifdef CSP_HAVE_STDBOOL_H +#include +#endif + +#ifdef __cplusplus +extern "C" { +#endif + +/* Make bool for compilers without stdbool.h */ +#ifndef CSP_HAVE_STDBOOL_H +#define bool int +#define false 0 +#define true !false +#endif + +/** + * RESERVED PORTS (SERVICES) + */ + +enum csp_reserved_ports_e { + CSP_CMP = 0, + CSP_PING = 1, + CSP_PS = 2, + CSP_MEMFREE = 3, + CSP_REBOOT = 4, + CSP_BUF_FREE = 5, + CSP_UPTIME = 6, + CSP_ANY = (CSP_MAX_BIND_PORT + 1), + CSP_PROMISC = (CSP_MAX_BIND_PORT + 2) +}; + +typedef enum { + CSP_PRIO_CRITICAL = 0, + CSP_PRIO_HIGH = 1, + CSP_PRIO_NORM = 2, + CSP_PRIO_LOW = 3, +} csp_prio_t; + +#define CSP_PRIORITIES (1 << CSP_ID_PRIO_SIZE) + +#ifdef CSP_USE_QOS +#define CSP_RX_QUEUE_LENGTH (CSP_CONN_QUEUE_LENGTH / CSP_PRIORITIES) +#define CSP_ROUTE_FIFOS CSP_PRIORITIES +#define CSP_RX_QUEUES CSP_PRIORITIES +#else +#define CSP_RX_QUEUE_LENGTH CSP_CONN_QUEUE_LENGTH +#define CSP_ROUTE_FIFOS 1 +#define CSP_RX_QUEUES 1 +#endif + +/** Size of bit-fields in CSP header */ +#define CSP_ID_PRIO_SIZE 2 +#define CSP_ID_HOST_SIZE 5 +#define CSP_ID_PORT_SIZE 6 +#define CSP_ID_FLAGS_SIZE 8 + +#define CSP_HEADER_BITS (CSP_ID_PRIO_SIZE + 2 * CSP_ID_HOST_SIZE + 2 * CSP_ID_PORT_SIZE + CSP_ID_FLAGS_SIZE) +#define CSP_HEADER_LENGTH (CSP_HEADER_BITS / 8) + +#if CSP_HEADER_BITS != 32 && __GNUC__ +#error "Header length must be 32 bits" +#endif + +/** Highest number to be entered in field */ +#define CSP_ID_PRIO_MAX ((1 << (CSP_ID_PRIO_SIZE)) - 1) +#define CSP_ID_HOST_MAX ((1 << (CSP_ID_HOST_SIZE)) - 1) +#define CSP_ID_PORT_MAX ((1 << (CSP_ID_PORT_SIZE)) - 1) +#define CSP_ID_FLAGS_MAX ((1 << (CSP_ID_FLAGS_SIZE)) - 1) + +/** Identifier field masks */ +#define CSP_ID_PRIO_MASK ((uint32_t) CSP_ID_PRIO_MAX << (CSP_ID_FLAGS_SIZE + 2 * CSP_ID_PORT_SIZE + 2 * CSP_ID_HOST_SIZE)) +#define CSP_ID_SRC_MASK ((uint32_t) CSP_ID_HOST_MAX << (CSP_ID_FLAGS_SIZE + 2 * CSP_ID_PORT_SIZE + 1 * CSP_ID_HOST_SIZE)) +#define CSP_ID_DST_MASK ((uint32_t) CSP_ID_HOST_MAX << (CSP_ID_FLAGS_SIZE + 2 * CSP_ID_PORT_SIZE)) +#define CSP_ID_DPORT_MASK ((uint32_t) CSP_ID_PORT_MAX << (CSP_ID_FLAGS_SIZE + 1 * CSP_ID_PORT_SIZE)) +#define CSP_ID_SPORT_MASK ((uint32_t) CSP_ID_PORT_MAX << (CSP_ID_FLAGS_SIZE)) +#define CSP_ID_FLAGS_MASK ((uint32_t) CSP_ID_FLAGS_MAX << (0)) + +#define CSP_ID_CONN_MASK (CSP_ID_SRC_MASK | CSP_ID_DST_MASK | CSP_ID_DPORT_MASK | CSP_ID_SPORT_MASK) + +/** + CSP identifier. +*/ +typedef union { + //! Entire identifier. + uint32_t ext; + //! Individual fields. + struct __attribute__((__packed__)) { +#if defined(CSP_BIG_ENDIAN) && !defined(CSP_LITTLE_ENDIAN) + unsigned int pri : CSP_ID_PRIO_SIZE; + unsigned int src : CSP_ID_HOST_SIZE; + unsigned int dst : CSP_ID_HOST_SIZE; + unsigned int dport : CSP_ID_PORT_SIZE; + unsigned int sport : CSP_ID_PORT_SIZE; + unsigned int flags : CSP_ID_FLAGS_SIZE; +#elif defined(CSP_LITTLE_ENDIAN) && !defined(CSP_BIG_ENDIAN) + unsigned int flags : CSP_ID_FLAGS_SIZE; + unsigned int sport : CSP_ID_PORT_SIZE; + unsigned int dport : CSP_ID_PORT_SIZE; + unsigned int dst : CSP_ID_HOST_SIZE; + unsigned int src : CSP_ID_HOST_SIZE; + unsigned int pri : CSP_ID_PRIO_SIZE; +#else +#error "Must define one of CSP_BIG_ENDIAN or CSP_LITTLE_ENDIAN in csp_platform.h" +#endif + }; +} csp_id_t; + +/** Broadcast address */ +#define CSP_BROADCAST_ADDR CSP_ID_HOST_MAX + +/** Default routing address */ +#define CSP_DEFAULT_ROUTE (CSP_ID_HOST_MAX + 1) + +/** CSP Flags */ +#define CSP_FRES1 0x80 // Reserved for future use +#define CSP_FRES2 0x40 // Reserved for future use +#define CSP_FRES3 0x20 // Reserved for future use +#define CSP_FFRAG 0x10 // Use fragmentation +#define CSP_FHMAC 0x08 // Use HMAC verification +#define CSP_FXTEA 0x04 // Use XTEA encryption +#define CSP_FRDP 0x02 // Use RDP protocol +#define CSP_FCRC32 0x01 // Use CRC32 checksum + +/** CSP Socket options */ +#define CSP_SO_NONE 0x0000 // No socket options +#define CSP_SO_RDPREQ 0x0001 // Require RDP +#define CSP_SO_RDPPROHIB 0x0002 // Prohibit RDP +#define CSP_SO_HMACREQ 0x0004 // Require HMAC +#define CSP_SO_HMACPROHIB 0x0008 // Prohibit HMAC +#define CSP_SO_XTEAREQ 0x0010 // Require XTEA +#define CSP_SO_XTEAPROHIB 0x0020 // Prohibit HMAC +#define CSP_SO_CRC32REQ 0x0040 // Require CRC32 +#define CSP_SO_CRC32PROHIB 0x0080 // Prohibit CRC32 +#define CSP_SO_CONN_LESS 0x0100 // Enable Connection Less mode +#define CSP_SO_INTERNAL_LISTEN 0x1000 // Internal flag: listen called on socket + +/** CSP Connect options */ +#define CSP_O_NONE CSP_SO_NONE // No connection options +#define CSP_O_RDP CSP_SO_RDPREQ // Enable RDP +#define CSP_O_NORDP CSP_SO_RDPPROHIB // Disable RDP +#define CSP_O_HMAC CSP_SO_HMACREQ // Enable HMAC +#define CSP_O_NOHMAC CSP_SO_HMACPROHIB // Disable HMAC +#define CSP_O_XTEA CSP_SO_XTEAREQ // Enable XTEA +#define CSP_O_NOXTEA CSP_SO_XTEAPROHIB // Disable XTEA +#define CSP_O_CRC32 CSP_SO_CRC32REQ // Enable CRC32 +#define CSP_O_NOCRC32 CSP_SO_CRC32PROHIB // Disable CRC32 + +/** + * CSP PACKET STRUCTURE + * Note: This structure is constructed to fit + * with all interface frame types in order to + * have buffer reuse + */ +typedef struct __attribute__((__packed__)) { + uint8_t padding[CSP_PADDING_BYTES]; /**< Interface dependent padding */ + uint16_t length; /**< Length field must be just before CSP ID */ + csp_id_t id; /**< CSP id must be just before data */ + union { + uint8_t data[0]; /**< This just points to the rest of the buffer, without a size indication. */ + uint16_t data16[0]; /**< The data 16 and 32 types makes it easy to reference an integer (properly aligned) */ + uint32_t data32[0]; /**< without the compiler warning about strict aliasing rules. */ + }; +} csp_packet_t; + +/** Interface TX function */ +struct csp_iface_s; +typedef int (*nexthop_t)(struct csp_iface_s * interface, csp_packet_t *packet, uint32_t timeout); + +/** Interface struct */ +typedef struct csp_iface_s { + const char *name; /**< Interface name (keep below 10 bytes) */ + void * driver; /**< Pointer to interface handler structure */ + nexthop_t nexthop; /**< Next hop function */ + uint16_t mtu; /**< Maximum Transmission Unit of interface */ + uint8_t split_horizon_off; /**< Disable the route-loop prevention on if */ + uint32_t tx; /**< Successfully transmitted packets */ + uint32_t rx; /**< Successfully received packets */ + uint32_t tx_error; /**< Transmit errors */ + uint32_t rx_error; /**< Receive errors */ + uint32_t drop; /**< Dropped packets */ + uint32_t autherr; /**< Authentication errors */ + uint32_t frame; /**< Frame format errors */ + uint32_t txbytes; /**< Transmitted bytes */ + uint32_t rxbytes; /**< Received bytes */ + uint32_t irq; /**< Interrupts */ + struct csp_iface_s *next; /**< Next interface */ +} csp_iface_t; + +/** + * This define must be equal to the size of the packet overhead in csp_packet_t. + * It is used in csp_buffer_get() to check the allocated buffer size against + * the required buffer size. + */ +#define CSP_BUFFER_PACKET_OVERHEAD (sizeof(csp_packet_t) - sizeof(((csp_packet_t *)0)->data)) + +/** Forward declaration of socket and connection structures */ +typedef struct csp_conn_s csp_socket_t; +typedef struct csp_conn_s csp_conn_t; + +#define CSP_HOSTNAME_LEN 20 +#define CSP_MODEL_LEN 30 + +/* CSP_REBOOT magic values */ +#define CSP_REBOOT_MAGIC 0x80078007 +#define CSP_REBOOT_SHUTDOWN_MAGIC 0xD1E5529A + +#ifdef __cplusplus +} +#endif +#endif /* CSP_TYPES_H_ */ diff --git a/thirdparty/libcsp/include/csp/drivers/can_socketcan.h b/thirdparty/libcsp/include/csp/drivers/can_socketcan.h new file mode 100644 index 00000000..0963b414 --- /dev/null +++ b/thirdparty/libcsp/include/csp/drivers/can_socketcan.h @@ -0,0 +1,22 @@ +/* + * can_socketcan.h + * + * Created on: Feb 6, 2017 + * Author: johan + */ + +#ifndef LIB_CSP_INCLUDE_CSP_DRIVERS_CAN_SOCKETCAN_H_ +#define LIB_CSP_INCLUDE_CSP_DRIVERS_CAN_SOCKETCAN_H_ + +#include + +#ifdef __cplusplus +extern "C" { +#endif + +csp_iface_t * csp_can_socketcan_init(const char * ifc, int bitrate, int promisc); + +#ifdef __cplusplus +} +#endif +#endif /* LIB_CSP_INCLUDE_CSP_DRIVERS_CAN_SOCKETCAN_H_ */ diff --git a/thirdparty/libcsp/include/csp/drivers/i2c.h b/thirdparty/libcsp/include/csp/drivers/i2c.h new file mode 100644 index 00000000..3cf605ee --- /dev/null +++ b/thirdparty/libcsp/include/csp/drivers/i2c.h @@ -0,0 +1,120 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +/** + * @file + * Common I2C interface, + * This file is derived from the Gomspace I2C driver, + * + */ + +#ifndef I2C_H_ +#define I2C_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * The return value of the driver is a bit strange, + * It should return E_NO_ERR if successfull and the value is -1 + */ +#define E_NO_ERR -1 + +/** + * Maximum transfer length on I2C + */ +#define I2C_MTU 256 + +/** + I2C device modes + @{ +*/ +/** + I2C Master mode. +*/ +#define I2C_MASTER 0 +/** + I2C Slave mode. +*/ +#define I2C_SLAVE 1 +/**@}*/ + +/** + Data structure for I2C frames. + This structs fits on top of #csp_packet_t, removing the need for copying data. +*/ +typedef struct __attribute__((packed)) i2c_frame_s { + //! Not used by CSP + uint8_t padding; + //! Not used by CSP - cleared before Tx + uint8_t retries; + //! Not used by CSP + uint32_t reserved; + //! Destination address + uint8_t dest; + //! Not used by CSP - cleared before Tx + uint8_t len_rx; + //! Length of \a data part + uint16_t len; + //! CSP data + uint8_t data[I2C_MTU]; +} i2c_frame_t; + +/** + Callback for receiving data. + + @param[in] frame received I2C frame + @param[out] pxTaskWoken can be set, if context switch is required due to received data. +*/ +typedef void (*i2c_callback_t) (i2c_frame_t * frame, void * pxTaskWoken); + +/** + Initialise the I2C driver + + Functions is called by csp_i2c_init(). + + @param handle Which I2C bus (if more than one exists) + @param mode I2C device mode. Must be either I2C_MASTER or I2C_SLAVE + @param addr Own slave address + @param speed Bus speed in kbps + @param queue_len_tx Length of transmit queue + @param queue_len_rx Length of receive queue + @param callback If this value is set, the driver will call this function instead of using an RX queue + @return Error code +*/ +int i2c_init(int handle, int mode, uint8_t addr, uint16_t speed, int queue_len_tx, int queue_len_rx, i2c_callback_t callback); + +/** + User I2C transmit function. + + Called by CSP, when sending message over I2C. + + @param handle Handle to the device + @param frame Pointer to I2C frame + @param timeout Ticks to wait + @return Error code +*/ +int i2c_send(int handle, i2c_frame_t * frame, uint16_t timeout); + +#ifdef __cplusplus +} +#endif +#endif diff --git a/thirdparty/libcsp/include/csp/drivers/usart.h b/thirdparty/libcsp/include/csp/drivers/usart.h new file mode 100644 index 00000000..d2da8448 --- /dev/null +++ b/thirdparty/libcsp/include/csp/drivers/usart.h @@ -0,0 +1,107 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +/** + * @file + * Common USART interface, + * This file is derived from the Gomspace USART driver, + * the main difference is the assumption that only one USART will be present on a PC + */ + +#ifndef USART_H_ +#define USART_H_ + +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/** + Usart configuration, to be used with the usart_init call. +*/ +struct usart_conf { + //! USART device. + const char *device; + //! bits per second. + uint32_t baudrate; + //! Number of data bits. + uint8_t databits; + //! Number of stop bits. + uint8_t stopbits; + //! Parity setting. + uint8_t paritysetting; + //! Enable parity checking (Windows only). + uint8_t checkparity; +}; + +/** + Initialise UART with the usart_conf data structure + @param[in] conf full configuration structure +*/ +void usart_init(struct usart_conf *conf); + +/** + In order to catch incoming chars use the callback. + Only one callback per interface. + @param[in] handle usart[0,1,2,3] + @param[in] callback function pointer +*/ +typedef void (*usart_callback_t) (uint8_t *buf, int len, void *pxTaskWoken); + +/** + Set callback for receiving data. +*/ +void usart_set_callback(usart_callback_t callback); + +/** + Insert a character to the RX buffer of a usart + + @param[in] c character to insert + @param[out] pxTaskWoken can be set, if context switch is required due to received data. +*/ +void usart_insert(char c, void *pxTaskWoken); + +/** + Polling putchar (stdin). + + @param[in] c Character to transmit +*/ +void usart_putc(char c); + +/** + Send char buffer on UART (stdout). + + @param[in] buf Pointer to data + @param[in] len Length of data +*/ +void usart_putstr(char *buf, int len); + +/** + Buffered getchar (stdin). + + @return Character received +*/ +char usart_getc(void); + +#ifdef __cplusplus +} +#endif +#endif /* USART_H_ */ diff --git a/thirdparty/libcsp/include/csp/interfaces/csp_if_can.h b/thirdparty/libcsp/include/csp/interfaces/csp_if_can.h new file mode 100644 index 00000000..229671f2 --- /dev/null +++ b/thirdparty/libcsp/include/csp/interfaces/csp_if_can.h @@ -0,0 +1,76 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef _CSP_IF_CAN_H_ +#define _CSP_IF_CAN_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +#include + +#include +#include + +/* CAN header macros */ +#define CFP_HOST_SIZE 5 +#define CFP_TYPE_SIZE 1 +#define CFP_REMAIN_SIZE 8 +#define CFP_ID_SIZE 10 + +/* Macros for extracting header fields */ +#define CFP_FIELD(id,rsiz,fsiz) ((uint32_t)((uint32_t)((id) >> (rsiz)) & (uint32_t)((1 << (fsiz)) - 1))) +#define CFP_SRC(id) CFP_FIELD(id, CFP_HOST_SIZE + CFP_TYPE_SIZE + CFP_REMAIN_SIZE + CFP_ID_SIZE, CFP_HOST_SIZE) +#define CFP_DST(id) CFP_FIELD(id, CFP_TYPE_SIZE + CFP_REMAIN_SIZE + CFP_ID_SIZE, CFP_HOST_SIZE) +#define CFP_TYPE(id) CFP_FIELD(id, CFP_REMAIN_SIZE + CFP_ID_SIZE, CFP_TYPE_SIZE) +#define CFP_REMAIN(id) CFP_FIELD(id, CFP_ID_SIZE, CFP_REMAIN_SIZE) +#define CFP_ID(id) CFP_FIELD(id, 0, CFP_ID_SIZE) + +/* Macros for building CFP headers */ +#define CFP_MAKE_FIELD(id,fsiz,rsiz) ((uint32_t)(((id) & (uint32_t)((uint32_t)(1 << (fsiz)) - 1)) << (rsiz))) +#define CFP_MAKE_SRC(id) CFP_MAKE_FIELD(id, CFP_HOST_SIZE, CFP_HOST_SIZE + CFP_TYPE_SIZE + CFP_REMAIN_SIZE + CFP_ID_SIZE) +#define CFP_MAKE_DST(id) CFP_MAKE_FIELD(id, CFP_HOST_SIZE, CFP_TYPE_SIZE + CFP_REMAIN_SIZE + CFP_ID_SIZE) +#define CFP_MAKE_TYPE(id) CFP_MAKE_FIELD(id, CFP_TYPE_SIZE, CFP_REMAIN_SIZE + CFP_ID_SIZE) +#define CFP_MAKE_REMAIN(id) CFP_MAKE_FIELD(id, CFP_REMAIN_SIZE, CFP_ID_SIZE) +#define CFP_MAKE_ID(id) CFP_MAKE_FIELD(id, CFP_ID_SIZE, 0) + +/* Mask to uniquely separate connections */ +#define CFP_ID_CONN_MASK (CFP_MAKE_SRC((uint32_t)(1 << CFP_HOST_SIZE) - 1) | \ + CFP_MAKE_DST((uint32_t)(1 << CFP_HOST_SIZE) - 1) | \ + CFP_MAKE_ID((uint32_t)(1 << CFP_ID_SIZE) - 1)) + +/** + Default Maximum Transmission Unit (MTU) for CSP over CAN. + Maximum value is 2042 bytes. +*/ +#define CSP_CAN_MTU 256 + +int csp_can_rx(csp_iface_t *interface, uint32_t id, const uint8_t * data, uint8_t dlc, CSP_BASE_TYPE *task_woken); +int csp_can_tx(csp_iface_t *interface, csp_packet_t *packet, uint32_t timeout); + +/* Must be implemented by the driver */ +int csp_can_tx_frame(csp_iface_t *interface, uint32_t id, const uint8_t * data, uint8_t dlc); + +#ifdef __cplusplus +} /* extern "C" */ +#endif + +#endif /* _CSP_IF_CAN_H_ */ diff --git a/thirdparty/libcsp/include/csp/interfaces/csp_if_i2c.h b/thirdparty/libcsp/include/csp/interfaces/csp_if_i2c.h new file mode 100644 index 00000000..c2169843 --- /dev/null +++ b/thirdparty/libcsp/include/csp/interfaces/csp_if_i2c.h @@ -0,0 +1,51 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef _CSP_IF_I2C_H_ +#define _CSP_IF_I2C_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +#include + +#include +#include +#include + +extern csp_iface_t csp_if_i2c; + +/** + * Capture I2C RX events for CSP + * @param opt_addr local i2c address + * @param handle which i2c device to use + * @param speed interface speed in kHz (normally 100 or 400) + * @return csp_error.h code + */ +int csp_i2c_init(uint8_t opt_addr, int handle, int speed); + +void csp_i2c_rx(i2c_frame_t * frame, void * pxTaskWoken); + +#ifdef __cplusplus +} /* extern "C" */ +#endif + +#endif /* _CSP_IF_I2C_H_ */ diff --git a/thirdparty/libcsp/include/csp/interfaces/csp_if_kiss.h b/thirdparty/libcsp/include/csp/interfaces/csp_if_kiss.h new file mode 100644 index 00000000..f164cad1 --- /dev/null +++ b/thirdparty/libcsp/include/csp/interfaces/csp_if_kiss.h @@ -0,0 +1,110 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef _CSP_IF_KISS_H_ +#define _CSP_IF_KISS_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +#include + +#include +#include + +/** + * The KISS interface relies on the USART callback in order to parse incoming + * messaged from the serial interface. The USART callback however does not + * support passing the handle number of the responding USART, so you need to implement + * a USART callback for each handle and then call kiss_rx subsequently. + * + * In order to initialize the KISS interface. Fist call kiss_init() and then + * setup your usart to call csp_kiss_rx when new data is available. + * + * When a byte is not a part of a kiss packet, it will be returned to your + * usart driver using the usart_insert funtion that you provide. + * + * @param csp_iface pointer to interface + * @param buf pointer to incoming data + * @param len length of incoming data + * @param pxTaskWoken NULL if task context, pointer to variable if ISR + */ +void csp_kiss_rx(csp_iface_t * interface, uint8_t *buf, int len, void *pxTaskWoken); + +/** + * The putc function is used by the kiss interface to send + * a string of data to the serial port. This function must + * be implemented by the user, and passed to the kiss + * interface through the kiss_init function. + * @param buf byte to push + */ +typedef void (*csp_kiss_putc_f)(char buf); + +/** + * The characters not accepted by the kiss interface, are discarded + * using this function, which must be implemented by the user + * and passed through the kiss_init function. + * + * This reject function is typically used to display ASCII strings + * sent over the serial port, which are not in KISS format. Such as + * debugging information. + * + * @param c rejected character + * @param pxTaskWoken NULL if task context, pointer to variable if ISR + */ +typedef void (*csp_kiss_discard_f)(char c, void *pxTaskWoken); + +typedef enum { + KISS_MODE_NOT_STARTED, + KISS_MODE_STARTED, + KISS_MODE_ESCAPED, + KISS_MODE_SKIP_FRAME, +} kiss_mode_e; + +/** + * This structure should be statically allocated by the user + * and passed to the kiss interface during the init function + * no member information should be changed + */ +typedef struct csp_kiss_handle_s { + //! Put character on usart (tx). + csp_kiss_putc_f kiss_putc; + //! Discard - not KISS data (rx). + csp_kiss_discard_f kiss_discard; + //! Internal KISS state. + unsigned int rx_length; + //! Internal KISS state. + kiss_mode_e rx_mode; + //! Internal KISS state. + unsigned int rx_first; + //! Not used. + volatile unsigned char *rx_cbuf; + //! Internal KISS state. + csp_packet_t * rx_packet; +} csp_kiss_handle_t; + +void csp_kiss_init(csp_iface_t * csp_iface, csp_kiss_handle_t * csp_kiss_handle, csp_kiss_putc_f kiss_putc_f, csp_kiss_discard_f kiss_discard_f, const char * name); + +#ifdef __cplusplus +} /* extern "C" */ +#endif + +#endif /* _CSP_IF_KISS_H_ */ diff --git a/thirdparty/libcsp/include/csp/interfaces/csp_if_lo.h b/thirdparty/libcsp/include/csp/interfaces/csp_if_lo.h new file mode 100644 index 00000000..793c45ac --- /dev/null +++ b/thirdparty/libcsp/include/csp/interfaces/csp_if_lo.h @@ -0,0 +1,38 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef _CSP_IF_LO_H_ +#define _CSP_IF_LO_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +/* CSP includes */ +#include +#include + +extern csp_iface_t csp_if_lo; + +#ifdef __cplusplus +} /* extern "C" */ +#endif + +#endif // _CSP_IF_LO_H_ diff --git a/thirdparty/libcsp/include/csp/interfaces/csp_if_zmqhub.h b/thirdparty/libcsp/include/csp/interfaces/csp_if_zmqhub.h new file mode 100644 index 00000000..f9ab43bf --- /dev/null +++ b/thirdparty/libcsp/include/csp/interfaces/csp_if_zmqhub.h @@ -0,0 +1,26 @@ +#ifndef CSP_IF_ZMQHUB_H_ +#define CSP_IF_ZMQHUB_H_ + +#include + +extern csp_iface_t csp_if_zmqhub; + +/** + * Setup ZMQ interface + * @param addr only receive messages matching this address (255 means all) + * @param host Pointer to string containing zmqproxy host + * @return CSP_ERR + */ +int csp_zmqhub_init(uint8_t addr, const char * host); + +/** + * Setup ZMQ interface + * @param addr only receive messages matching this address (255 means all) + * @param publisher_endpoint Pointer to string containing zmqproxy publisher endpoint + * @param subscriber_endpoint Pointer to string containing zmqproxy subscriber endpoint + * @return CSP_ERR + */ +int csp_zmqhub_init_w_endpoints(uint8_t addr, const char * publisher_url, + const char * subscriber_url); + +#endif /* CSP_IF_ZMQHUB_H_ */ diff --git a/thirdparty/libcsp/libcsp.mk b/thirdparty/libcsp/libcsp.mk new file mode 100644 index 00000000..febffad7 --- /dev/null +++ b/thirdparty/libcsp/libcsp.mk @@ -0,0 +1,12 @@ +CSRC += $(wildcard $(CURRENTPATH)/src/drivers/can/*.c) +CSRC += $(wildcard $(CURRENTPATH)/src/*.c) +CSRC += $(wildcard $(CURRENTPATH)/src/interfaces/*.c) +CSRC += $(wildcard $(CURRENTPATH)/src/rtable/csp_rtable_cidr.c) +CSRC += $(wildcard $(CURRENTPATH)/src/crypto/*.c) +CSRC += $(wildcard $(CURRENTPATH)/src/arch/posix/*.c) +CSRC += $(wildcard $(CURRENTPATH)/src/transport/*.c) + +INCLUDES += $(CURRENTPATH)/include +INCLUDES += $(CURRENTPATH)/include/csp +INCLUDES += $(CURRENTPATH)/include/csp/crypto +INCLUDES += $(CURRENTPATH) \ No newline at end of file diff --git a/thirdparty/libcsp/src/CMakeLists.txt b/thirdparty/libcsp/src/CMakeLists.txt new file mode 100644 index 00000000..39c67877 --- /dev/null +++ b/thirdparty/libcsp/src/CMakeLists.txt @@ -0,0 +1,27 @@ +target_sources(${LIB_CSP_NAME} PRIVATE + csp_bridge.c + csp_buffer.c + csp_conn.c + csp_crc32.c + csp_debug.c + csp_dedup.c + csp_endian.c + csp_hex_dump.c + csp_iflist.c + csp_io.c + csp_port.c + csp_promisc.c + csp_qfifo.c + csp_route.c + csp_service_handler.c + csp_services.c + csp_sfp.c +) + +add_subdirectory(drivers) +add_subdirectory(crypto) +add_subdirectory(interfaces) +add_subdirectory(rtable) +add_subdirectory(transport) +add_subdirectory(arch) + diff --git a/thirdparty/libcsp/src/arch/CMakeLists.txt b/thirdparty/libcsp/src/arch/CMakeLists.txt new file mode 100644 index 00000000..aa0e4ca6 --- /dev/null +++ b/thirdparty/libcsp/src/arch/CMakeLists.txt @@ -0,0 +1,3 @@ +add_subdirectory(posix) + + diff --git a/thirdparty/libcsp/src/arch/freertos/csp_malloc.c b/thirdparty/libcsp/src/arch/freertos/csp_malloc.c new file mode 100644 index 00000000..97e5c8f4 --- /dev/null +++ b/thirdparty/libcsp/src/arch/freertos/csp_malloc.c @@ -0,0 +1,33 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include +#include + +/* FreeRTOS includes */ +#include + +void * csp_malloc(size_t size) { + return pvPortMalloc(size); +} + +void csp_free(void *ptr) { + vPortFree(ptr); +} diff --git a/thirdparty/libcsp/src/arch/freertos/csp_queue.c b/thirdparty/libcsp/src/arch/freertos/csp_queue.c new file mode 100644 index 00000000..44efd0eb --- /dev/null +++ b/thirdparty/libcsp/src/arch/freertos/csp_queue.c @@ -0,0 +1,66 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include + +/* FreeRTOS includes */ +#include +#include + +/* CSP includes */ +#include + +#include + +csp_queue_handle_t csp_queue_create(int length, size_t item_size) { + return xQueueCreate(length, item_size); +} + +void csp_queue_remove(csp_queue_handle_t queue) { + vQueueDelete(queue); +} + +int csp_queue_enqueue(csp_queue_handle_t handle, void * value, uint32_t timeout) { + if (timeout != CSP_MAX_DELAY) + timeout = timeout / portTICK_RATE_MS; + return xQueueSendToBack(handle, value, timeout); +} + +int csp_queue_enqueue_isr(csp_queue_handle_t handle, void * value, CSP_BASE_TYPE * task_woken) { + return xQueueSendToBackFromISR(handle, value, task_woken); +} + +int csp_queue_dequeue(csp_queue_handle_t handle, void * buf, uint32_t timeout) { + if (timeout != CSP_MAX_DELAY) + timeout = timeout / portTICK_RATE_MS; + return xQueueReceive(handle, buf, timeout); +} + +int csp_queue_dequeue_isr(csp_queue_handle_t handle, void * buf, CSP_BASE_TYPE * task_woken) { + return xQueueReceiveFromISR(handle, buf, task_woken); +} + +int csp_queue_size(csp_queue_handle_t handle) { + return uxQueueMessagesWaiting(handle); +} + +int csp_queue_size_isr(csp_queue_handle_t handle) { + return uxQueueMessagesWaitingFromISR(handle); +} diff --git a/thirdparty/libcsp/src/arch/freertos/csp_semaphore.c b/thirdparty/libcsp/src/arch/freertos/csp_semaphore.c new file mode 100644 index 00000000..b91757e5 --- /dev/null +++ b/thirdparty/libcsp/src/arch/freertos/csp_semaphore.c @@ -0,0 +1,96 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include +#include + +/* FreeRTOS includes */ +#include +#include + +/* CSP includes */ +#include + +#include +#include +#include + +int csp_mutex_create(csp_mutex_t * mutex) { + *mutex = xSemaphoreCreateMutex(); + if (*mutex) { + return CSP_SEMAPHORE_OK; + } else { + return CSP_SEMAPHORE_ERROR; + } +} + +int csp_mutex_remove(csp_mutex_t * mutex) { + return csp_bin_sem_remove(mutex); +} + +int csp_mutex_lock(csp_mutex_t * mutex, uint32_t timeout) { + return csp_bin_sem_wait(mutex, timeout); +} + +int csp_mutex_unlock(csp_mutex_t * mutex) { + return csp_bin_sem_post(mutex); +} + +int csp_bin_sem_create(csp_bin_sem_handle_t * sem) { + vSemaphoreCreateBinary(*sem); + return CSP_SEMAPHORE_OK; +} + +int csp_bin_sem_remove(csp_bin_sem_handle_t * sem) { + if ((sem != NULL) && (*sem != NULL)) { + csp_queue_remove(*sem); + } + return CSP_SEMAPHORE_OK; +} + +int csp_bin_sem_wait(csp_bin_sem_handle_t * sem, uint32_t timeout) { + csp_log_lock("Wait: %p", sem); + if (timeout != CSP_MAX_DELAY) + timeout = timeout / portTICK_RATE_MS; + if (xSemaphoreTake(*sem, timeout) == pdPASS) { + return CSP_SEMAPHORE_OK; + } else { + return CSP_SEMAPHORE_ERROR; + } +} + +int csp_bin_sem_post(csp_bin_sem_handle_t * sem) { + csp_log_lock("Post: %p", sem); + if (xSemaphoreGive(*sem) == pdPASS) { + return CSP_SEMAPHORE_OK; + } else { + return CSP_SEMAPHORE_ERROR; + } +} + +int csp_bin_sem_post_isr(csp_bin_sem_handle_t * sem, CSP_BASE_TYPE * task_woken) { + csp_log_lock("Post: %p", sem); + if (xSemaphoreGiveFromISR(*sem, task_woken) == pdPASS) { + return CSP_SEMAPHORE_OK; + } else { + return CSP_SEMAPHORE_ERROR; + } +} + diff --git a/thirdparty/libcsp/src/arch/freertos/csp_system.c b/thirdparty/libcsp/src/arch/freertos/csp_system.c new file mode 100644 index 00000000..a81c84b4 --- /dev/null +++ b/thirdparty/libcsp/src/arch/freertos/csp_system.c @@ -0,0 +1,139 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include +#include +#include +#include + +#include +#include + +#include + +int csp_sys_tasklist(char * out) { +#if (tskKERNEL_VERSION_MAJOR < 8) + vTaskList((signed portCHAR *) out); +#else + vTaskList(out); +#endif + return CSP_ERR_NONE; +} + +int csp_sys_tasklist_size(void) { + return 40 * uxTaskGetNumberOfTasks(); +} + +uint32_t csp_sys_memfree(void) { + + uint32_t total = 0, max = UINT32_MAX, size; + void * pmem; + + /* If size_t is less than 32 bits, start with 10 KiB */ + size = sizeof(uint32_t) > sizeof(size_t) ? 10000 : 1000000; + + while (1) { + pmem = pvPortMalloc(size + total); + if (pmem == NULL) { + max = size + total; + size = size / 2; + } else { + total += size; + if (total + size >= max) + size = size / 2; + vPortFree(pmem); + } + if (size < 32) break; + } + + return total; +} + +int csp_sys_reboot(void) { + + extern void __attribute__((weak)) cpu_set_reset_cause(unsigned int); + if (cpu_set_reset_cause) + cpu_set_reset_cause(1); + + extern void __attribute__((weak)) cpu_reset(void); + if (cpu_reset) { + cpu_reset(); + while (1); + } + + csp_log_error("Failed to reboot"); + + return CSP_ERR_INVAL; +} + +int csp_sys_shutdown(void) { + + extern void __attribute__((weak)) cpu_shutdown(void); + if (cpu_shutdown) { + cpu_shutdown(); + while (1); + } + + csp_log_error("Failed to shutdown"); + + return CSP_ERR_INVAL; +} + +void csp_sys_set_color(csp_color_t color) { + + unsigned int color_code, modifier_code; + switch (color & COLOR_MASK_COLOR) { + case COLOR_BLACK: + color_code = 30; break; + case COLOR_RED: + color_code = 31; break; + case COLOR_GREEN: + color_code = 32; break; + case COLOR_YELLOW: + color_code = 33; break; + case COLOR_BLUE: + color_code = 34; break; + case COLOR_MAGENTA: + color_code = 35; break; + case COLOR_CYAN: + color_code = 36; break; + case COLOR_WHITE: + color_code = 37; break; + case COLOR_RESET: + default: + color_code = 0; break; + } + + switch (color & COLOR_MASK_MODIFIER) { + case COLOR_BOLD: + modifier_code = 1; break; + case COLOR_UNDERLINE: + modifier_code = 2; break; + case COLOR_BLINK: + modifier_code = 3; break; + case COLOR_HIDE: + modifier_code = 4; break; + case COLOR_NORMAL: + default: + modifier_code = 0; break; + } + + printf("\033[%u;%um", modifier_code, color_code); +} diff --git a/thirdparty/libcsp/src/arch/freertos/csp_thread.c b/thirdparty/libcsp/src/arch/freertos/csp_thread.c new file mode 100644 index 00000000..af8296cd --- /dev/null +++ b/thirdparty/libcsp/src/arch/freertos/csp_thread.c @@ -0,0 +1,38 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include +#include + +/* CSP includes */ +#include + +#include + +int csp_thread_create(csp_thread_return_t (* routine)(void *), const char * const thread_name, unsigned short stack_depth, void * parameters, unsigned int priority, csp_thread_handle_t * handle) { +#if (tskKERNEL_VERSION_MAJOR >= 8) + portBASE_TYPE ret = xTaskCreate(routine, thread_name, stack_depth, parameters, priority, handle); +#else + portBASE_TYPE ret = xTaskCreate(routine, (signed char *) thread_name, stack_depth, parameters, priority, handle); +#endif + if (ret != pdTRUE) + return CSP_ERR_NOMEM; + return CSP_ERR_NONE; +} diff --git a/thirdparty/libcsp/src/arch/freertos/csp_time.c b/thirdparty/libcsp/src/arch/freertos/csp_time.c new file mode 100644 index 00000000..fd54a8cb --- /dev/null +++ b/thirdparty/libcsp/src/arch/freertos/csp_time.c @@ -0,0 +1,46 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include + +/* FreeRTOS includes */ +#include +#include + +/* CSP includes */ +#include + +#include + +uint32_t csp_get_ms(void) { + return (uint32_t)(xTaskGetTickCount() * (1000/configTICK_RATE_HZ)); +} + +uint32_t csp_get_ms_isr(void) { + return (uint32_t)(xTaskGetTickCountFromISR() * (1000/configTICK_RATE_HZ)); +} + +uint32_t csp_get_s(void) { + return (uint32_t)(xTaskGetTickCount()/configTICK_RATE_HZ); +} + +uint32_t csp_get_s_isr(void) { + return (uint32_t)(xTaskGetTickCountFromISR()/configTICK_RATE_HZ); +} diff --git a/thirdparty/libcsp/src/arch/macosx/csp_malloc.c b/thirdparty/libcsp/src/arch/macosx/csp_malloc.c new file mode 100644 index 00000000..95bb8cc7 --- /dev/null +++ b/thirdparty/libcsp/src/arch/macosx/csp_malloc.c @@ -0,0 +1,31 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include +#include + +void * csp_malloc(size_t size) { + return malloc(size); +} + +void csp_free(void *ptr) { + free(ptr); +} + diff --git a/thirdparty/libcsp/src/arch/macosx/csp_queue.c b/thirdparty/libcsp/src/arch/macosx/csp_queue.c new file mode 100644 index 00000000..a2fb1b4f --- /dev/null +++ b/thirdparty/libcsp/src/arch/macosx/csp_queue.c @@ -0,0 +1,64 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include +#include + +/* CSP includes */ +#include + +#include +#include + + +csp_queue_handle_t csp_queue_create(int length, size_t item_size) { + return pthread_queue_create(length, item_size); +} + +void csp_queue_remove(csp_queue_handle_t queue) { + return pthread_queue_delete(queue); +} + +int csp_queue_enqueue(csp_queue_handle_t handle, void *value, uint32_t timeout) { + return pthread_queue_enqueue(handle, value, timeout); +} + +int csp_queue_enqueue_isr(csp_queue_handle_t handle, void * value, CSP_BASE_TYPE * task_woken) { + if (task_woken != NULL) + *task_woken = 0; + return csp_queue_enqueue(handle, value, 0); +} + +int csp_queue_dequeue(csp_queue_handle_t handle, void *buf, uint32_t timeout) { + return pthread_queue_dequeue(handle, buf, timeout); +} + +int csp_queue_dequeue_isr(csp_queue_handle_t handle, void *buf, CSP_BASE_TYPE * task_woken) { + *task_woken = 0; + return csp_queue_dequeue(handle, buf, 0); +} + +int csp_queue_size(csp_queue_handle_t handle) { + return pthread_queue_items(handle); +} + +int csp_queue_size_isr(csp_queue_handle_t handle) { + return pthread_queue_items(handle); +} diff --git a/thirdparty/libcsp/src/arch/macosx/csp_semaphore.c b/thirdparty/libcsp/src/arch/macosx/csp_semaphore.c new file mode 100644 index 00000000..915447f3 --- /dev/null +++ b/thirdparty/libcsp/src/arch/macosx/csp_semaphore.c @@ -0,0 +1,105 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +/* CSP includes */ +#include + +#include + +int csp_mutex_create(csp_mutex_t * mutex) { + csp_log_lock("Mutex init: %p", mutex); + *mutex = pthread_queue_create(1, sizeof(int)); + if (mutex) { + int dummy = 0; + pthread_queue_enqueue(*mutex, &dummy, 0); + return CSP_SEMAPHORE_OK; + } else { + return CSP_SEMAPHORE_ERROR; + } +} + +int csp_mutex_remove(csp_mutex_t * mutex) { + pthread_queue_delete(*mutex); + return CSP_SEMAPHORE_OK; +} + +int csp_mutex_lock(csp_mutex_t * mutex, uint32_t timeout) { + + int ret; + csp_log_lock("Wait: %p timeout %"PRIu32, mutex, timeout); + + if (timeout == CSP_INFINITY) { + /* TODO: fix this to be infinite */ + int dummy = 0; + if (pthread_queue_dequeue(*mutex, &dummy, timeout) == PTHREAD_QUEUE_OK) + ret = CSP_MUTEX_OK; + else + ret = CSP_MUTEX_ERROR; + } else { + int dummy = 0; + if (pthread_queue_dequeue(*mutex, &dummy, timeout) == PTHREAD_QUEUE_OK) + ret = CSP_MUTEX_OK; + else + ret = CSP_MUTEX_ERROR; + } + + return ret == CSP_MUTEX_ERROR ? CSP_SEMAPHORE_ERROR : CSP_SEMAPHORE_OK; +} + +int csp_mutex_unlock(csp_mutex_t * mutex) { + int dummy = 0; + if (pthread_queue_enqueue(*mutex, &dummy, 0) == PTHREAD_QUEUE_OK) { + return CSP_SEMAPHORE_OK; + } else { + return CSP_SEMAPHORE_ERROR; + } +} + +int csp_bin_sem_create(csp_bin_sem_handle_t * sem) { + return csp_mutex_create(sem); +} + +int csp_bin_sem_remove(csp_bin_sem_handle_t * sem) { + return csp_mutex_remove(sem); +} + +int csp_bin_sem_wait(csp_bin_sem_handle_t * sem, uint32_t timeout) { + return csp_mutex_lock(sem, timeout); +} + +int csp_bin_sem_post(csp_bin_sem_handle_t * sem) { + return csp_mutex_unlock(sem); +} + +int csp_bin_sem_post_isr(csp_bin_sem_handle_t * sem, CSP_BASE_TYPE * task_woken) { + return csp_mutex_unlock(sem); +} diff --git a/thirdparty/libcsp/src/arch/macosx/csp_system.c b/thirdparty/libcsp/src/arch/macosx/csp_system.c new file mode 100644 index 00000000..834cb210 --- /dev/null +++ b/thirdparty/libcsp/src/arch/macosx/csp_system.c @@ -0,0 +1,99 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include +#include +#include + +#include +#include + +#include + +int csp_sys_tasklist(char * out) { + strcpy(out, "Tasklist not available on OSX"); + return CSP_ERR_NONE; +} + +int csp_sys_tasklist_size(void) { + return 100; +} + +uint32_t csp_sys_memfree(void) { + /* TODO: Fix memory free on OSX */ + uint32_t total = 0; + return total; +} + +int csp_sys_reboot(void) { + /* TODO: Fix reboot on OSX */ + csp_log_error("Failed to reboot"); + + return CSP_ERR_INVAL; +} + +int csp_sys_shutdown(void) { + /* TODO: Fix shutdown on OSX */ + csp_log_error("Failed to shutdown"); + + return CSP_ERR_INVAL; +} + +void csp_sys_set_color(csp_color_t color) { + + unsigned int color_code, modifier_code; + switch (color & COLOR_MASK_COLOR) { + case COLOR_BLACK: + color_code = 30; break; + case COLOR_RED: + color_code = 31; break; + case COLOR_GREEN: + color_code = 32; break; + case COLOR_YELLOW: + color_code = 33; break; + case COLOR_BLUE: + color_code = 34; break; + case COLOR_MAGENTA: + color_code = 35; break; + case COLOR_CYAN: + color_code = 36; break; + case COLOR_WHITE: + color_code = 37; break; + case COLOR_RESET: + default: + color_code = 0; break; + } + + switch (color & COLOR_MASK_MODIFIER) { + case COLOR_BOLD: + modifier_code = 1; break; + case COLOR_UNDERLINE: + modifier_code = 2; break; + case COLOR_BLINK: + modifier_code = 3; break; + case COLOR_HIDE: + modifier_code = 4; break; + case COLOR_NORMAL: + default: + modifier_code = 0; break; + } + + printf("\033[%u;%um", modifier_code, color_code); +} diff --git a/thirdparty/libcsp/src/arch/macosx/csp_thread.c b/thirdparty/libcsp/src/arch/macosx/csp_thread.c new file mode 100644 index 00000000..ed64856a --- /dev/null +++ b/thirdparty/libcsp/src/arch/macosx/csp_thread.c @@ -0,0 +1,31 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include +#include + +/* CSP includes */ +#include + +#include + +int csp_thread_create(csp_thread_return_t (* routine)(void *), const char * const thread_name, unsigned short stack_depth, void * parameters, unsigned int priority, csp_thread_handle_t * handle) { + return pthread_create(handle, NULL, routine, parameters); +} diff --git a/thirdparty/libcsp/src/arch/macosx/csp_time.c b/thirdparty/libcsp/src/arch/macosx/csp_time.c new file mode 100644 index 00000000..a53f27e6 --- /dev/null +++ b/thirdparty/libcsp/src/arch/macosx/csp_time.c @@ -0,0 +1,65 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include +#include +#include +#include + +/* CSP includes */ +#include + +#include + +uint32_t csp_get_ms(void) { + struct timespec ts; + + clock_serv_t cclock; + mach_timespec_t mts; + host_get_clock_service(mach_host_self(), CALENDAR_CLOCK, &cclock); + clock_get_time(cclock, &mts); + mach_port_deallocate(mach_task_self(), cclock); + ts.tv_sec = mts.tv_sec; + ts.tv_nsec = mts.tv_nsec; + + return (uint32_t)(ts.tv_sec*1000+ts.tv_nsec/1000000); +} + +uint32_t csp_get_ms_isr(void) { + return csp_get_ms(); +} + +uint32_t csp_get_s(void) { + struct timespec ts; + + clock_serv_t cclock; + mach_timespec_t mts; + host_get_clock_service(mach_host_self(), CALENDAR_CLOCK, &cclock); + clock_get_time(cclock, &mts); + mach_port_deallocate(mach_task_self(), cclock); + ts.tv_sec = mts.tv_sec; + ts.tv_nsec = mts.tv_nsec; + + return (uint32_t)ts.tv_sec; +} + +uint32_t csp_get_s_isr(void) { + return csp_get_s(); +} diff --git a/thirdparty/libcsp/src/arch/macosx/pthread_queue.c b/thirdparty/libcsp/src/arch/macosx/pthread_queue.c new file mode 100644 index 00000000..c4ac8c1d --- /dev/null +++ b/thirdparty/libcsp/src/arch/macosx/pthread_queue.c @@ -0,0 +1,179 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +/* +Inspired by c-pthread-queue by Matthew Dickinson +http://code.google.com/p/c-pthread-queue/ +*/ + +#include +#include +#include +#include +#include +#include +#include + +/* CSP includes */ +#include + +pthread_queue_t * pthread_queue_create(int length, size_t item_size) { + + pthread_queue_t * q = malloc(sizeof(pthread_queue_t)); + + if (q != NULL) { + q->buffer = malloc(length*item_size); + if (q->buffer != NULL) { + q->size = length; + q->item_size = item_size; + q->items = 0; + q->in = 0; + q->out = 0; + if (pthread_mutex_init(&(q->mutex), NULL) || pthread_cond_init(&(q->cond_full), NULL) || pthread_cond_init(&(q->cond_empty), NULL)) { + free(q->buffer); + free(q); + q = NULL; + } + } else { + free(q); + q = NULL; + } + } + + return q; + +} + +void pthread_queue_delete(pthread_queue_t * q) { + + if (q == NULL) + return; + + free(q->buffer); + free(q); + + return; + +} + +int pthread_queue_enqueue(pthread_queue_t * queue, void * value, uint32_t timeout) { + + int ret; + + /* Calculate timeout */ + struct timespec ts; + + clock_serv_t cclock; + mach_timespec_t mts; + host_get_clock_service(mach_host_self(), CALENDAR_CLOCK, &cclock); + clock_get_time(cclock, &mts); + mach_port_deallocate(mach_task_self(), cclock); + ts.tv_sec = mts.tv_sec; + ts.tv_nsec = mts.tv_nsec; + + uint32_t sec = timeout / 1000; + uint32_t nsec = (timeout - 1000 * sec) * 1000000; + + ts.tv_sec += sec; + + if (ts.tv_nsec + nsec > 1000000000) + ts.tv_sec++; + + ts.tv_nsec = (ts.tv_nsec + nsec) % 1000000000; + + /* Get queue lock */ + pthread_mutex_lock(&(queue->mutex)); + while (queue->items == queue->size) { + ret = pthread_cond_timedwait(&(queue->cond_full), &(queue->mutex), &ts); + if (ret != 0) { + pthread_mutex_unlock(&(queue->mutex)); + return PTHREAD_QUEUE_FULL; + } + } + + /* Coby object from input buffer */ + memcpy(queue->buffer+(queue->in * queue->item_size), value, queue->item_size); + queue->items++; + queue->in = (queue->in + 1) % queue->size; + pthread_mutex_unlock(&(queue->mutex)); + + /* Nofify blocked threads */ + pthread_cond_broadcast(&(queue->cond_empty)); + + return PTHREAD_QUEUE_OK; + +} + +int pthread_queue_dequeue(pthread_queue_t * queue, void * buf, uint32_t timeout) { + + int ret; + + /* Calculate timeout */ + struct timespec ts; + clock_serv_t cclock; + mach_timespec_t mts; + host_get_clock_service(mach_host_self(), CALENDAR_CLOCK, &cclock); + clock_get_time(cclock, &mts); + mach_port_deallocate(mach_task_self(), cclock); + ts.tv_sec = mts.tv_sec; + ts.tv_nsec = mts.tv_nsec; + + uint32_t sec = timeout / 1000; + uint32_t nsec = (timeout - 1000 * sec) * 1000000; + + ts.tv_sec += sec; + + if (ts.tv_nsec + nsec > 1000000000) + ts.tv_sec++; + + ts.tv_nsec = (ts.tv_nsec + nsec) % 1000000000; + + /* Get queue lock */ + pthread_mutex_lock(&(queue->mutex)); + while (queue->items == 0) { + ret = pthread_cond_timedwait(&(queue->cond_empty), &(queue->mutex), &ts); + if (ret != 0) { + pthread_mutex_unlock(&(queue->mutex)); + return PTHREAD_QUEUE_EMPTY; + } + } + + /* Coby object to output buffer */ + memcpy(buf, queue->buffer+(queue->out * queue->item_size), queue->item_size); + queue->items--; + queue->out = (queue->out + 1) % queue->size; + pthread_mutex_unlock(&(queue->mutex)); + + /* Nofify blocked threads */ + pthread_cond_broadcast(&(queue->cond_full)); + + return PTHREAD_QUEUE_OK; + +} + +int pthread_queue_items(pthread_queue_t * queue) { + + pthread_mutex_lock(&(queue->mutex)); + int items = queue->items; + pthread_mutex_unlock(&(queue->mutex)); + + return items; + +} diff --git a/thirdparty/libcsp/src/arch/posix/CMakeLists.txt b/thirdparty/libcsp/src/arch/posix/CMakeLists.txt new file mode 100644 index 00000000..6bf13773 --- /dev/null +++ b/thirdparty/libcsp/src/arch/posix/CMakeLists.txt @@ -0,0 +1,9 @@ +target_sources(${LIB_CSP_NAME} PRIVATE + csp_malloc.c + csp_queue.c + csp_semaphore.c + csp_system.c + csp_thread.c + csp_time.c + pthread_queue.c +) diff --git a/thirdparty/libcsp/src/arch/posix/csp_malloc.c b/thirdparty/libcsp/src/arch/posix/csp_malloc.c new file mode 100644 index 00000000..95bb8cc7 --- /dev/null +++ b/thirdparty/libcsp/src/arch/posix/csp_malloc.c @@ -0,0 +1,31 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include +#include + +void * csp_malloc(size_t size) { + return malloc(size); +} + +void csp_free(void *ptr) { + free(ptr); +} + diff --git a/thirdparty/libcsp/src/arch/posix/csp_queue.c b/thirdparty/libcsp/src/arch/posix/csp_queue.c new file mode 100644 index 00000000..a2fb1b4f --- /dev/null +++ b/thirdparty/libcsp/src/arch/posix/csp_queue.c @@ -0,0 +1,64 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include +#include + +/* CSP includes */ +#include + +#include +#include + + +csp_queue_handle_t csp_queue_create(int length, size_t item_size) { + return pthread_queue_create(length, item_size); +} + +void csp_queue_remove(csp_queue_handle_t queue) { + return pthread_queue_delete(queue); +} + +int csp_queue_enqueue(csp_queue_handle_t handle, void *value, uint32_t timeout) { + return pthread_queue_enqueue(handle, value, timeout); +} + +int csp_queue_enqueue_isr(csp_queue_handle_t handle, void * value, CSP_BASE_TYPE * task_woken) { + if (task_woken != NULL) + *task_woken = 0; + return csp_queue_enqueue(handle, value, 0); +} + +int csp_queue_dequeue(csp_queue_handle_t handle, void *buf, uint32_t timeout) { + return pthread_queue_dequeue(handle, buf, timeout); +} + +int csp_queue_dequeue_isr(csp_queue_handle_t handle, void *buf, CSP_BASE_TYPE * task_woken) { + *task_woken = 0; + return csp_queue_dequeue(handle, buf, 0); +} + +int csp_queue_size(csp_queue_handle_t handle) { + return pthread_queue_items(handle); +} + +int csp_queue_size_isr(csp_queue_handle_t handle) { + return pthread_queue_items(handle); +} diff --git a/thirdparty/libcsp/src/arch/posix/csp_semaphore.c b/thirdparty/libcsp/src/arch/posix/csp_semaphore.c new file mode 100644 index 00000000..6829dec2 --- /dev/null +++ b/thirdparty/libcsp/src/arch/posix/csp_semaphore.c @@ -0,0 +1,164 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +/* CSP includes */ +#include + +#include + +int csp_mutex_create(csp_mutex_t * mutex) { + csp_log_lock("Mutex init: %p", mutex); + if (pthread_mutex_init(mutex, NULL) == 0) { + return CSP_SEMAPHORE_OK; + } else { + return CSP_SEMAPHORE_ERROR; + } +} + +int csp_mutex_remove(csp_mutex_t * mutex) { + if (pthread_mutex_destroy(mutex) == 0) { + return CSP_SEMAPHORE_OK; + } else { + return CSP_SEMAPHORE_ERROR; + } +} + +int csp_mutex_lock(csp_mutex_t * mutex, uint32_t timeout) { + + int ret; + struct timespec ts; + uint32_t sec, nsec; + + csp_log_lock("Wait: %p timeout %"PRIu32, mutex, timeout); + + if (timeout == CSP_INFINITY) { + ret = pthread_mutex_lock(mutex); + } else { + if (clock_gettime(CLOCK_REALTIME, &ts)) + return CSP_SEMAPHORE_ERROR; + + sec = timeout / 1000; + nsec = (timeout - 1000 * sec) * 1000000; + + ts.tv_sec += sec; + + if (ts.tv_nsec + nsec >= 1000000000) + ts.tv_sec++; + + ts.tv_nsec = (ts.tv_nsec + nsec) % 1000000000; + + ret = pthread_mutex_timedlock(mutex, &ts); + } + + if (ret != 0) + return CSP_SEMAPHORE_ERROR; + + return CSP_SEMAPHORE_OK; +} + +int csp_mutex_unlock(csp_mutex_t * mutex) { + if (pthread_mutex_unlock(mutex) == 0) { + return CSP_SEMAPHORE_OK; + } else { + return CSP_SEMAPHORE_ERROR; + } +} + +int csp_bin_sem_create(csp_bin_sem_handle_t * sem) { + csp_log_lock("Semaphore init: %p", sem); + if (sem_init(sem, 0, 1) == 0) { + return CSP_SEMAPHORE_OK; + } else { + return CSP_SEMAPHORE_ERROR; + } +} + +int csp_bin_sem_remove(csp_bin_sem_handle_t * sem) { + if (sem_destroy(sem) == 0) + return CSP_SEMAPHORE_OK; + else + return CSP_SEMAPHORE_ERROR; +} + +int csp_bin_sem_wait(csp_bin_sem_handle_t * sem, uint32_t timeout) { + + int ret; + struct timespec ts; + uint32_t sec, nsec; + + csp_log_lock("Wait: %p timeout %"PRIu32, sem, timeout); + + if (timeout == CSP_INFINITY) { + ret = sem_wait(sem); + } else { + if (clock_gettime(CLOCK_REALTIME, &ts)) + return CSP_SEMAPHORE_ERROR; + + sec = timeout / 1000; + nsec = (timeout - 1000 * sec) * 1000000; + + ts.tv_sec += sec; + + if (ts.tv_nsec + nsec >= 1000000000) + ts.tv_sec++; + + ts.tv_nsec = (ts.tv_nsec + nsec) % 1000000000; + + ret = sem_timedwait(sem, &ts); + } + + if (ret != 0) + return CSP_SEMAPHORE_ERROR; + + return CSP_SEMAPHORE_OK; +} + +int csp_bin_sem_post(csp_bin_sem_handle_t * sem) { + CSP_BASE_TYPE dummy = 0; + return csp_bin_sem_post_isr(sem, &dummy); +} + +int csp_bin_sem_post_isr(csp_bin_sem_handle_t * sem, CSP_BASE_TYPE * task_woken) { + csp_log_lock("Post: %p", sem); + *task_woken = 0; + + int value; + sem_getvalue(sem, &value); + if (value > 0) + return CSP_SEMAPHORE_OK; + + if (sem_post(sem) == 0) { + return CSP_SEMAPHORE_OK; + } else { + return CSP_SEMAPHORE_ERROR; + } +} diff --git a/thirdparty/libcsp/src/arch/posix/csp_system.c b/thirdparty/libcsp/src/arch/posix/csp_system.c new file mode 100644 index 00000000..6c882c7c --- /dev/null +++ b/thirdparty/libcsp/src/arch/posix/csp_system.c @@ -0,0 +1,131 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +#include + +int csp_sys_tasklist(char * out) { + strcpy(out, "Tasklist not available on POSIX"); + return CSP_ERR_NONE; +} + +int csp_sys_tasklist_size(void) { + return 100; +} + +uint32_t csp_sys_memfree(void) { + uint32_t total = 0; + struct sysinfo info; + sysinfo(&info); + total = info.freeram * info.mem_unit; + return total; +} + +int csp_sys_reboot(void) { +#ifdef CSP_USE_INIT_SHUTDOWN + /* Let init(1) handle the reboot */ + int ret = system("reboot"); + (void) ret; /* Silence warning */ +#else + int magic = LINUX_REBOOT_CMD_RESTART; + + /* Sync filesystem before reboot */ + sync(); + reboot(magic); +#endif + + /* If reboot(2) returns, it is an error */ + csp_log_error("Failed to reboot: %s", strerror(errno)); + + return CSP_ERR_INVAL; +} + +int csp_sys_shutdown(void) { +#ifdef CSP_USE_INIT_SHUTDOWN + /* Let init(1) handle the shutdown */ + int ret = system("halt"); + (void) ret; /* Silence warning */ +#else + int magic = LINUX_REBOOT_CMD_HALT; + + /* Sync filesystem before reboot */ + sync(); + reboot(magic); +#endif + + /* If reboot(2) returns, it is an error */ + csp_log_error("Failed to shutdown: %s", strerror(errno)); + + return CSP_ERR_INVAL; +} + +void csp_sys_set_color(csp_color_t color) { + + unsigned int color_code, modifier_code; + switch (color & COLOR_MASK_COLOR) { + case COLOR_BLACK: + color_code = 30; break; + case COLOR_RED: + color_code = 31; break; + case COLOR_GREEN: + color_code = 32; break; + case COLOR_YELLOW: + color_code = 33; break; + case COLOR_BLUE: + color_code = 34; break; + case COLOR_MAGENTA: + color_code = 35; break; + case COLOR_CYAN: + color_code = 36; break; + case COLOR_WHITE: + color_code = 37; break; + case COLOR_RESET: + default: + color_code = 0; break; + } + + switch (color & COLOR_MASK_MODIFIER) { + case COLOR_BOLD: + modifier_code = 1; break; + case COLOR_UNDERLINE: + modifier_code = 2; break; + case COLOR_BLINK: + modifier_code = 3; break; + case COLOR_HIDE: + modifier_code = 4; break; + case COLOR_NORMAL: + default: + modifier_code = 0; break; + } + + printf("\033[%u;%um", modifier_code, color_code); +} diff --git a/thirdparty/libcsp/src/arch/posix/csp_thread.c b/thirdparty/libcsp/src/arch/posix/csp_thread.c new file mode 100644 index 00000000..3277d35d --- /dev/null +++ b/thirdparty/libcsp/src/arch/posix/csp_thread.c @@ -0,0 +1,55 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include +#include +#include + +/* CSP includes */ +#include + +#include + +int csp_thread_create(csp_thread_return_t (* routine)(void *), const char * const thread_name, unsigned short stack_depth, void * parameters, unsigned int priority, csp_thread_handle_t * handle) { + pthread_attr_t attributes, *attr_ref; + int return_code; + + if( pthread_attr_init(&attributes) == 0 ) + { + unsigned int stack_size = PTHREAD_STACK_MIN;// use at least one memory page + + while(stack_size < stack_depth)// must reach at least the provided size + { + stack_size += PTHREAD_STACK_MIN;// keep memory page boundary (some systems may fail otherwise)) + } + attr_ref = &attributes; + + pthread_attr_setdetachstate(attr_ref, PTHREAD_CREATE_DETACHED);// do not waste memory on each call + pthread_attr_setstacksize(attr_ref, stack_size); + } + else + { + attr_ref = NULL; + } + return_code = pthread_create(handle, attr_ref, routine, parameters); + if( attr_ref != NULL ) pthread_attr_destroy(attr_ref); + + return return_code; +} diff --git a/thirdparty/libcsp/src/arch/posix/csp_time.c b/thirdparty/libcsp/src/arch/posix/csp_time.c new file mode 100644 index 00000000..c9677443 --- /dev/null +++ b/thirdparty/libcsp/src/arch/posix/csp_time.c @@ -0,0 +1,54 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include +#include +#include + +/* CSP includes */ +#include + +#include + +uint32_t csp_get_ms(void) { + struct timespec ts; + + if (clock_gettime(CLOCK_MONOTONIC, &ts) == 0) + return (uint32_t)(ts.tv_sec*1000+ts.tv_nsec/1000000); + else + return 0; +} + +uint32_t csp_get_ms_isr(void) { + return csp_get_ms(); +} + +uint32_t csp_get_s(void) { + struct timespec ts; + + if (clock_gettime(CLOCK_MONOTONIC, &ts) == 0) + return (uint32_t)ts.tv_sec; + else + return 0; +} + +uint32_t csp_get_s_isr(void) { + return csp_get_s(); +} diff --git a/thirdparty/libcsp/src/arch/posix/pthread_queue.c b/thirdparty/libcsp/src/arch/posix/pthread_queue.c new file mode 100644 index 00000000..e8b6d4ab --- /dev/null +++ b/thirdparty/libcsp/src/arch/posix/pthread_queue.c @@ -0,0 +1,243 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +/* +Inspired by c-pthread-queue by Matthew Dickinson +http://code.google.com/p/c-pthread-queue/ +*/ + +#include +#include +#include +#include +#include +#include +#include + +/* CSP includes */ +#include + +static inline int get_deadline(struct timespec *ts, uint32_t timeout_ms) +{ + int ret = clock_gettime(CLOCK_MONOTONIC, ts); + + if (ret < 0) { + return ret; + } + + uint32_t sec = timeout_ms / 1000; + uint32_t nsec = (timeout_ms - 1000 * sec) * 1000000; + + ts->tv_sec += sec; + + if (ts->tv_nsec + nsec >= 1000000000) { + ts->tv_sec++; + } + + ts->tv_nsec = (ts->tv_nsec + nsec) % 1000000000; + + return ret; +} + +static inline int init_cond_clock_monotonic(pthread_cond_t * cond) +{ + + int ret; + pthread_condattr_t attr; + + pthread_condattr_init(&attr); + ret = pthread_condattr_setclock(&attr, CLOCK_MONOTONIC); + + if (ret == 0) { + ret = pthread_cond_init(cond, &attr); + } + + pthread_condattr_destroy(&attr); + return ret; + +} + +pthread_queue_t * pthread_queue_create(int length, size_t item_size) { + + pthread_queue_t * q = malloc(sizeof(pthread_queue_t)); + + if (q != NULL) { + q->buffer = malloc(length*item_size); + if (q->buffer != NULL) { + q->size = length; + q->item_size = item_size; + q->items = 0; + q->in = 0; + q->out = 0; + if (pthread_mutex_init(&(q->mutex), NULL) || init_cond_clock_monotonic(&(q->cond_full)) || init_cond_clock_monotonic(&(q->cond_empty))) { + free(q->buffer); + free(q); + q = NULL; + } + } else { + free(q); + q = NULL; + } + } + + return q; + +} + +void pthread_queue_delete(pthread_queue_t * q) { + + if (q == NULL) + return; + + free(q->buffer); + free(q); + + return; + +} + + +static inline int wait_slot_available(pthread_queue_t * queue, struct timespec *ts) { + + int ret; + + while (queue->items == queue->size) { + + if (ts != NULL) { + ret = pthread_cond_timedwait(&(queue->cond_full), &(queue->mutex), ts); + } else { + ret = pthread_cond_wait(&(queue->cond_full), &(queue->mutex)); + } + + if (ret != 0 && errno != EINTR) { + return PTHREAD_QUEUE_FULL; //Timeout + } + } + + return PTHREAD_QUEUE_OK; + +} + +int pthread_queue_enqueue(pthread_queue_t * queue, void * value, uint32_t timeout) { + + int ret; + struct timespec ts; + struct timespec *pts = NULL; + + /* Calculate timeout */ + if (timeout != CSP_MAX_DELAY) { + if (get_deadline(&ts, timeout) != 0) { + return PTHREAD_QUEUE_ERROR; + } + pts = &ts; + } else { + pts = NULL; + } + + /* Get queue lock */ + pthread_mutex_lock(&(queue->mutex)); + + ret = wait_slot_available(queue, pts); + if (ret == PTHREAD_QUEUE_OK) { + /* Copy object from input buffer */ + memcpy(queue->buffer+(queue->in * queue->item_size), value, queue->item_size); + queue->items++; + queue->in = (queue->in + 1) % queue->size; + } + + pthread_mutex_unlock(&(queue->mutex)); + + if (ret == PTHREAD_QUEUE_OK) { + /* Nofify blocked threads */ + pthread_cond_broadcast(&(queue->cond_empty)); + } + + return ret; + +} + +static inline int wait_item_available(pthread_queue_t * queue, struct timespec *ts) { + + int ret; + + while (queue->items == 0) { + + if (ts != NULL) { + ret = pthread_cond_timedwait(&(queue->cond_empty), &(queue->mutex), ts); + } else { + ret = pthread_cond_wait(&(queue->cond_empty), &(queue->mutex)); + } + + if (ret != 0 && errno != EINTR) { + return PTHREAD_QUEUE_EMPTY; //Timeout + } + } + + return PTHREAD_QUEUE_OK; + +} + +int pthread_queue_dequeue(pthread_queue_t * queue, void * buf, uint32_t timeout) { + + int ret; + struct timespec ts; + struct timespec *pts; + + /* Calculate timeout */ + if (timeout != CSP_MAX_DELAY) { + if (get_deadline(&ts, timeout) != 0) { + return PTHREAD_QUEUE_ERROR; + } + pts = &ts; + } else { + pts = NULL; + } + + /* Get queue lock */ + pthread_mutex_lock(&(queue->mutex)); + + ret = wait_item_available(queue, pts); + if (ret == PTHREAD_QUEUE_OK) { + /* Coby object to output buffer */ + memcpy(buf, queue->buffer+(queue->out * queue->item_size), queue->item_size); + queue->items--; + queue->out = (queue->out + 1) % queue->size; + } + + pthread_mutex_unlock(&(queue->mutex)); + + if (ret == PTHREAD_QUEUE_OK) { + /* Nofify blocked threads */ + pthread_cond_broadcast(&(queue->cond_full)); + } + + return ret; + +} + +int pthread_queue_items(pthread_queue_t * queue) { + + pthread_mutex_lock(&(queue->mutex)); + int items = queue->items; + pthread_mutex_unlock(&(queue->mutex)); + + return items; + +} diff --git a/thirdparty/libcsp/src/arch/windows/README b/thirdparty/libcsp/src/arch/windows/README new file mode 100644 index 00000000..b97ce7f5 --- /dev/null +++ b/thirdparty/libcsp/src/arch/windows/README @@ -0,0 +1,18 @@ +This directory contains files specific to the windows port of libcsp. + +To compile and create a static library, execute: + + python waf configure --with-os=windows build + +from the root of this project. Note python must be in PATH. + +The build requirements are: + * Windows Vista SP1 + * A recent version of MinGW _or_ MinGW-w64 + * Windows API headers + * cPython 2.5 or newer + +What provides the Windows API headers depends on the development environment: +Using MinGW: Headers provided by w32api package. windows_glue.h header is needed because these headers do not declare condition variables. +Using MinGW-w64: Headers should be available in the default configuration. You may have to compile the distribution from source. windows_glue.h should not be needed. + diff --git a/thirdparty/libcsp/src/arch/windows/csp_malloc.c b/thirdparty/libcsp/src/arch/windows/csp_malloc.c new file mode 100644 index 00000000..4b301e49 --- /dev/null +++ b/thirdparty/libcsp/src/arch/windows/csp_malloc.c @@ -0,0 +1,9 @@ +#include + +void * csp_malloc(size_t size) { + return malloc(size); +} + +void csp_free(void * ptr) { + free(ptr); +} diff --git a/thirdparty/libcsp/src/arch/windows/csp_queue.c b/thirdparty/libcsp/src/arch/windows/csp_queue.c new file mode 100644 index 00000000..177f8fa9 --- /dev/null +++ b/thirdparty/libcsp/src/arch/windows/csp_queue.c @@ -0,0 +1,40 @@ +#include +#include +#include +#include "windows_queue.h" + +csp_queue_handle_t csp_queue_create(int length, size_t item_size) { + return windows_queue_create(length, item_size); +} + +void csp_queue_remove(csp_queue_handle_t queue) { + windows_queue_delete(queue); +} + +int csp_queue_enqueue(csp_queue_handle_t handle, void *value, uint32_t timeout) { + return windows_queue_enqueue(handle, value, timeout); +} + +int csp_queue_enqueue_isr(csp_queue_handle_t handle, void * value, CSP_BASE_TYPE * task_woken) { + if( task_woken != NULL ) + *task_woken = 0; + return windows_queue_enqueue(handle, value, 0); +} + +int csp_queue_dequeue(csp_queue_handle_t handle, void *buf, uint32_t timeout) { + return windows_queue_dequeue(handle, buf, timeout); +} + +int csp_queue_dequeue_isr(csp_queue_handle_t handle, void * buf, CSP_BASE_TYPE * task_woken) { + if( task_woken != NULL ) + *task_woken = 0; + return windows_queue_dequeue(handle, buf, 0); +} + +int csp_queue_size(csp_queue_handle_t handle) { + return windows_queue_items(handle); +} + +int csp_queue_size_isr(csp_queue_handle_t handle) { + return windows_queue_items(handle); +} diff --git a/thirdparty/libcsp/src/arch/windows/csp_semaphore.c b/thirdparty/libcsp/src/arch/windows/csp_semaphore.c new file mode 100644 index 00000000..aa69251e --- /dev/null +++ b/thirdparty/libcsp/src/arch/windows/csp_semaphore.c @@ -0,0 +1,74 @@ +#include +#include +#include + +int csp_mutex_create(csp_mutex_t * mutex) { + HANDLE mutexHandle = CreateMutex(NULL, FALSE, FALSE); + if( mutexHandle == NULL ) { + return CSP_MUTEX_ERROR; + } + *mutex = mutexHandle; + return CSP_MUTEX_OK; +} + +int csp_mutex_remove(csp_mutex_t * mutex) { + if( !CloseHandle(*mutex) ) { + return CSP_MUTEX_ERROR; + } + return CSP_MUTEX_OK; +} + +int csp_mutex_lock(csp_mutex_t * mutex, uint32_t timeout) { + if(WaitForSingleObject(*mutex, timeout) == WAIT_OBJECT_0) { + return CSP_MUTEX_OK; + } + return CSP_MUTEX_ERROR; + +} + +int csp_mutex_unlock(csp_mutex_t * mutex) { + if( !ReleaseMutex(*mutex) ) { + return CSP_MUTEX_ERROR; + } + return CSP_MUTEX_OK; +} + +int csp_bin_sem_create(csp_bin_sem_handle_t * sem) { + HANDLE semHandle = CreateSemaphore(NULL, 1, 1, NULL); + if( semHandle == NULL ) { + return CSP_SEMAPHORE_ERROR; + } + *sem = semHandle; + return CSP_SEMAPHORE_OK; +} + +int csp_bin_sem_remove(csp_bin_sem_handle_t * sem) { + if( !CloseHandle(*sem) ) { + return CSP_SEMAPHORE_ERROR; + } + return CSP_SEMAPHORE_OK; +} + +int csp_bin_sem_wait(csp_bin_sem_handle_t * sem, uint32_t timeout) { + if( WaitForSingleObject(*sem, timeout) == WAIT_OBJECT_0 ) { + return CSP_SEMAPHORE_OK; + } + return CSP_SEMAPHORE_ERROR; + +} + +int csp_bin_sem_post(csp_bin_sem_handle_t * sem) { + if( !ReleaseSemaphore(*sem, 1, NULL) ) { + return CSP_SEMAPHORE_ERROR; + } + return CSP_SEMAPHORE_OK; +} + +int csp_bin_sem_post_isr(csp_bin_sem_handle_t * sem, CSP_BASE_TYPE * task_woken) { + if( task_woken != NULL ) { + *task_woken = 0; + } + return csp_bin_sem_post(sem); +} + + diff --git a/thirdparty/libcsp/src/arch/windows/csp_system.c b/thirdparty/libcsp/src/arch/windows/csp_system.c new file mode 100644 index 00000000..262c2052 --- /dev/null +++ b/thirdparty/libcsp/src/arch/windows/csp_system.c @@ -0,0 +1,60 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include +#include +#include + +#include +#include + +#include + +int csp_sys_tasklist(char * out) { + strcpy(out, "Tasklist not available on Windows"); + return CSP_ERR_NONE; +} + +uint32_t csp_sys_memfree(void) { + MEMORYSTATUSEX statex; + statex.dwLength = sizeof(statex); + GlobalMemoryStatusEx(&statex); + DWORDLONG freePhysicalMem = statex.ullAvailPhys; + size_t total = (size_t) freePhysicalMem; + return (uint32_t)total; +} + +int csp_sys_reboot(void) { + /* TODO: Fix reboot on Windows */ + csp_log_error("Failed to reboot"); + + return CSP_ERR_INVAL; +} + +int csp_sys_shutdown(void) { + /* TODO: Fix shutdown on Windows */ + csp_log_error("Failed to shutdown"); + + return CSP_ERR_INVAL; +} + +void csp_sys_set_color(csp_color_t color) { + /* TODO: Add Windows color output here */ +} diff --git a/thirdparty/libcsp/src/arch/windows/csp_thread.c b/thirdparty/libcsp/src/arch/windows/csp_thread.c new file mode 100644 index 00000000..ef46a948 --- /dev/null +++ b/thirdparty/libcsp/src/arch/windows/csp_thread.c @@ -0,0 +1,11 @@ +#include +#include +#include + +int csp_thread_create(csp_thread_return_t (* routine)(void *)__attribute__((stdcall)), const char * const thread_name, unsigned short stack_depth, void * parameters, unsigned int priority, csp_thread_handle_t * handle) { + HANDLE taskHandle = (HANDLE) _beginthreadex(NULL, stack_depth, routine, parameters, 0, 0); + if( taskHandle == 0 ) + return CSP_ERR_NOMEM; // Failure + *handle = taskHandle; + return CSP_ERR_NONE; +} diff --git a/thirdparty/libcsp/src/arch/windows/csp_time.c b/thirdparty/libcsp/src/arch/windows/csp_time.c new file mode 100644 index 00000000..618292ab --- /dev/null +++ b/thirdparty/libcsp/src/arch/windows/csp_time.c @@ -0,0 +1,20 @@ +#include +#include +#include + +uint32_t csp_get_ms(void) { + return (uint32_t)GetTickCount(); +} + +uint32_t csp_get_ms_isr(void) { + return csp_get_ms(); +} + +uint32_t csp_get_s(void) { + uint32_t time_ms = csp_get_ms(); + return time_ms/1000; +} + +uint32_t csp_get_s_isr(void) { + return csp_get_s(); +} diff --git a/thirdparty/libcsp/src/arch/windows/windows_glue.h b/thirdparty/libcsp/src/arch/windows/windows_glue.h new file mode 100644 index 00000000..6e0cf6db --- /dev/null +++ b/thirdparty/libcsp/src/arch/windows/windows_glue.h @@ -0,0 +1,23 @@ +#ifndef WINDOWS_GLUE_H +#define WINDOWS_GLUE_H + +#include +#undef interface + +#if (_WIN32_WINNT >= 0x0600) + +#define RTL_CONDITION_VARIABLE_INIT 0 +#define RTL_CONDITION_VARIABLE_LOCKMODE_SHARED 1 +#define CONDITION_VARIABLE_INIT RTL_CONDITION_VARIABLE_INIT +#define CONDITION_VARIABLE_LOCKMODE_SHARED RTL_CONDITION_VARIABLE_LOCKMODE_SHARED + +typedef PVOID RTL_CONDITION_VARIABLE; +typedef RTL_CONDITION_VARIABLE CONDITION_VARIABLE, *PCONDITION_VARIABLE; + +WINBASEAPI VOID WINAPI InitializeConditionVariable(PCONDITION_VARIABLE ConditionVariable); +WINBASEAPI WINBOOL WINAPI SleepConditionVariableCS(PCONDITION_VARIABLE ConditionVariable, PCRITICAL_SECTION CriticalSection, DWORD dwMilliseconds); +WINBASEAPI VOID WINAPI WakeAllConditionVariable(PCONDITION_VARIABLE ConditionVariable); +WINBASEAPI VOID WINAPI WakeConditionVariable(PCONDITION_VARIABLE ConditionVariable); + +#endif // _WIN#"_WINNT +#endif diff --git a/thirdparty/libcsp/src/arch/windows/windows_queue.c b/thirdparty/libcsp/src/arch/windows/windows_queue.c new file mode 100644 index 00000000..aa337dc8 --- /dev/null +++ b/thirdparty/libcsp/src/arch/windows/windows_queue.c @@ -0,0 +1,91 @@ +#include "windows_queue.h" +#include "windows_glue.h" +#include + +static int queueFull(windows_queue_t * queue) { + return queue->items == queue->size; +} + +static int queueEmpty(windows_queue_t * queue) { + return queue->items == 0; +} + +windows_queue_t * windows_queue_create(int length, size_t item_size) { + windows_queue_t *queue = (windows_queue_t*)malloc(sizeof(windows_queue_t)); + if(queue == NULL) + goto queue_malloc_failed; + + queue->buffer = malloc(length*item_size); + if(queue->buffer == NULL) + goto buffer_malloc_failed; + + queue->size = length; + queue->item_size = item_size; + queue->items = 0; + queue->head_idx = 0; + + InitializeCriticalSection(&(queue->mutex)); + InitializeConditionVariable(&(queue->cond_full)); + InitializeConditionVariable(&(queue->cond_empty)); + goto queue_init_success; + +buffer_malloc_failed: + free(queue); + queue = NULL; +queue_malloc_failed: +queue_init_success: + return queue; +} + +void windows_queue_delete(windows_queue_t * q) { + if(q==NULL) return; + DeleteCriticalSection(&(q->mutex)); + free(q->buffer); + free(q); +} + +int windows_queue_enqueue(windows_queue_t * queue, void * value, int timeout) { + int offset; + EnterCriticalSection(&(queue->mutex)); + while(queueFull(queue)) { + int ret = SleepConditionVariableCS(&(queue->cond_full), &(queue->mutex), timeout); + if( !ret ) { + LeaveCriticalSection(&(queue->mutex)); + return ret == WAIT_TIMEOUT ? WINDOWS_QUEUE_FULL : WINDOWS_QUEUE_ERROR; + } + } + offset = ((queue->head_idx+queue->items) % queue->size) * queue->item_size; + memcpy((unsigned char*)queue->buffer + offset, value, queue->item_size); + queue->items++; + + LeaveCriticalSection(&(queue->mutex)); + WakeAllConditionVariable(&(queue->cond_empty)); + return WINDOWS_QUEUE_OK; +} + +int windows_queue_dequeue(windows_queue_t * queue, void * buf, int timeout) { + EnterCriticalSection(&(queue->mutex)); + while(queueEmpty(queue)) { + int ret = SleepConditionVariableCS(&(queue->cond_empty), &(queue->mutex), timeout); + if( !ret ) { + LeaveCriticalSection(&(queue->mutex)); + return ret == WAIT_TIMEOUT ? WINDOWS_QUEUE_EMPTY : WINDOWS_QUEUE_ERROR; + } + } + memcpy(buf, (unsigned char*)queue->buffer+(queue->head_idx%queue->size*queue->item_size), queue->item_size); + queue->items--; + queue->head_idx = (queue->head_idx + 1) % queue->size; + + LeaveCriticalSection(&(queue->mutex)); + WakeAllConditionVariable(&(queue->cond_full)); + return WINDOWS_QUEUE_OK; +} + +int windows_queue_items(windows_queue_t * queue) { + int items; + EnterCriticalSection(&(queue->mutex)); + items = queue->items; + LeaveCriticalSection(&(queue->mutex)); + + return items; +} diff --git a/thirdparty/libcsp/src/arch/windows/windows_queue.h b/thirdparty/libcsp/src/arch/windows/windows_queue.h new file mode 100644 index 00000000..e6bc5423 --- /dev/null +++ b/thirdparty/libcsp/src/arch/windows/windows_queue.h @@ -0,0 +1,41 @@ +#ifndef _WINDOWS_QUEUE_H_ +#define _WINDOWS_QUEUE_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +#include +#include "windows_glue.h" +#undef interface + +#include + +#define WINDOWS_QUEUE_ERROR CSP_QUEUE_ERROR +#define WINDOWS_QUEUE_EMPTY CSP_QUEUE_ERROR +#define WINDOWS_QUEUE_FULL CSP_QUEUE_ERROR +#define WINDOWS_QUEUE_OK CSP_QUEUE_OK + +typedef struct windows_queue_s { + void * buffer; + int size; + int item_size; + int items; + int head_idx; + CRITICAL_SECTION mutex; + CONDITION_VARIABLE cond_full; + CONDITION_VARIABLE cond_empty; +} windows_queue_t; + +windows_queue_t * windows_queue_create(int length, size_t item_size); +void windows_queue_delete(windows_queue_t * q); +int windows_queue_enqueue(windows_queue_t * queue, void * value, int timeout); +int windows_queue_dequeue(windows_queue_t * queue, void * buf, int timeout); +int windows_queue_items(windows_queue_t * queue); + +#ifdef __cplusplus +} /* extern "C" */ +#endif + +#endif // _WINDOWS_QUEUE_H_ + diff --git a/thirdparty/libcsp/src/bindings/python/pycsp.c b/thirdparty/libcsp/src/bindings/python/pycsp.c new file mode 100644 index 00000000..f1009d1a --- /dev/null +++ b/thirdparty/libcsp/src/bindings/python/pycsp.c @@ -0,0 +1,1052 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#if PY_MAJOR_VERSION == 3 +#define IS_PY3 +#endif + +static int is_capsule_of_type(PyObject* capsule, const char* expected_type) { + const char* capsule_name = PyCapsule_GetName(capsule); + if (strcmp(capsule_name, expected_type) != 0) { + PyErr_Format( + PyExc_TypeError, + "capsule contains unexpected type, expected=%s, got=%s", + expected_type, capsule_name); // TypeError is thrown + return 0; + } + return 1; +} + +/** + * csp/csp.h + */ + +/* + * void csp_service_handler(csp_conn_t *conn, csp_packet_t *packet); + */ +static PyObject* pycsp_service_handler(PyObject *self, PyObject *args) { + PyObject* conn_capsule; + PyObject* packet_capsule; + if (!PyArg_ParseTuple(args, "OO", &conn_capsule, &packet_capsule)) { + return NULL; // TypeError is thrown + } + + if (!is_capsule_of_type(conn_capsule, "csp_conn_t") || + !is_capsule_of_type(packet_capsule, "csp_packet_t")) { + return NULL; // TypeError is thrown + } + + csp_service_handler( + (csp_conn_t*)PyCapsule_GetPointer(conn_capsule, "csp_conn_t"), + (csp_packet_t*)PyCapsule_GetPointer(packet_capsule, "csp_packet_t")); + + Py_RETURN_NONE; +} + +/* + * int csp_init(uint8_t my_node_address); + */ +static PyObject* pycsp_init(PyObject *self, PyObject *args) { + uint8_t my_node_address; + if (!PyArg_ParseTuple(args, "b", &my_node_address)) { + return NULL; // TypeError is thrown + } + + return Py_BuildValue("i", csp_init(my_node_address)); +} + +/* + * void csp_set_hostname(const char *hostname); + */ +static PyObject* pycsp_set_hostname(PyObject *self, PyObject *args) { + char* hostname; + if (!PyArg_ParseTuple(args, "s", &hostname)) { + return NULL; // TypeError is thrown + } + + csp_set_hostname(hostname); + Py_RETURN_NONE; +} + +/* + * const char *csp_get_hostname(void); + */ +static PyObject* pycsp_get_hostname(PyObject *self, PyObject *args) { + return Py_BuildValue("s", csp_get_hostname()); +} + +/* + * void csp_set_model(const char *model); + */ +static PyObject* pycsp_set_model(PyObject *self, PyObject *args) { + char* model; + if (!PyArg_ParseTuple(args, "s", &model)) { + return NULL; // TypeError is thrown + } + + csp_set_model(model); + Py_RETURN_NONE; +} + +/* + * const char *csp_get_model(void); + */ +static PyObject* pycsp_get_model(PyObject *self, PyObject *args) { + return Py_BuildValue("s", csp_get_model()); +} + +/* + * void csp_set_revision(const char *revision); + */ +static PyObject* pycsp_set_revision(PyObject *self, PyObject *args) { + char* revision; + if (!PyArg_ParseTuple(args, "s", &revision)) { + return NULL; // TypeError is thrown + } + + csp_set_revision(revision); + Py_RETURN_NONE; +} + +/* + * const char *csp_get_revision(void); + */ +static PyObject* pycsp_get_revision(PyObject *self, PyObject *args) { + return Py_BuildValue("s", csp_get_revision()); +} + +/* + * csp_socket_t *csp_socket(uint32_t opts); + */ +static PyObject* pycsp_socket(PyObject *self, PyObject *args) { + uint32_t opts = CSP_SO_NONE; + if (!PyArg_ParseTuple(args, "|I", &opts)) { + return NULL; // TypeError is thrown + } + + return PyCapsule_New(csp_socket(opts), "csp_socket_t", NULL); +} + +/* + * csp_conn_t *csp_accept(csp_socket_t *socket, uint32_t timeout); + */ +static PyObject* pycsp_accept(PyObject *self, PyObject *args) { + PyObject* socket_capsule; + uint32_t timeout = 500; + if (!PyArg_ParseTuple(args, "O|I", &socket_capsule, &timeout)) { + return NULL; // TypeError is thrown + } + + if (!is_capsule_of_type(socket_capsule, "csp_socket_t")) { + return NULL; // TypeError is thrown + } + + void* socket = PyCapsule_GetPointer(socket_capsule, "csp_socket_t"); + csp_conn_t* conn = csp_accept((csp_socket_t*)socket, timeout); + if (conn == NULL) { + Py_RETURN_NONE; // because a capsule cannot contain a NULL-pointer + } + + return PyCapsule_New(conn, "csp_conn_t", NULL); +} + +/* + * csp_packet_t *csp_read(csp_conn_t *conn, uint32_t timeout); + */ +static PyObject* pycsp_read(PyObject *self, PyObject *args) { + PyObject* conn_capsule; + uint32_t timeout = 500; + if (!PyArg_ParseTuple(args, "O|I", &conn_capsule, &timeout)) { + return NULL; // TypeError is thrown + } + + if (!is_capsule_of_type(conn_capsule, "csp_conn_t")) { + return NULL; // TypeError is thrown + } + + void* conn = PyCapsule_GetPointer(conn_capsule, "csp_conn_t"); + csp_packet_t* packet = csp_read((csp_conn_t*)conn, timeout); + if (packet == NULL) { + Py_RETURN_NONE; // because capsule cannot contain a NULL-pointer + } + + return PyCapsule_New(packet, "csp_packet_t", NULL); +} + +/* +* int csp_send(csp_conn_t * conn, csp_packet_t * packet, uint32_t timeout) +*/ +static PyObject* pycsp_send(PyObject *self, PyObject *args) { + PyObject* conn_capsule; + PyObject* packet_capsule; + uint32_t timeout = 500; + if (!PyArg_ParseTuple(args, "OO|I", &conn_capsule, &packet_capsule, &timeout)) { + return NULL; // TypeError is thrown + } + + if (!is_capsule_of_type(conn_capsule, "csp_conn_t")) { + return NULL; // TypeError is thrown + } + + void* packet = PyCapsule_GetPointer(packet_capsule, "csp_packet_t"); + if (packet == NULL) { + Py_RETURN_NONE; + } + + void* conn = PyCapsule_GetPointer(conn_capsule, "csp_conn_t"); + + int result = csp_send(conn, packet, timeout); + + return Py_BuildValue("i", result); +} + +/* + * int csp_transaction(uint8_t prio, uint8_t dest, uint8_t port, + * uint32_t timeout, void *outbuf, int outlen, + * void *inbuf, int inlen); + */ +static PyObject* pycsp_transaction(PyObject *self, PyObject *args) { + uint8_t prio; + uint8_t dest; + uint8_t port; + uint32_t timeout; + Py_buffer inbuf; + Py_buffer outbuf; + if (!PyArg_ParseTuple(args, "bbbIw*w*", &prio, &dest, &port, &timeout, &outbuf, &inbuf)) { + return NULL; // TypeError is thrown + } + + int result = csp_transaction(prio, dest, port, timeout, + outbuf.buf, outbuf.len, + inbuf.buf, inbuf.len); + + return Py_BuildValue("i", result); +} + +/* int csp_sendto(uint8_t prio, uint8_t dest, uint8_t dport, uint8_t src_port, uint32_t opts, csp_packet_t *packet, uint32_t timeout); */ +static PyObject* pycsp_sendto(PyObject *self, PyObject *args) { + uint8_t prio; + uint8_t dest; + uint8_t dport; + uint8_t src_port; + uint32_t opts; + PyObject* packet_capsule; + uint32_t timeout; + if (!PyArg_ParseTuple(args, "bbbbIOI", &prio, &dest, &dport, &src_port, &opts, &packet_capsule, &timeout)) { + Py_RETURN_NONE; + } + + void* packet = PyCapsule_GetPointer(packet_capsule, "csp_packet_t"); + if (packet == NULL) { + Py_RETURN_NONE; + } + + return Py_BuildValue("i", csp_sendto(prio, + dest, + dport, + src_port, + opts, + (csp_packet_t*)packet, + timeout)); +} + + +/* + * int csp_sendto_reply(csp_packet_t * request_packet, + * csp_packet_t * reply_packet, + * uint32_t opts, uint32_t timeout); + */ +static PyObject* pycsp_sendto_reply(PyObject *self, PyObject *args) { + PyObject* request_packet_capsule; + PyObject* reply_packet_capsule; + uint32_t opts = CSP_O_NONE; + uint32_t timeout = 500; + if (!PyArg_ParseTuple(args, "OO|II", &request_packet_capsule, &reply_packet_capsule, &opts, &timeout)) { + return NULL; // TypeError is thrown + } + + if (!is_capsule_of_type(request_packet_capsule, "csp_packet_t") || + !is_capsule_of_type(reply_packet_capsule, "csp_packet_t")) { + return NULL; // TypeError is thrown + } + + void* request_packet = PyCapsule_GetPointer(request_packet_capsule, "csp_packet_t"); + void* reply_packet = PyCapsule_GetPointer(reply_packet_capsule, "csp_packet_t"); + + return Py_BuildValue("i", csp_sendto_reply((csp_packet_t*)request_packet, + (csp_packet_t*)reply_packet, + opts, + timeout)); +} + +/* + * csp_conn_t *csp_connect(uint8_t prio, uint8_t dest, uint8_t dport, uint32_t timeout, uint32_t opts); + */ +static PyObject* pycsp_connect(PyObject *self, PyObject *args) { + uint8_t prio; + uint8_t dest; + uint8_t dport; + uint32_t timeout; + uint32_t opts; + if (!PyArg_ParseTuple(args, "bbbII", &prio, &dest, &dport, &timeout, &opts)) { + return NULL; // TypeError is thrown + } + + csp_conn_t *conn = csp_connect(prio, dest, dport, timeout,opts); + + return PyCapsule_New(conn, "csp_conn_t", NULL); +} + +/* + * int csp_close(csp_conn_t *conn); + */ +static PyObject* pycsp_close(PyObject *self, PyObject *conn_capsule) { + if (!is_capsule_of_type(conn_capsule, "csp_conn_t")) { + return NULL; // TypeError is thrown + } + + void *conn = PyCapsule_GetPointer(conn_capsule, "csp_conn_t"); + return Py_BuildValue("i", csp_close((csp_conn_t*)conn)); +} + +/* + * int csp_conn_dport(csp_conn_t *conn); + */ +static PyObject* pycsp_conn_dport(PyObject *self, PyObject *conn_capsule) { + if (!is_capsule_of_type(conn_capsule, "csp_conn_t")) { + return NULL; // TypeError is thrown + } + + void* conn = PyCapsule_GetPointer(conn_capsule, "csp_conn_t"); + return Py_BuildValue("i", csp_conn_dport((csp_conn_t*)conn)); +} + +/* + * int csp_conn_sport(csp_conn_t *conn); + */ +static PyObject* pycsp_conn_sport(PyObject *self, PyObject *conn_capsule) { + if (!is_capsule_of_type(conn_capsule, "csp_conn_t")) { + return NULL; // TypeError is thrown + } + + void* conn = PyCapsule_GetPointer(conn_capsule, "csp_conn_t"); + return Py_BuildValue("i", csp_conn_sport((csp_conn_t*)conn)); +} + +/* int csp_conn_dst(csp_conn_t *conn); */ +static PyObject* pycsp_conn_dst(PyObject *self, PyObject *conn_capsule) { + if (!is_capsule_of_type(conn_capsule, "csp_conn_t")) { + return NULL; // TypeError is thrown + } + + void* conn = PyCapsule_GetPointer(conn_capsule, "csp_conn_t"); + return Py_BuildValue("i", csp_conn_dst((csp_conn_t*)conn)); +} + +/* + * int csp_conn_src(csp_conn_t *conn); + */ +static PyObject* pycsp_conn_src(PyObject *self, PyObject *conn_capsule) { + if (!is_capsule_of_type(conn_capsule, "csp_conn_t")) { + return NULL; // TypeError is thrown + } + + void* conn = PyCapsule_GetPointer(conn_capsule, "csp_conn_t"); + return Py_BuildValue("i", csp_conn_src((csp_conn_t*)conn)); +} + +/* int csp_listen(csp_socket_t *socket, size_t conn_queue_length); */ +static PyObject* pycsp_listen(PyObject *self, PyObject *args) { + PyObject* socket_capsule; + size_t conn_queue_len = 10; + if (!PyArg_ParseTuple(args, "O|n", &socket_capsule, &conn_queue_len)) { + return NULL; // TypeError is thrown + } + + if (!is_capsule_of_type(socket_capsule, "csp_socket_t")) { + return NULL; // TypeError is thrown + } + + void* sock = PyCapsule_GetPointer(socket_capsule, "csp_socket_t"); + return Py_BuildValue("i", csp_listen((csp_socket_t*)sock, conn_queue_len)); +} + +/* int csp_bind(csp_socket_t *socket, uint8_t port); */ +static PyObject* pycsp_bind(PyObject *self, PyObject *args) { + PyObject* socket_capsule; + uint8_t port; + if (!PyArg_ParseTuple(args, "Ob", &socket_capsule, &port)) { + return NULL; // TypeError is thrown + } + + if (!is_capsule_of_type(socket_capsule, "csp_socket_t")) { + return NULL; // TypeError is thrown + } + + void* sock = PyCapsule_GetPointer(socket_capsule, "csp_socket_t"); + return Py_BuildValue("i", csp_bind((csp_socket_t*)sock, port)); +} + +/* int csp_route_start_task(unsigned int task_stack_size, unsigned int priority); */ +static PyObject* pycsp_route_start_task(PyObject *self, PyObject *args) { + unsigned int priority = CSP_PRIO_NORM; + if (!PyArg_ParseTuple(args, "|I", &priority)) { + return NULL; // TypeError is thrown + } + + return Py_BuildValue("i", csp_route_start_task(0, priority)); +} + +/* + * int csp_ping(uint8_t node, uint32_t timeout, + * unsigned int size, uint8_t conn_options); + */ +static PyObject* pycsp_ping(PyObject *self, PyObject *args) { + uint8_t node; + uint32_t timeout = 500; + unsigned int size = 100; + uint8_t conn_options = CSP_O_NONE; + if (!PyArg_ParseTuple(args, "b|IIb", &node, &timeout, &size, &conn_options)) { + return NULL; // TypeError is thrown + } + + return Py_BuildValue("i", csp_ping(node, timeout, size, conn_options)); +} + +/* + * void csp_reboot(uint8_t node); + */ +static PyObject* pycsp_reboot(PyObject *self, PyObject *args) { + uint8_t node; + if (!PyArg_ParseTuple(args, "b", &node)) { + return NULL; // TypeError is thrown + } + + csp_reboot(node); + Py_RETURN_NONE; +} + +/* + * void csp_shutdown(uint8_t node); + */ +static PyObject* pycsp_shutdown(PyObject *self, PyObject *args) { + uint8_t node; + if (!PyArg_ParseTuple(args, "b", &node)) { + return NULL; // TypeError is thrown + } + + csp_shutdown(node); + Py_RETURN_NONE; +} + +/* + * void csp_rdp_set_opt(unsigned int window_size, + * unsigned int conn_timeout_ms, + * unsigned int packet_timeout_ms, + * unsigned int delayed_acks, + * unsigned int ack_timeout, + * unsigned int ack_delay_count); + */ +static PyObject* pycsp_rdp_set_opt(PyObject *self, PyObject *args) { + unsigned int window_size; + unsigned int conn_timeout_ms; + unsigned int packet_timeout_ms; + unsigned int delayed_acks; + unsigned int ack_timeout; + unsigned int ack_delay_count; + if (!PyArg_ParseTuple(args, "IIIIII", &window_size, &conn_timeout_ms, + &packet_timeout_ms, &delayed_acks, + &ack_timeout, &ack_delay_count)) { + return NULL; // TypeError is thrown + } +#ifdef CSP_USE_RDP + csp_rdp_set_opt(window_size, conn_timeout_ms, packet_timeout_ms, + delayed_acks, ack_timeout, ack_delay_count); +#endif + Py_RETURN_NONE; +} + +/* + * void csp_rdp_get_opt(unsigned int *window_size, + * unsigned int *conn_timeout_ms, + * unsigned int *packet_timeout_ms, + * unsigned int *delayed_acks, + * unsigned int *ack_timeout, + * unsigned int *ack_delay_count); + */ +static PyObject* pycsp_rdp_get_opt(PyObject *self, PyObject *args) { + + unsigned int window_size = 0; + unsigned int conn_timeout_ms = 0; + unsigned int packet_timeout_ms = 0; + unsigned int delayed_acks = 0; + unsigned int ack_timeout = 0; + unsigned int ack_delay_count = 0; +#ifdef CSP_USE_RDP + csp_rdp_get_opt(&window_size, + &conn_timeout_ms, + &packet_timeout_ms, + &delayed_acks, + &ack_timeout, + &ack_delay_count); +#endif + return Py_BuildValue("IIIIII", + window_size, + conn_timeout_ms, + packet_timeout_ms, + delayed_acks, + ack_timeout, + ack_delay_count); +} + + +/* + * + * int csp_xtea_set_key(char *key, uint32_t keylen); + */ +static PyObject* pycsp_xtea_set_key(PyObject *self, PyObject *args) { + char* key; + uint32_t keylen; + if (!PyArg_ParseTuple(args, "si", &key, &keylen)) { + return NULL; // TypeError is thrown + } + return Py_BuildValue("i", csp_xtea_set_key(key, keylen)); +} +/** + * csp/csp_rtable.h + */ + +/* + * int csp_rtable_set(uint8_t node, uint8_t mask, + * csp_iface_t *ifc, uint8_t mac); + */ +static PyObject* pycsp_rtable_set(PyObject *self, PyObject *args) { + uint8_t node; + uint8_t mask; + char* interface_name; + uint8_t mac = CSP_NODE_MAC; + if (!PyArg_ParseTuple(args, "bbs|b", &node, &mask, &interface_name, &mac)) { + return NULL; // TypeError is thrown + } + + return Py_BuildValue("i", csp_rtable_set(node, + mask, + csp_iflist_get_by_name(interface_name), + mac)); +} + +/* + * void csp_rtable_clear(void); + */ +static PyObject* pycsp_rtable_clear(PyObject *self, PyObject *args) { + csp_rtable_clear(); + Py_RETURN_NONE; +} + +/* +* int csp_rtable_check(const char * buffer) +*/ +static PyObject* pycsp_rtable_check(PyObject *self, PyObject *args) { + char* buffer; + if (!PyArg_ParseTuple(args, "s", &buffer)) { + return NULL; // TypeError is thrown + } + + return Py_BuildValue("i", csp_rtable_check(buffer)); +} + +/* +* void csp_rtable_load(const char * buffer) +*/ +static PyObject* pycsp_rtable_load(PyObject *self, PyObject *args) { + char* buffer; + if (!PyArg_ParseTuple(args, "s", &buffer)) { + return NULL; // TypeError is thrown + } + + csp_rtable_load(buffer); + Py_RETURN_NONE; +} + +/** + * csp/csp_buffer.h + */ + +/* + * int csp_buffer_init(int count, int size); + */ +static PyObject* pycsp_buffer_init(PyObject *self, PyObject *args) { + int count; + int size; + if (!PyArg_ParseTuple(args, "ii", &count, &size)) { + return NULL; // TypeError is thrown + } + + return Py_BuildValue("i", csp_buffer_init(count, size)); +} + +/* + * void * csp_buffer_get(size_t size); + */ +static PyObject* pycsp_buffer_get(PyObject *self, PyObject *args) { + size_t size; + if (!PyArg_ParseTuple(args, "n", &size)) { + return NULL; // TypeError is thrown + } + + void* packet = csp_buffer_get(size); + if (packet == NULL) { + Py_RETURN_NONE; + } + + return PyCapsule_New(packet, "csp_packet_t", NULL); +} +/* + * void csp_buffer_free(void *packet); + */ +static PyObject* pycsp_buffer_free(PyObject *self, PyObject *args) { + PyObject* packet_capsule; + if (!PyArg_ParseTuple(args, "O", &packet_capsule)) { + return NULL; // TypeError is thrown + } + + + if (!is_capsule_of_type(packet_capsule, "csp_packet_t")) { + return NULL; // TypeError is thrown + } + + csp_buffer_free(PyCapsule_GetPointer(packet_capsule, "csp_packet_t")); + Py_RETURN_NONE; +} + +/* + * int csp_buffer_remaining(void); + */ +static PyObject* pycsp_buffer_remaining(PyObject *self, PyObject *args) { + return Py_BuildValue("i", csp_buffer_remaining()); +} + +/** + * csp/csp_cmp.h + */ + +/* + * static inline int csp_cmp_ident(uint8_t node, uint32_t timeout, + * struct csp_cmp_message *msg) + */ +static PyObject* pycsp_cmp_ident(PyObject *self, PyObject *args) { + uint8_t node; + uint32_t timeout = 500; + if (!PyArg_ParseTuple(args, "b|i", &node, &timeout)) { + return NULL; // TypeError is thrown + } + + struct csp_cmp_message msg; + int rc = csp_cmp_ident(node, timeout, &msg); + return Py_BuildValue("isssss", + rc, + msg.ident.hostname, + msg.ident.model, + msg.ident.revision, + msg.ident.date, + msg.ident.time); +} + +/* + * static inline int csp_cmp_route_set(uint8_t node, uint32_t timeout, + * struct csp_cmp_message *msg) + */ +static PyObject* pycsp_cmp_route_set(PyObject *self, PyObject *args) { + uint8_t node; + uint32_t timeout = 500; + uint8_t addr; + uint8_t mac; + char* ifstr; + if (!PyArg_ParseTuple(args, "bibbs", &node, &timeout, &addr, &mac, &ifstr)) { + return NULL; // TypeError is thrown + } + + struct csp_cmp_message msg; + msg.route_set.dest_node = addr; + msg.route_set.next_hop_mac = mac; + strncpy(msg.route_set.interface, ifstr, CSP_CMP_ROUTE_IFACE_LEN); + int rc = csp_cmp_route_set(node, timeout, &msg); + return Py_BuildValue("i", + rc); +} + +/* static inline int pycsp_cmp_peek(uint8_t node, uint32_t timeout, struct csp_cmp_message *msg); */ +static PyObject* pycsp_cmp_peek(PyObject *self, PyObject *args) { + uint8_t node; + uint32_t timeout; + uint8_t len; + uint32_t addr; + Py_buffer outbuf; + + if (!PyArg_ParseTuple(args, "biibw*", &node, &timeout, &addr, &len, &outbuf)) { + Py_RETURN_NONE; + } + + if (len > CSP_CMP_PEEK_MAX_LEN) { + len = CSP_CMP_PEEK_MAX_LEN; + } + struct csp_cmp_message msg; + msg.peek.addr = csp_hton32(addr); + msg.peek.len = len; + int rc = csp_cmp_peek(node, timeout, &msg); + if (rc != CSP_ERR_NONE) { + Py_RETURN_NONE; + } + memcpy(outbuf.buf, msg.peek.data, len); + outbuf.len = len; + + return Py_BuildValue("i", rc); +} + +/* static inline int pycsp_cmp_poke(uint8_t node, uint32_t timeout, struct csp_cmp_message *msg); */ +static PyObject* pycsp_cmp_poke(PyObject *self, PyObject *args) { + uint8_t node; + uint32_t timeout; + uint8_t len; + uint32_t addr; + Py_buffer inbuf; + + if (!PyArg_ParseTuple(args, "biibw*", &node, &timeout, &addr, &len, &inbuf)) { + Py_RETURN_NONE; + } + + if (len > CSP_CMP_POKE_MAX_LEN) { + len = CSP_CMP_POKE_MAX_LEN; + } + struct csp_cmp_message msg; + msg.poke.addr = csp_hton32(addr); + msg.poke.len = len; + memcpy(msg.poke.data, inbuf.buf, len); + int rc = csp_cmp_poke(node, timeout, &msg); + if (rc != CSP_ERR_NONE) { + Py_RETURN_NONE; + } + + return Py_BuildValue("i", rc); +} + +/* static inline int csp_cmp_clock(uint8_t node, uint32_t timeout, struct csp_cmp_message *msg); */ +static PyObject* pycsp_cmp_clock(PyObject *self, PyObject *args) { + uint8_t node; + uint32_t timeout; + uint32_t sec; + uint32_t nsec; + if (!PyArg_ParseTuple(args, "bIII", &node, &timeout, &sec, &nsec)) { + Py_RETURN_NONE; + } + + struct csp_cmp_message msg; + msg.clock.tv_sec = csp_hton32(sec); + msg.clock.tv_nsec = csp_hton32(nsec); + return Py_BuildValue("i", csp_cmp_clock(node, timeout, &msg)); +} + +/** + * csp/interfaces/csp_if_zmqhub.h + */ + +/* + * int csp_zmqhub_init(char addr, char * host); + */ +static PyObject* pycsp_zmqhub_init(PyObject *self, PyObject *args) { + char addr; + char* host; + if (!PyArg_ParseTuple(args, "bs", &addr, &host)) { + return NULL; // TypeError is thrown + } + + return Py_BuildValue("i", csp_zmqhub_init(addr, host)); +} + +/** + * csp/drivers/can_socketcan.h + */ + +/* + * csp_iface_t * csp_can_socketcan_init(const char * ifc, int bitrate, int promisc); + */ +static PyObject* pycsp_can_socketcan_init(PyObject *self, PyObject *args) +{ + char* ifc; + int bitrate = 1000000; + int promisc = 0; + + if (!PyArg_ParseTuple(args, "s|ii", &ifc, &bitrate, &promisc)) + { + return NULL; + } + + csp_can_socketcan_init(ifc, bitrate, promisc); + Py_RETURN_NONE; +} + + +/** + * csp/interfaces/csp_if_kiss.h + */ + +/* + * int csp_kiss_init(char addr, char * host); + */ +static PyObject* pycsp_kiss_init(PyObject *self, PyObject *args) { + char* device; + uint32_t baudrate = 500000; + uint32_t mtu = 512; + const char* if_name = "KISS"; + if (!PyArg_ParseTuple(args, "s|IIs", &device, &baudrate, &mtu, &if_name)) { + return NULL; // TypeError is thrown + } + + static csp_iface_t csp_if_kiss; + static csp_kiss_handle_t csp_kiss_driver; + csp_if_kiss.mtu = (uint16_t) mtu; + struct usart_conf conf = {.device = device, .baudrate = baudrate}; + csp_kiss_init(&csp_if_kiss, &csp_kiss_driver, usart_putc, usart_insert, if_name); + usart_init(&conf); + + void my_usart_rx(uint8_t * buf, int len, void * pxTaskWoken) { + csp_kiss_rx(&csp_if_kiss, buf, len, pxTaskWoken); + } + usart_set_callback(my_usart_rx); + + Py_RETURN_NONE; +} + +/** + * Helpers - accessing csp_packet_t members + */ +static PyObject* pycsp_packet_set_data(PyObject *self, PyObject *args) { + PyObject* packet_capsule; + Py_buffer data; + if (!PyArg_ParseTuple(args, "Ow*", &packet_capsule, &data)) { + return NULL; // TypeError is thrown + } + + if (!is_capsule_of_type(packet_capsule, "csp_packet_t")) { + return NULL; // TypeError is thrown + } + + csp_packet_t* packet = PyCapsule_GetPointer(packet_capsule, "csp_packet_t"); + + memcpy((char *)packet->data, data.buf, data.len); + packet->length = data.len; + + Py_RETURN_NONE; +} +static PyObject* pycsp_packet_get_data(PyObject *self, PyObject *packet_capsule) { + if (!is_capsule_of_type(packet_capsule, "csp_packet_t")) { + return NULL; // TypeError is thrown + } + + csp_packet_t* packet = PyCapsule_GetPointer(packet_capsule, "csp_packet_t"); +#ifdef IS_PY3 + return Py_BuildValue("y#", packet->data, packet->length); +#else + return Py_BuildValue("s#", packet->data, packet->length); +#endif +} + +static PyObject* pycsp_packet_get_length(PyObject *self, PyObject *packet_capsule) { + if (!is_capsule_of_type(packet_capsule, "csp_packet_t")) { + return NULL; // TypeError is thrown + } + + csp_packet_t* packet = PyCapsule_GetPointer(packet_capsule, "csp_packet_t"); + return Py_BuildValue("H", packet->length); +} + +static PyMethodDef methods[] = { + + /* csp/csp.h */ + {"service_handler", pycsp_service_handler, METH_VARARGS, ""}, + {"init", pycsp_init, METH_VARARGS, ""}, + {"set_hostname", pycsp_set_hostname, METH_VARARGS, ""}, + {"get_hostname", pycsp_get_hostname, METH_NOARGS, ""}, + {"set_model", pycsp_set_model, METH_VARARGS, ""}, + {"get_model", pycsp_get_model, METH_NOARGS, ""}, + {"set_revision", pycsp_set_revision, METH_VARARGS, ""}, + {"get_revision", pycsp_get_revision, METH_NOARGS, ""}, + {"socket", pycsp_socket, METH_VARARGS, ""}, + {"accept", pycsp_accept, METH_VARARGS, ""}, + {"read", pycsp_read, METH_VARARGS, ""}, + {"send", pycsp_send, METH_VARARGS, ""}, + {"transaction", pycsp_transaction, METH_VARARGS, ""}, + {"sendto_reply", pycsp_sendto_reply, METH_VARARGS, ""}, + {"sendto", pycsp_sendto, METH_VARARGS, ""}, + {"connect", pycsp_connect, METH_VARARGS, ""}, + {"close", pycsp_close, METH_O, ""}, + {"conn_dport", pycsp_conn_dport, METH_O, ""}, + {"conn_sport", pycsp_conn_sport, METH_O, ""}, + {"conn_dst", pycsp_conn_dst, METH_O, ""}, + {"conn_src", pycsp_conn_src, METH_O, ""}, + {"listen", pycsp_listen, METH_VARARGS, ""}, + {"bind", pycsp_bind, METH_VARARGS, ""}, + {"route_start_task", pycsp_route_start_task, METH_VARARGS, ""}, + {"ping", pycsp_ping, METH_VARARGS, ""}, + {"reboot", pycsp_reboot, METH_VARARGS, ""}, + {"shutdown", pycsp_shutdown, METH_VARARGS, ""}, + {"rdp_set_opt", pycsp_rdp_set_opt, METH_VARARGS, ""}, + {"rdp_get_opt", pycsp_rdp_get_opt, METH_NOARGS, ""}, + {"xtea_set_key", pycsp_xtea_set_key, METH_VARARGS, ""}, + + /* csp/csp_rtable.h */ + {"rtable_set", pycsp_rtable_set, METH_VARARGS, ""}, + {"rtable_clear", pycsp_rtable_clear, METH_NOARGS, ""}, + {"rtable_check", pycsp_rtable_check, METH_VARARGS, ""}, + {"rtable_load", pycsp_rtable_load, METH_VARARGS, ""}, + + /* csp/csp_buffer.h */ + {"buffer_init", pycsp_buffer_init, METH_VARARGS, ""}, + {"buffer_free", pycsp_buffer_free, METH_VARARGS, ""}, + {"buffer_get", pycsp_buffer_get, METH_VARARGS, ""}, + {"buffer_remaining", pycsp_buffer_remaining, METH_NOARGS, ""}, + + /* csp/csp_cmp.h */ + {"cmp_ident", pycsp_cmp_ident, METH_VARARGS, ""}, + {"cmp_route_set", pycsp_cmp_route_set, METH_VARARGS, ""}, + {"cmp_peek", pycsp_cmp_peek, METH_VARARGS, ""}, + {"cmp_poke", pycsp_cmp_poke, METH_VARARGS, ""}, + {"cmp_clock", pycsp_cmp_clock, METH_VARARGS, ""}, + + + /* csp/interfaces/csp_if_zmqhub.h */ + {"zmqhub_init", pycsp_zmqhub_init, METH_VARARGS, ""}, + {"kiss_init", pycsp_kiss_init, METH_VARARGS, ""}, + + /* csp/drivers/can_socketcan.h */ + {"can_socketcan_init", pycsp_can_socketcan_init, METH_VARARGS, ""}, + + /* helpers */ + {"packet_get_length", pycsp_packet_get_length, METH_O, ""}, + {"packet_get_data", pycsp_packet_get_data, METH_O, ""}, + {"packet_set_data", pycsp_packet_set_data, METH_VARARGS, ""}, + + /* sentinel */ + {NULL, NULL, 0, NULL} +}; + +#ifdef IS_PY3 +static struct PyModuleDef moduledef = { + PyModuleDef_HEAD_INIT, + "libcsp_py3", + NULL, + -1, + methods, + NULL, + NULL, + NULL, + NULL +}; +#endif + +#ifdef IS_PY3 +PyMODINIT_FUNC PyInit_libcsp_py3(void) { +#else + PyMODINIT_FUNC initlibcsp_py2(void) { +#endif + + PyObject* m; + +#ifdef IS_PY3 + m = PyModule_Create(&moduledef); +#else + m = Py_InitModule("libcsp_py2", methods); +#endif + /** + * csp/csp_types.h + */ + + /* RESERVED PORTS */ + PyModule_AddIntConstant(m, "CSP_CMP", CSP_CMP); + PyModule_AddIntConstant(m, "CSP_PING", CSP_PING); + PyModule_AddIntConstant(m, "CSP_PS", CSP_PS); + PyModule_AddIntConstant(m, "CSP_MEMFREE", CSP_MEMFREE); + PyModule_AddIntConstant(m, "CSP_REBOOT", CSP_REBOOT); + PyModule_AddIntConstant(m, "CSP_BUF_FREE", CSP_BUF_FREE); + PyModule_AddIntConstant(m, "CSP_UPTIME", CSP_UPTIME); + PyModule_AddIntConstant(m, "CSP_ANY", CSP_MAX_BIND_PORT + 1); + PyModule_AddIntConstant(m, "CSP_PROMISC", CSP_MAX_BIND_PORT + 2); + + /* PRIORITIES */ + PyModule_AddIntConstant(m, "CSP_PRIO_CRITICAL", CSP_PRIO_CRITICAL); + PyModule_AddIntConstant(m, "CSP_PRIO_HIGH", CSP_PRIO_HIGH); + PyModule_AddIntConstant(m, "CSP_PRIO_NORM", CSP_PRIO_NORM); + PyModule_AddIntConstant(m, "CSP_PRIO_LOW", CSP_PRIO_LOW); + + /* FLAGS */ + PyModule_AddIntConstant(m, "CSP_FFRAG", CSP_FFRAG); + PyModule_AddIntConstant(m, "CSP_FHMAC", CSP_FHMAC); + PyModule_AddIntConstant(m, "CSP_FXTEA", CSP_FXTEA); + PyModule_AddIntConstant(m, "CSP_FRDP", CSP_FRDP); + PyModule_AddIntConstant(m, "CSP_FCRC32", CSP_FCRC32); + + /* SOCKET OPTIONS */ + PyModule_AddIntConstant(m, "CSP_SO_NONE", CSP_SO_NONE); + PyModule_AddIntConstant(m, "CSP_SO_RDPREQ", CSP_SO_RDPREQ); + PyModule_AddIntConstant(m, "CSP_SO_RDPPROHIB", CSP_SO_RDPPROHIB); + PyModule_AddIntConstant(m, "CSP_SO_HMACREQ", CSP_SO_HMACREQ); + PyModule_AddIntConstant(m, "CSP_SO_HMACPROHIB", CSP_SO_HMACPROHIB); + PyModule_AddIntConstant(m, "CSP_SO_XTEAREQ", CSP_SO_XTEAREQ); + PyModule_AddIntConstant(m, "CSP_SO_XTEAPROHIB", CSP_SO_XTEAPROHIB); + PyModule_AddIntConstant(m, "CSP_SO_CRC32REQ", CSP_SO_CRC32REQ); + PyModule_AddIntConstant(m, "CSP_SO_CRC32PROHIB", CSP_SO_CRC32PROHIB); + PyModule_AddIntConstant(m, "CSP_SO_CONN_LESS", CSP_SO_CONN_LESS); + + /* CONNECT OPTIONS */ + PyModule_AddIntConstant(m, "CSP_O_NONE", CSP_O_NONE); + PyModule_AddIntConstant(m, "CSP_O_RDP", CSP_O_RDP); + PyModule_AddIntConstant(m, "CSP_O_NORDP", CSP_O_NORDP); + PyModule_AddIntConstant(m, "CSP_O_HMAC", CSP_O_HMAC); + PyModule_AddIntConstant(m, "CSP_O_NOHMAC", CSP_O_NOHMAC); + PyModule_AddIntConstant(m, "CSP_O_XTEA", CSP_O_XTEA); + PyModule_AddIntConstant(m, "CSP_O_NOXTEA", CSP_O_NOXTEA); + PyModule_AddIntConstant(m, "CSP_O_CRC32", CSP_O_CRC32); + PyModule_AddIntConstant(m, "CSP_O_NOCRC32", CSP_O_NOCRC32); + + + /** + * csp/csp_error.h + */ + + PyModule_AddIntConstant(m, "CSP_ERR_NONE", CSP_ERR_NONE); + PyModule_AddIntConstant(m, "CSP_ERR_NOMEM", CSP_ERR_NOMEM); + PyModule_AddIntConstant(m, "CSP_ERR_INVAL", CSP_ERR_INVAL); + PyModule_AddIntConstant(m, "CSP_ERR_TIMEDOUT", CSP_ERR_TIMEDOUT); + PyModule_AddIntConstant(m, "CSP_ERR_USED", CSP_ERR_USED); + PyModule_AddIntConstant(m, "CSP_ERR_NOTSUP", CSP_ERR_NOTSUP); + PyModule_AddIntConstant(m, "CSP_ERR_BUSY", CSP_ERR_BUSY); + PyModule_AddIntConstant(m, "CSP_ERR_ALREADY", CSP_ERR_ALREADY); + PyModule_AddIntConstant(m, "CSP_ERR_RESET", CSP_ERR_RESET); + PyModule_AddIntConstant(m, "CSP_ERR_NOBUFS", CSP_ERR_NOBUFS); + PyModule_AddIntConstant(m, "CSP_ERR_TX", CSP_ERR_TX); + PyModule_AddIntConstant(m, "CSP_ERR_DRIVER", CSP_ERR_DRIVER); + PyModule_AddIntConstant(m, "CSP_ERR_AGAIN", CSP_ERR_AGAIN); + PyModule_AddIntConstant(m, "CSP_ERR_HMAC", CSP_ERR_HMAC); + PyModule_AddIntConstant(m, "CSP_ERR_XTEA", CSP_ERR_XTEA); + PyModule_AddIntConstant(m, "CSP_ERR_CRC32", CSP_ERR_CRC32); + + /** + * csp/rtable.h + */ + PyModule_AddIntConstant(m, "CSP_NODE_MAC", CSP_NODE_MAC); + +#ifdef IS_PY3 + return m; +#endif + } + diff --git a/thirdparty/libcsp/src/crypto/CMakeLists.txt b/thirdparty/libcsp/src/crypto/CMakeLists.txt new file mode 100644 index 00000000..19cb878a --- /dev/null +++ b/thirdparty/libcsp/src/crypto/CMakeLists.txt @@ -0,0 +1,5 @@ +target_sources(${LIB_CSP_NAME} PRIVATE + csp_hmac.c + csp_sha1.c + csp_xtea.c +) diff --git a/thirdparty/libcsp/src/crypto/csp_hmac.c b/thirdparty/libcsp/src/crypto/csp_hmac.c new file mode 100644 index 00000000..ae7fbb00 --- /dev/null +++ b/thirdparty/libcsp/src/crypto/csp_hmac.c @@ -0,0 +1,202 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +/* Hash-based Message Authentication Code - based on code from libtom.org */ + +#include +#include +#include + +/* CSP includes */ +#include + +#include +#include + +#ifdef CSP_USE_HMAC + +#define HMAC_KEY_LENGTH 16 + +/* HMAC key */ +static uint8_t csp_hmac_key[HMAC_KEY_LENGTH]; + +/* HMAC state structure */ +typedef struct { + csp_sha1_state md; + uint8_t key[SHA1_BLOCKSIZE]; +} hmac_state; + +static int csp_hmac_init(hmac_state * hmac, const uint8_t * key, uint32_t keylen) { + uint32_t i; + uint8_t buf[SHA1_BLOCKSIZE]; + + /* NULL pointer and key check */ + if (!hmac || !key || keylen < 1) + return CSP_ERR_INVAL; + + /* Make sure we have a large enough key */ + if(keylen > SHA1_BLOCKSIZE) { + csp_sha1_memory(key, keylen, hmac->key); + if(SHA1_DIGESTSIZE < SHA1_BLOCKSIZE) + memset((hmac->key) + SHA1_DIGESTSIZE, 0, (size_t)(SHA1_BLOCKSIZE - SHA1_DIGESTSIZE)); + } else { + memcpy(hmac->key, key, (size_t)keylen); + if(keylen < SHA1_BLOCKSIZE) + memset((hmac->key) + keylen, 0, (size_t)(SHA1_BLOCKSIZE - keylen)); + } + + /* Create the initial vector */ + for(i = 0; i < SHA1_BLOCKSIZE; i++) + buf[i] = hmac->key[i] ^ 0x36; + + /* Prepend to the hash data */ + csp_sha1_init(&hmac->md); + csp_sha1_process(&hmac->md, buf, SHA1_BLOCKSIZE); + + return CSP_ERR_NONE; +} + +static int csp_hmac_process(hmac_state * hmac, const uint8_t * in, uint32_t inlen) { + + /* NULL pointer check */ + if (!hmac || !in) + return CSP_ERR_INVAL; + + /* Process data */ + csp_sha1_process(&hmac->md, in, inlen); + + return CSP_ERR_NONE; +} + +static int csp_hmac_done(hmac_state * hmac, uint8_t * out) { + + uint32_t i; + uint8_t buf[SHA1_BLOCKSIZE]; + uint8_t isha[SHA1_DIGESTSIZE]; + + if (!hmac || !out) + return CSP_ERR_INVAL; + + /* Get the hash of the first HMAC vector plus the data */ + csp_sha1_done(&hmac->md, isha); + + /* Create the second HMAC vector vector */ + for(i = 0; i < SHA1_BLOCKSIZE; i++) + buf[i] = hmac->key[i] ^ 0x5C; + + /* Now calculate the outer hash */ + csp_sha1_init(&hmac->md); + csp_sha1_process(&hmac->md, buf, SHA1_BLOCKSIZE); + csp_sha1_process(&hmac->md, isha, SHA1_DIGESTSIZE); + csp_sha1_done(&hmac->md, buf); + + /* Copy to output */ + for (i = 0; i < SHA1_DIGESTSIZE; i++) + out[i] = buf[i]; + + return CSP_ERR_NONE; +} + +int csp_hmac_memory(const uint8_t * key, uint32_t keylen, const uint8_t * data, uint32_t datalen, uint8_t * hmac) { + hmac_state state; + + /* NULL pointer check */ + if (!key || !data || !hmac) + return CSP_ERR_INVAL; + + /* Init HMAC state */ + if (csp_hmac_init(&state, key, keylen) != 0) + return CSP_ERR_INVAL; + + /* Process data */ + if (csp_hmac_process(&state, data, datalen) != 0) + return CSP_ERR_INVAL; + + /* Output HMAC */ + if (csp_hmac_done(&state, hmac) != 0) + return CSP_ERR_INVAL; + + return CSP_ERR_NONE; +} + +int csp_hmac_set_key(char * key, uint32_t keylen) { + + /* Use SHA1 as KDF */ + uint8_t hash[SHA1_DIGESTSIZE]; + csp_sha1_memory((uint8_t *)key, keylen, hash); + + /* Copy key */ + memcpy(csp_hmac_key, hash, HMAC_KEY_LENGTH); + + return CSP_ERR_NONE; + +} + +int csp_hmac_append(csp_packet_t * packet, bool include_header) { + + /* NULL pointer check */ + if (packet == NULL) + return CSP_ERR_INVAL; + + uint8_t hmac[SHA1_DIGESTSIZE]; + + /* Calculate HMAC */ + if (include_header) { + csp_hmac_memory(csp_hmac_key, HMAC_KEY_LENGTH, (uint8_t *) &packet->id, packet->length + sizeof(packet->id), hmac); + } else { + csp_hmac_memory(csp_hmac_key, HMAC_KEY_LENGTH, packet->data, packet->length, hmac); + } + + /* Truncate hash and copy to packet */ + memcpy(&packet->data[packet->length], hmac, CSP_HMAC_LENGTH); + packet->length += CSP_HMAC_LENGTH; + + return CSP_ERR_NONE; + +} + +int csp_hmac_verify(csp_packet_t * packet, bool include_header) { + + /* NULL pointer check */ + if (packet == NULL) + return CSP_ERR_INVAL; + + uint8_t hmac[SHA1_DIGESTSIZE]; + + /* Calculate HMAC */ + if (include_header) { + csp_hmac_memory(csp_hmac_key, HMAC_KEY_LENGTH, (uint8_t *) &packet->id, packet->length + sizeof(packet->id) - CSP_HMAC_LENGTH, hmac); + } else { + csp_hmac_memory(csp_hmac_key, HMAC_KEY_LENGTH, packet->data, packet->length - CSP_HMAC_LENGTH, hmac); + } + + /* Compare calculated HMAC with packet header */ + if (memcmp(&packet->data[packet->length] - CSP_HMAC_LENGTH, hmac, CSP_HMAC_LENGTH) != 0) { + /* HMAC failed */ + return CSP_ERR_HMAC; + } else { + /* Strip HMAC */ + packet->length -= CSP_HMAC_LENGTH; + return CSP_ERR_NONE; + } + +} + +#endif // CSP_USE_HMAC diff --git a/thirdparty/libcsp/src/crypto/csp_sha1.c b/thirdparty/libcsp/src/crypto/csp_sha1.c new file mode 100644 index 00000000..6c3920e9 --- /dev/null +++ b/thirdparty/libcsp/src/crypto/csp_sha1.c @@ -0,0 +1,217 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +/* Code originally from Python's SHA1 Module, who based it on libtom.org */ + +#include +#include + +/* CSP includes */ +#include + +#include + +#if defined(CSP_USE_HMAC) || defined(CSP_USE_XTEA) + +/* Rotate left macro */ +#define ROL(x,y) (((x) << (y)) | ((x) >> (32-y))) + +/* Endian Neutral macros that work on all platforms */ +#define STORE32H(x, y) do { (y)[0] = (uint8_t)(((x) >> 24) & 0xff); \ + (y)[1] = (uint8_t)(((x) >> 16) & 0xff); \ + (y)[2] = (uint8_t)(((x) >> 8) & 0xff); \ + (y)[3] = (uint8_t)(((x) >> 0) & 0xff); } while (0) + +#define LOAD32H(x, y) do { (x) = ((uint32_t)((y)[0] & 0xff) << 24) | \ + ((uint32_t)((y)[1] & 0xff) << 16) | \ + ((uint32_t)((y)[2] & 0xff) << 8) | \ + ((uint32_t)((y)[3] & 0xff) << 0); } while (0) + +#define STORE64H(x, y) do { (y)[0] = (uint8_t)(((x) >> 56) & 0xff); \ + (y)[1] = (uint8_t)(((x) >> 48) & 0xff); \ + (y)[2] = (uint8_t)(((x) >> 40) & 0xff); \ + (y)[3] = (uint8_t)(((x) >> 32) & 0xff); \ + (y)[4] = (uint8_t)(((x) >> 24) & 0xff); \ + (y)[5] = (uint8_t)(((x) >> 16) & 0xff); \ + (y)[6] = (uint8_t)(((x) >> 8) & 0xff); \ + (y)[7] = (uint8_t)(((x) >> 0) & 0xff); } while (0) + +#define MIN(x, y) (((x) < (y)) ? (x) : (y)) + +/* SHA1 macros */ +#define F0(x,y,z) (z ^ (x & (y ^ z))) +#define F1(x,y,z) (x ^ y ^ z) +#define F2(x,y,z) ((x & y) | (z & (x | y))) +#define F3(x,y,z) (x ^ y ^ z) + +#define FF_0(a, b, c, d, e, i) do {e = (ROL(a, 5) + F0(b,c,d) + e + W[i] + 0x5a827999UL); b = ROL(b, 30);} while (0) +#define FF_1(a, b, c, d, e, i) do {e = (ROL(a, 5) + F1(b,c,d) + e + W[i] + 0x6ed9eba1UL); b = ROL(b, 30);} while (0) +#define FF_2(a, b, c, d, e, i) do {e = (ROL(a, 5) + F2(b,c,d) + e + W[i] + 0x8f1bbcdcUL); b = ROL(b, 30);} while (0) +#define FF_3(a, b, c, d, e, i) do {e = (ROL(a, 5) + F3(b,c,d) + e + W[i] + 0xca62c1d6UL); b = ROL(b, 30);} while (0) + +static void csp_sha1_compress(csp_sha1_state * sha1, const uint8_t * buf) { + + uint32_t a, b, c, d, e, W[80], i; + + /* Copy the state into 512-bits into W[0..15] */ + for (i = 0; i < 16; i++) + LOAD32H(W[i], buf + (4*i)); + + /* Copy state */ + a = sha1->state[0]; + b = sha1->state[1]; + c = sha1->state[2]; + d = sha1->state[3]; + e = sha1->state[4]; + + /* Expand it */ + for (i = 16; i < 80; i++) + W[i] = ROL(W[i-3] ^ W[i-8] ^ W[i-14] ^ W[i-16], 1); + + /* Compress */ + i = 0; + + /* Round one */ + for (; i < 20;) { + FF_0(a, b, c, d, e, i++); + FF_0(e, a, b, c, d, i++); + FF_0(d, e, a, b, c, i++); + FF_0(c, d, e, a, b, i++); + FF_0(b, c, d, e, a, i++); + } + + /* Round two */ + for (; i < 40;) { + FF_1(a, b, c, d, e, i++); + FF_1(e, a, b, c, d, i++); + FF_1(d, e, a, b, c, i++); + FF_1(c, d, e, a, b, i++); + FF_1(b, c, d, e, a, i++); + } + + /* Round three */ + for (; i < 60;) { + FF_2(a, b, c, d, e, i++); + FF_2(e, a, b, c, d, i++); + FF_2(d, e, a, b, c, i++); + FF_2(c, d, e, a, b, i++); + FF_2(b, c, d, e, a, i++); + } + + /* Round four */ + for (; i < 80;) { + FF_3(a, b, c, d, e, i++); + FF_3(e, a, b, c, d, i++); + FF_3(d, e, a, b, c, i++); + FF_3(c, d, e, a, b, i++); + FF_3(b, c, d, e, a, i++); + } + + /* Store */ + sha1->state[0] += a; + sha1->state[1] += b; + sha1->state[2] += c; + sha1->state[3] += d; + sha1->state[4] += e; + +} + +void csp_sha1_init(csp_sha1_state * sha1) { + + sha1->state[0] = 0x67452301UL; + sha1->state[1] = 0xefcdab89UL; + sha1->state[2] = 0x98badcfeUL; + sha1->state[3] = 0x10325476UL; + sha1->state[4] = 0xc3d2e1f0UL; + sha1->curlen = 0; + sha1->length = 0; + +} + +void csp_sha1_process(csp_sha1_state * sha1, const uint8_t * in, uint32_t inlen) { + + uint32_t n; + while (inlen > 0) { + if (sha1->curlen == 0 && inlen >= SHA1_BLOCKSIZE) { + csp_sha1_compress(sha1, in); + sha1->length += SHA1_BLOCKSIZE * 8; + in += SHA1_BLOCKSIZE; + inlen -= SHA1_BLOCKSIZE; + } else { + n = MIN(inlen, (SHA1_BLOCKSIZE - sha1->curlen)); + memcpy(sha1->buf + sha1->curlen, in, (size_t)n); + sha1->curlen += n; + in += n; + inlen -= n; + if (sha1->curlen == SHA1_BLOCKSIZE) { + csp_sha1_compress(sha1, sha1->buf); + sha1->length += 8*SHA1_BLOCKSIZE; + sha1->curlen = 0; + } + } + } + +} + +void csp_sha1_done(csp_sha1_state * sha1, uint8_t * out) { + + uint32_t i; + + /* Increase the length of the message */ + sha1->length += sha1->curlen * 8; + + /* Append the '1' bit */ + sha1->buf[sha1->curlen++] = 0x80; + + /* If the length is currently above 56 bytes we append zeros + * then compress. Then we can fall back to padding zeros and length + * encoding like normal. + */ + if (sha1->curlen > 56) { + while (sha1->curlen < 64) + sha1->buf[sha1->curlen++] = 0; + csp_sha1_compress(sha1, sha1->buf); + sha1->curlen = 0; + } + + /* Pad up to 56 bytes of zeroes */ + while (sha1->curlen < 56) + sha1->buf[sha1->curlen++] = 0; + + /* Store length */ + STORE64H(sha1->length, sha1->buf + 56); + csp_sha1_compress(sha1, sha1->buf); + + /* Copy output */ + for (i = 0; i < 5; i++) + STORE32H(sha1->state[i], out + (4 * i)); + +} + +void csp_sha1_memory(const uint8_t * msg, uint32_t len, uint8_t * hash) { + + csp_sha1_state md; + csp_sha1_init(&md); + csp_sha1_process(&md, msg, len); + csp_sha1_done(&md, hash); + +} + +#endif // CSP_USE_HMAC diff --git a/thirdparty/libcsp/src/crypto/csp_xtea.c b/thirdparty/libcsp/src/crypto/csp_xtea.c new file mode 100644 index 00000000..718824d1 --- /dev/null +++ b/thirdparty/libcsp/src/crypto/csp_xtea.c @@ -0,0 +1,134 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +/* Simple implementation of XTEA in CTR mode */ + +#include +#include + +/* CSP includes */ +#include +#include +#include +#include + +#ifdef CSP_USE_XTEA + +#define XTEA_BLOCKSIZE 8 +#define XTEA_ROUNDS 32 +#define XTEA_KEY_LENGTH 16 + +/* XTEA key */ +static uint32_t csp_xtea_key[XTEA_KEY_LENGTH/sizeof(uint32_t)] __attribute__ ((aligned(sizeof(uint32_t)))); + +#define STORE32L(x, y) do { (y)[3] = (uint8_t)(((x) >> 24) & 0xff); \ + (y)[2] = (uint8_t)(((x) >> 16) & 0xff); \ + (y)[1] = (uint8_t)(((x) >> 8) & 0xff); \ + (y)[0] = (uint8_t)(((x) >> 0) & 0xff); } while (0) + +#define LOAD32L(x, y) do { (x) = ((uint32_t)((y)[3] & 0xff) << 24) | \ + ((uint32_t)((y)[2] & 0xff) << 16) | \ + ((uint32_t)((y)[1] & 0xff) << 8) | \ + ((uint32_t)((y)[0] & 0xff) << 0); } while (0) + +/* This function takes 64 bits of data in block and the 128 bits key in key */ +static inline void csp_xtea_encrypt_block(uint8_t *block, uint8_t const *key) { + + uint32_t i, v0, v1, delta = 0x9E3779B9, sum = 0, k[4]; + + LOAD32L(k[0], &key[0]); + LOAD32L(k[1], &key[4]); + LOAD32L(k[2], &key[8]); + LOAD32L(k[3], &key[12]); + + LOAD32L(v0, &block[0]); + LOAD32L(v1, &block[4]); + + for (i = 0; i < XTEA_ROUNDS; i++) { + v0 += (((v1 << 4) ^ (v1 >> 5)) + v1) ^ (sum + k[sum & 3]); + sum += delta; + v1 += (((v0 << 4) ^ (v0 >> 5)) + v0) ^ (sum + k[(sum >> 11) & 3]); + } + + STORE32L(v0, &block[0]); + STORE32L(v1, &block[4]); + +} + +static inline void csp_xtea_xor_byte(uint8_t * dst, uint8_t * src, uint32_t len) { + + unsigned int i; + for (i = 0; i < len; i++) + dst[i] ^= src[i]; + +} + +int csp_xtea_set_key(char * key, uint32_t keylen) { + + /* Use SHA1 as KDF */ + uint8_t hash[SHA1_DIGESTSIZE]; + csp_sha1_memory((uint8_t *)key, keylen, hash); + + /* Copy key */ + memcpy(csp_xtea_key, hash, XTEA_KEY_LENGTH); + + return CSP_ERR_NONE; + +} + +int csp_xtea_encrypt(uint8_t * plain, const uint32_t len, uint32_t iv[2]) { + + unsigned int i; + uint32_t stream[2]; + + uint32_t blocks = (len + XTEA_BLOCKSIZE - 1)/ XTEA_BLOCKSIZE; + uint32_t remain; + + /* Initialize stream */ + stream[0] = csp_htobe32(iv[0]); + stream[1] = csp_htobe32(iv[1]); + + for (i = 0; i < blocks; i++) { + /* Create stream */ + csp_xtea_encrypt_block((uint8_t *)stream, (uint8_t *)csp_xtea_key); + + /* Calculate remaining bytes */ + remain = len - i * XTEA_BLOCKSIZE; + + /* XOR plain text with stream to generate cipher text */ + csp_xtea_xor_byte(&plain[len - remain], (uint8_t *)stream, remain < XTEA_BLOCKSIZE ? remain : XTEA_BLOCKSIZE); + + /* Increment counter */ + stream[0] = csp_htobe32(iv[0]); + stream[1] = csp_htobe32(iv[1]++); + } + + return CSP_ERR_NONE; + +} + +int csp_xtea_decrypt(uint8_t * cipher, const uint32_t len, uint32_t iv[2]) { + + /* Since we use counter mode, we can reuse the encryption function */ + return csp_xtea_encrypt(cipher, len, iv); + +} + +#endif // CSP_USE_XTEA diff --git a/thirdparty/libcsp/src/csp_bridge.c b/thirdparty/libcsp/src/csp_bridge.c new file mode 100644 index 00000000..1c579a9f --- /dev/null +++ b/thirdparty/libcsp/src/csp_bridge.c @@ -0,0 +1,94 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include +#include +#include +#include "csp_route.h" +#include "csp_qfifo.h" +#include "csp_io.h" +#include "csp_promisc.h" + +static csp_iface_t* if_a = NULL; +static csp_iface_t* if_b = NULL; + +static CSP_DEFINE_TASK(csp_bridge) { + + csp_qfifo_t input; + csp_packet_t * packet; + + /* Here there be bridging */ + while (1) { + + /* Get next packet to route */ + if (csp_qfifo_read(&input) != CSP_ERR_NONE) + continue; + + packet = input.packet; + + csp_log_packet("Input: Src %u, Dst %u, Dport %u, Sport %u, Pri %u, Flags 0x%02X, Size %"PRIu16, + packet->id.src, packet->id.dst, packet->id.dport, + packet->id.sport, packet->id.pri, packet->id.flags, packet->length); + + /* Here there be promiscuous mode */ +#ifdef CSP_USE_PROMISC + csp_promisc_add(packet); +#endif + + /* Find the opposing interface */ + csp_iface_t * ifout; + if (input.interface == if_a) { + ifout = if_b; + } else { + ifout = if_a; + } + + /* Send to the interface directly, no hassle */ + if (csp_send_direct(packet->id, packet, ifout, 0) != CSP_ERR_NONE) { + csp_log_warn("Router failed to send"); + csp_buffer_free(packet); + } + + /* Next message, please */ + continue; + + } + + return CSP_TASK_RETURN; + +} + +int csp_bridge_start(unsigned int task_stack_size, unsigned int task_priority, csp_iface_t * _if_a, csp_iface_t * _if_b) { + + /* Set static references to A/B side of bridge */ + if_a = _if_a; + if_b = _if_b; + + static csp_thread_handle_t handle; + int ret = csp_thread_create(csp_bridge, "BRIDGE", task_stack_size, NULL, task_priority, &handle); + + if (ret != 0) { + csp_log_error("Failed to start task"); + return CSP_ERR_NOMEM; + } + + return CSP_ERR_NONE; + +} diff --git a/thirdparty/libcsp/src/csp_buffer.c b/thirdparty/libcsp/src/csp_buffer.c new file mode 100644 index 00000000..8947f337 --- /dev/null +++ b/thirdparty/libcsp/src/csp_buffer.c @@ -0,0 +1,224 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include +#include +#include + +/* CSP includes */ +#include +#include +#include +#include +#include + +#ifndef CSP_BUFFER_ALIGN +#define CSP_BUFFER_ALIGN (sizeof(int *)) +#endif + +typedef struct csp_skbf_s { + unsigned int refcount; + void * skbf_addr; + char skbf_data[]; +} csp_skbf_t; + +static csp_queue_handle_t csp_buffers; +static char * csp_buffer_pool; +static unsigned int count, size; + +CSP_DEFINE_CRITICAL(csp_critical_lock); + +int csp_buffer_init(int buf_count, int buf_size) { + + unsigned int i; + csp_skbf_t * buf; + + count = buf_count; + size = buf_size + CSP_BUFFER_PACKET_OVERHEAD; + unsigned int skbfsize = (sizeof(csp_skbf_t) + size); + skbfsize = CSP_BUFFER_ALIGN * ((skbfsize + CSP_BUFFER_ALIGN - 1) / CSP_BUFFER_ALIGN); + unsigned int poolsize = count * skbfsize; + + csp_buffer_pool = csp_malloc(poolsize); + if (csp_buffer_pool == NULL) + goto fail_malloc; + + csp_buffers = csp_queue_create(count, sizeof(void *)); + if (!csp_buffers) + goto fail_queue; + + if (CSP_INIT_CRITICAL(csp_critical_lock) != CSP_ERR_NONE) + goto fail_critical; + + memset(csp_buffer_pool, 0, poolsize); + + for (i = 0; i < count; i++) { + + /* We have already taken care of pointer alignment since + * skbfsize is an integer multiple of sizeof(int *) + * but the explicit cast to a void * is still necessary + * to tell the compiler so. + */ + buf = (void *) &csp_buffer_pool[i * skbfsize]; + buf->refcount = 0; + buf->skbf_addr = buf; + + csp_queue_enqueue(csp_buffers, &buf, 0); + + } + + return CSP_ERR_NONE; + +fail_critical: + csp_queue_remove(csp_buffers); +fail_queue: + csp_free(csp_buffer_pool); +fail_malloc: + return CSP_ERR_NOMEM; + +} + +void *csp_buffer_get_isr(size_t buf_size) { + + csp_skbf_t * buffer = NULL; + CSP_BASE_TYPE task_woken = 0; + + if (buf_size + CSP_BUFFER_PACKET_OVERHEAD > size) + return NULL; + + csp_queue_dequeue_isr(csp_buffers, &buffer, &task_woken); + if (buffer == NULL) + return NULL; + + if (buffer != buffer->skbf_addr) + return NULL; + + buffer->refcount++; + return buffer->skbf_data; + +} + +void *csp_buffer_get(size_t buf_size) { + + csp_skbf_t * buffer = NULL; + + if (buf_size + CSP_BUFFER_PACKET_OVERHEAD > size) { + csp_log_error("Attempt to allocate too large block %u", buf_size); + return NULL; + } + + csp_queue_dequeue(csp_buffers, &buffer, 0); + if (buffer == NULL) { + csp_log_error("Out of buffers"); + return NULL; + } + + csp_log_buffer("GET: %p %p", buffer, buffer->skbf_addr); + + if (buffer != buffer->skbf_addr) { + csp_log_error("Corrupt CSP buffer"); + return NULL; + } + + buffer->refcount++; + return buffer->skbf_data; +} + +void csp_buffer_free_isr(void *packet) { + CSP_BASE_TYPE task_woken = 0; + if (!packet) + return; + + csp_skbf_t * buf = packet - sizeof(csp_skbf_t); + + if (((uintptr_t) buf % CSP_BUFFER_ALIGN) > 0) + return; + + if (buf->skbf_addr != buf) + return; + + if (buf->refcount == 0) { + return; + } else if (buf->refcount > 1) { + buf->refcount--; + return; + } else { + buf->refcount = 0; + csp_queue_enqueue_isr(csp_buffers, &buf, &task_woken); + } + +} + +void csp_buffer_free(void *packet) { + if (!packet) { + csp_log_error("Attempt to free null pointer"); + return; + } + + csp_skbf_t * buf = packet - sizeof(csp_skbf_t); + + if (((uintptr_t) buf % CSP_BUFFER_ALIGN) > 0) { + csp_log_error("FREE: Unaligned CSP buffer pointer %p", packet); + return; + } + + if (buf->skbf_addr != buf) { + csp_log_error("FREE: Invalid CSP buffer pointer %p", packet); + return; + } + + if (buf->refcount == 0) { + csp_log_error("FREE: Buffer already free %p", buf); + return; + } else if (buf->refcount > 1) { + buf->refcount--; + csp_log_error("FREE: Buffer %p in use by %u users", buf, buf->refcount); + return; + } else { + buf->refcount = 0; + csp_log_buffer("FREE: %p", buf); + csp_queue_enqueue(csp_buffers, &buf, 0); + } + +} + +void *csp_buffer_clone(void *buffer) { + + csp_packet_t *packet = (csp_packet_t *) buffer; + + if (!packet) + return NULL; + + csp_packet_t *clone = csp_buffer_get(packet->length); + + if (clone) + memcpy(clone, packet, size); + + return clone; + +} + +int csp_buffer_remaining(void) { + return csp_queue_size(csp_buffers); +} + +int csp_buffer_size(void) { + return size; +} diff --git a/thirdparty/libcsp/src/csp_conn.c b/thirdparty/libcsp/src/csp_conn.c new file mode 100644 index 00000000..7daa569d --- /dev/null +++ b/thirdparty/libcsp/src/csp_conn.c @@ -0,0 +1,498 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include +#include +#include +#include + +/* CSP includes */ +#include +#include + +#include +#include +#include +#include +#include + +#include "csp_conn.h" +#include "transport/csp_transport.h" + +/* Static connection pool */ +static csp_conn_t arr_conn[CSP_CONN_MAX]; + +/* Connection pool lock */ +static csp_bin_sem_handle_t conn_lock; + +/* Source port */ +static uint8_t sport; + +/* Source port lock */ +static csp_bin_sem_handle_t sport_lock; + +void csp_conn_check_timeouts(void) { +#ifdef CSP_USE_RDP + int i; + for (i = 0; i < CSP_CONN_MAX; i++) + if (arr_conn[i].state == CONN_OPEN) + if (arr_conn[i].idin.flags & CSP_FRDP) + csp_rdp_check_timeouts(&arr_conn[i]); +#endif +} + +int csp_conn_get_rxq(int prio) { + +#ifdef CSP_USE_QOS + return prio; +#else + return 0; +#endif + +} + +int csp_conn_lock(csp_conn_t * conn, uint32_t timeout) { + + if (csp_mutex_lock(&conn->lock, timeout) != CSP_MUTEX_OK) + return CSP_ERR_TIMEDOUT; + + return CSP_ERR_NONE; + +} + +int csp_conn_unlock(csp_conn_t * conn) { + + csp_mutex_unlock(&conn->lock); + + return CSP_ERR_NONE; + +} + +int csp_conn_enqueue_packet(csp_conn_t * conn, csp_packet_t * packet) { + + if (!conn) + return CSP_ERR_INVAL; + + int rxq; + if (packet != NULL) { + rxq = csp_conn_get_rxq(packet->id.pri); + } else { + rxq = CSP_RX_QUEUES - 1; + } + + if (csp_queue_enqueue(conn->rx_queue[rxq], &packet, 0) != CSP_QUEUE_OK) { + csp_log_error("RX queue %p full with %u items", conn->rx_queue[rxq], csp_queue_size(conn->rx_queue[rxq])); + return CSP_ERR_NOMEM; + } + +#ifdef CSP_USE_QOS + int event = 0; + if (csp_queue_enqueue(conn->rx_event, &event, 0) != CSP_QUEUE_OK) { + csp_log_error("QOS event queue full"); + return CSP_ERR_NOMEM; + } +#endif + + return CSP_ERR_NONE; +} + +int csp_conn_init(void) { + + /* Initialize source port */ + srand(csp_get_ms()); + sport = (rand() % (CSP_ID_PORT_MAX - CSP_MAX_BIND_PORT)) + (CSP_MAX_BIND_PORT + 1); + + if (csp_bin_sem_create(&sport_lock) != CSP_SEMAPHORE_OK) { + csp_log_error("No more memory for sport semaphore"); + return CSP_ERR_NOMEM; + } + + int i, prio; + for (i = 0; i < CSP_CONN_MAX; i++) { + for (prio = 0; prio < CSP_RX_QUEUES; prio++) + arr_conn[i].rx_queue[prio] = csp_queue_create(CSP_RX_QUEUE_LENGTH, sizeof(csp_packet_t *)); + +#ifdef CSP_USE_QOS + arr_conn[i].rx_event = csp_queue_create(CSP_CONN_QUEUE_LENGTH, sizeof(int)); +#endif + arr_conn[i].state = CONN_CLOSED; + + if (csp_mutex_create(&arr_conn[i].lock) != CSP_MUTEX_OK) { + csp_log_error("Failed to create connection lock"); + return CSP_ERR_NOMEM; + } + +#ifdef CSP_USE_RDP + if (csp_rdp_allocate(&arr_conn[i]) != CSP_ERR_NONE) { + csp_log_error("Failed to create queues for RDP in csp_conn_init"); + return CSP_ERR_NOMEM; + } +#endif + } + + if (csp_bin_sem_create(&conn_lock) != CSP_SEMAPHORE_OK) { + csp_log_error("No more memory for conn semaphore"); + return CSP_ERR_NOMEM; + } + + return CSP_ERR_NONE; + +} + +csp_conn_t * csp_conn_find(uint32_t id, uint32_t mask) { + + /* Search for matching connection */ + int i; + csp_conn_t * conn; + id = (id & mask); + for (i = 0; i < CSP_CONN_MAX; i++) { + conn = &arr_conn[i]; + if ((conn->state != CONN_CLOSED) && (conn->type == CONN_CLIENT) && ((conn->idin.ext & mask) == id)) + return conn; + } + + return NULL; + +} + +static int csp_conn_flush_rx_queue(csp_conn_t * conn) { + + csp_packet_t * packet; + + int prio; + + /* Flush packet queues */ + for (prio = 0; prio < CSP_RX_QUEUES; prio++) { + while (csp_queue_dequeue(conn->rx_queue[prio], &packet, 0) == CSP_QUEUE_OK) + if (packet != NULL) + csp_buffer_free(packet); + } + + /* Flush event queue */ +#ifdef CSP_USE_QOS + int event; + while (csp_queue_dequeue(conn->rx_event, &event, 0) == CSP_QUEUE_OK); +#endif + + return CSP_ERR_NONE; + +} + +csp_conn_t * csp_conn_allocate(csp_conn_type_t type) { + + int i, j; + static uint8_t csp_conn_last_given = 0; + csp_conn_t * conn; + + if (csp_bin_sem_wait(&conn_lock, 100) != CSP_SEMAPHORE_OK) { + csp_log_error("Failed to lock conn array"); + return NULL; + } + + /* Search for free connection */ + i = csp_conn_last_given; + i = (i + 1) % CSP_CONN_MAX; + + for (j = 0; j < CSP_CONN_MAX; j++) { + conn = &arr_conn[i]; + if (conn->state == CONN_CLOSED) + break; + i = (i + 1) % CSP_CONN_MAX; + } + + if (conn->state == CONN_OPEN) { + csp_log_error("No more free connections"); + csp_bin_sem_post(&conn_lock); + return NULL; + } + + conn->idin.ext = 0; + conn->idout.ext = 0; + conn->socket = NULL; + conn->timestamp = 0; + conn->type = type; + conn->state = CONN_OPEN; + + csp_conn_last_given = i; + csp_bin_sem_post(&conn_lock); + + return conn; + +} + +csp_conn_t * csp_conn_new(csp_id_t idin, csp_id_t idout) { + + /* Allocate connection structure */ + csp_conn_t * conn = csp_conn_allocate(CONN_CLIENT); + + if (conn) { + /* No lock is needed here, because nobody else * + * has a reference to this connection yet. */ + conn->idin.ext = idin.ext; + conn->idout.ext = idout.ext; + conn->timestamp = csp_get_ms(); + + /* Ensure connection queue is empty */ + csp_conn_flush_rx_queue(conn); + } + + return conn; + +} + +int csp_close(csp_conn_t * conn) { + + if (conn == NULL) { + csp_log_error("NULL Pointer given to csp_close"); + return CSP_ERR_INVAL; + } + + if (conn->state == CONN_CLOSED) { + csp_log_protocol("Conn already closed"); + return CSP_ERR_NONE; + } + +#ifdef CSP_USE_RDP + /* Ensure RDP knows this connection is closing */ + if (conn->idin.flags & CSP_FRDP || conn->idout.flags & CSP_FRDP) + if (csp_rdp_close(conn) == CSP_ERR_AGAIN) + return CSP_ERR_NONE; +#endif + + /* Lock connection array while closing connection */ + if (csp_bin_sem_wait(&conn_lock, 100) != CSP_SEMAPHORE_OK) { + csp_log_error("Failed to lock conn array"); + return CSP_ERR_TIMEDOUT; + } + + /* Set to closed */ + conn->state = CONN_CLOSED; + + /* Ensure connection queue is empty */ + csp_conn_flush_rx_queue(conn); + + if (conn->socket && (conn->type == CONN_SERVER) && (conn->opts & (CSP_SO_CONN_LESS | CSP_SO_INTERNAL_LISTEN))) { + csp_queue_remove(conn->socket); + conn->socket = NULL; + } + + /* Reset RDP state */ +#ifdef CSP_USE_RDP + if (conn->idin.flags & CSP_FRDP) + csp_rdp_flush_all(conn); +#endif + + /* Unlock connection array */ + csp_bin_sem_post(&conn_lock); + + return CSP_ERR_NONE; +} + +csp_conn_t * csp_connect(uint8_t prio, uint8_t dest, uint8_t dport, uint32_t timeout, uint32_t opts) { + + /* Force options on all connections */ + opts |= CSP_CONNECTION_SO; + + /* Generate identifier */ + csp_id_t incoming_id, outgoing_id; + incoming_id.pri = prio; + incoming_id.dst = csp_get_address(); + incoming_id.src = dest; + incoming_id.sport = dport; + incoming_id.flags = 0; + outgoing_id.pri = prio; + outgoing_id.dst = dest; + outgoing_id.src = csp_get_address(); + outgoing_id.dport = dport; + outgoing_id.flags = 0; + + /* Set connection options */ + if (opts & CSP_O_NOCRC32) { + opts &= ~CSP_O_CRC32; + } + + if (opts & CSP_O_RDP) { +#ifdef CSP_USE_RDP + incoming_id.flags |= CSP_FRDP; + outgoing_id.flags |= CSP_FRDP; +#else + csp_log_error("Attempt to create RDP connection, but CSP was compiled without RDP support"); + return NULL; +#endif + } + + if (opts & CSP_O_HMAC) { +#ifdef CSP_USE_HMAC + outgoing_id.flags |= CSP_FHMAC; + incoming_id.flags |= CSP_FHMAC; +#else + csp_log_error("Attempt to create HMAC authenticated connection, but CSP was compiled without HMAC support"); + return NULL; +#endif + } + + if (opts & CSP_O_XTEA) { +#ifdef CSP_USE_XTEA + outgoing_id.flags |= CSP_FXTEA; + incoming_id.flags |= CSP_FXTEA; +#else + csp_log_error("Attempt to create XTEA encrypted connection, but CSP was compiled without XTEA support"); + return NULL; +#endif + } + + if (opts & CSP_O_CRC32) { +#ifdef CSP_USE_CRC32 + outgoing_id.flags |= CSP_FCRC32; + incoming_id.flags |= CSP_FCRC32; +#else + csp_log_error("Attempt to create CRC32 validated connection, but CSP was compiled without CRC32 support"); + return NULL; +#endif + } + + /* Find an unused ephemeral port */ + csp_conn_t * conn = NULL; + + /* Wait for sport lock - note that csp_conn_new(..) is called inside the lock! */ + if (csp_bin_sem_wait(&sport_lock, 1000) != CSP_SEMAPHORE_OK) + return NULL; + + const uint8_t start = sport; + while (++sport != start) { + if (sport > CSP_ID_PORT_MAX) + sport = CSP_MAX_BIND_PORT + 1; + + outgoing_id.sport = sport; + incoming_id.dport = sport; + + /* Match on destination port of _incoming_ identifier */ + if (csp_conn_find(incoming_id.ext, CSP_ID_DPORT_MASK) == NULL) { + /* Break - we found an unused ephemeral port + allocate connection while locked to mark port in use */ + conn = csp_conn_new(incoming_id, outgoing_id); + break; + } + } + + /* Post sport lock */ + csp_bin_sem_post(&sport_lock); + + if (conn == NULL) + return NULL; + + /* Set connection options */ + conn->opts = opts; + +#ifdef CSP_USE_RDP + /* Call Transport Layer connect */ + if (outgoing_id.flags & CSP_FRDP) { + /* If the transport layer has failed to connect + * deallocate connection structure again and return NULL */ + if (csp_rdp_connect(conn, timeout) != CSP_ERR_NONE) { + csp_close(conn); + return NULL; + } + } +#endif + + /* We have a successful connection */ + return conn; + +} + +inline int csp_conn_dport(csp_conn_t * conn) { + + return conn->idin.dport; + +} + +inline int csp_conn_sport(csp_conn_t * conn) { + + return conn->idin.sport; + +} + +inline int csp_conn_dst(csp_conn_t * conn) { + + return conn->idin.dst; + +} + +inline int csp_conn_src(csp_conn_t * conn) { + + return conn->idin.src; + +} + +inline int csp_conn_flags(csp_conn_t * conn) { + + return conn->idin.flags; + +} + +#ifdef CSP_DEBUG +void csp_conn_print_table(void) { + + int i; + csp_conn_t * conn; + + for (i = 0; i < CSP_CONN_MAX; i++) { + conn = &arr_conn[i]; + printf("[%02u %p] S:%u, %u -> %u, %u -> %u, sock: %p\r\n", + i, conn, conn->state, conn->idin.src, conn->idin.dst, + conn->idin.dport, conn->idin.sport, conn->socket); +#ifdef CSP_USE_RDP + if (conn->idin.flags & CSP_FRDP) + csp_rdp_conn_print(conn); +#endif + } +} + +int csp_conn_print_table_str(char * str_buf, int str_size) { + + int i, start = 0; + csp_conn_t * conn; + char buf[100]; + + /* Display up to 10 connections */ + if (CSP_CONN_MAX - 10 > 0) + start = CSP_CONN_MAX - 10; + + for (i = start; i < CSP_CONN_MAX; i++) { + conn = &arr_conn[i]; + snprintf(buf, sizeof(buf), "[%02u %p] S:%u, %u -> %u, %u -> %u, sock: %p\n", + i, conn, conn->state, conn->idin.src, conn->idin.dst, + conn->idin.dport, conn->idin.sport, conn->socket); + + strncat(str_buf, buf, str_size); + if ((str_size -= strlen(buf)) <= 0) + break; + } + + return CSP_ERR_NONE; +} +#endif + +const csp_conn_t * csp_conn_get_array(size_t * size) +{ + *size = CSP_CONN_MAX; + return arr_conn; +} diff --git a/thirdparty/libcsp/src/csp_conn.h b/thirdparty/libcsp/src/csp_conn.h new file mode 100644 index 00000000..3fa0ff52 --- /dev/null +++ b/thirdparty/libcsp/src/csp_conn.h @@ -0,0 +1,112 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef _CSP_CONN_H_ +#define _CSP_CONN_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +#include + +#include + +#include +#include + +/** @brief Connection states */ +typedef enum { + CONN_CLOSED = 0, + CONN_OPEN = 1, +} csp_conn_state_t; + +/** @brief Connection types */ +typedef enum { + CONN_CLIENT = 0, + CONN_SERVER = 1, +} csp_conn_type_t; + +typedef enum { + RDP_CLOSED = 0, + RDP_SYN_SENT, + RDP_SYN_RCVD, + RDP_OPEN, + RDP_CLOSE_WAIT, +} csp_rdp_state_t; + +/** @brief RDP Connection header + * @note Do not try to pack this struct, the posix sem handle will stop working */ +typedef struct { + csp_rdp_state_t state; /**< Connection state */ + uint16_t snd_nxt; /**< The sequence number of the next segment that is to be sent */ + uint16_t snd_una; /**< The sequence number of the oldest unacknowledged segment */ + uint16_t snd_iss; /**< The initial send sequence number */ + uint16_t rcv_cur; /**< The sequence number of the last segment received correctly and in sequence */ + uint16_t rcv_irs; /**< The initial receive sequence number */ + uint16_t rcv_lsa; /**< The last sequence number acknowledged by the receiver */ + uint32_t window_size; + uint32_t conn_timeout; + uint32_t packet_timeout; + uint32_t delayed_acks; + uint32_t ack_timeout; + uint32_t ack_delay_count; + uint32_t ack_timestamp; + csp_bin_sem_handle_t tx_wait; + csp_queue_handle_t tx_queue; + csp_queue_handle_t rx_queue; +} csp_rdp_t; + +/** @brief Connection struct */ +struct csp_conn_s { + csp_conn_type_t type; /* Connection type (CONN_CLIENT or CONN_SERVER) */ + csp_conn_state_t state; /* Connection state (CONN_OPEN or CONN_CLOSED) */ + csp_mutex_t lock; /* Connection structure lock */ + csp_id_t idin; /* Identifier received */ + csp_id_t idout; /* Identifier transmitted */ +#ifdef CSP_USE_QOS + csp_queue_handle_t rx_event; /* Event queue for RX packets */ +#endif + csp_queue_handle_t rx_queue[CSP_RX_QUEUES]; /* Queue for RX packets */ + csp_queue_handle_t socket; /* Socket to be "woken" when first packet is ready */ + uint32_t timestamp; /* Time the connection was opened */ + uint32_t opts; /* Connection or socket options */ +#ifdef CSP_USE_RDP + csp_rdp_t rdp; /* RDP state */ +#endif +}; + +int csp_conn_lock(csp_conn_t * conn, uint32_t timeout); +int csp_conn_unlock(csp_conn_t * conn); +int csp_conn_enqueue_packet(csp_conn_t * conn, csp_packet_t * packet); +int csp_conn_init(void); +csp_conn_t * csp_conn_allocate(csp_conn_type_t type); +csp_conn_t * csp_conn_find(uint32_t id, uint32_t mask); +csp_conn_t * csp_conn_new(csp_id_t idin, csp_id_t idout); +void csp_conn_check_timeouts(void); +int csp_conn_get_rxq(int prio); + +const csp_conn_t * csp_conn_get_array(size_t * size); // for test purposes only! + +#ifdef __cplusplus +} /* extern "C" */ +#endif + +#endif // _CSP_CONN_H_ diff --git a/thirdparty/libcsp/src/csp_crc32.c b/thirdparty/libcsp/src/csp_crc32.c new file mode 100644 index 00000000..8bf2145f --- /dev/null +++ b/thirdparty/libcsp/src/csp_crc32.c @@ -0,0 +1,140 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include +#include +#include + +#include +#include + +#include + +#ifdef CSP_USE_CRC32 + +#ifdef __AVR__ +#include +static const uint32_t crc_tab[256] PROGMEM = { +#else +static const uint32_t crc_tab[256] = { +#endif + 0x00000000, 0xF26B8303, 0xE13B70F7, 0x1350F3F4, 0xC79A971F, 0x35F1141C, 0x26A1E7E8, 0xD4CA64EB, + 0x8AD958CF, 0x78B2DBCC, 0x6BE22838, 0x9989AB3B, 0x4D43CFD0, 0xBF284CD3, 0xAC78BF27, 0x5E133C24, + 0x105EC76F, 0xE235446C, 0xF165B798, 0x030E349B, 0xD7C45070, 0x25AFD373, 0x36FF2087, 0xC494A384, + 0x9A879FA0, 0x68EC1CA3, 0x7BBCEF57, 0x89D76C54, 0x5D1D08BF, 0xAF768BBC, 0xBC267848, 0x4E4DFB4B, + 0x20BD8EDE, 0xD2D60DDD, 0xC186FE29, 0x33ED7D2A, 0xE72719C1, 0x154C9AC2, 0x061C6936, 0xF477EA35, + 0xAA64D611, 0x580F5512, 0x4B5FA6E6, 0xB93425E5, 0x6DFE410E, 0x9F95C20D, 0x8CC531F9, 0x7EAEB2FA, + 0x30E349B1, 0xC288CAB2, 0xD1D83946, 0x23B3BA45, 0xF779DEAE, 0x05125DAD, 0x1642AE59, 0xE4292D5A, + 0xBA3A117E, 0x4851927D, 0x5B016189, 0xA96AE28A, 0x7DA08661, 0x8FCB0562, 0x9C9BF696, 0x6EF07595, + 0x417B1DBC, 0xB3109EBF, 0xA0406D4B, 0x522BEE48, 0x86E18AA3, 0x748A09A0, 0x67DAFA54, 0x95B17957, + 0xCBA24573, 0x39C9C670, 0x2A993584, 0xD8F2B687, 0x0C38D26C, 0xFE53516F, 0xED03A29B, 0x1F682198, + 0x5125DAD3, 0xA34E59D0, 0xB01EAA24, 0x42752927, 0x96BF4DCC, 0x64D4CECF, 0x77843D3B, 0x85EFBE38, + 0xDBFC821C, 0x2997011F, 0x3AC7F2EB, 0xC8AC71E8, 0x1C661503, 0xEE0D9600, 0xFD5D65F4, 0x0F36E6F7, + 0x61C69362, 0x93AD1061, 0x80FDE395, 0x72966096, 0xA65C047D, 0x5437877E, 0x4767748A, 0xB50CF789, + 0xEB1FCBAD, 0x197448AE, 0x0A24BB5A, 0xF84F3859, 0x2C855CB2, 0xDEEEDFB1, 0xCDBE2C45, 0x3FD5AF46, + 0x7198540D, 0x83F3D70E, 0x90A324FA, 0x62C8A7F9, 0xB602C312, 0x44694011, 0x5739B3E5, 0xA55230E6, + 0xFB410CC2, 0x092A8FC1, 0x1A7A7C35, 0xE811FF36, 0x3CDB9BDD, 0xCEB018DE, 0xDDE0EB2A, 0x2F8B6829, + 0x82F63B78, 0x709DB87B, 0x63CD4B8F, 0x91A6C88C, 0x456CAC67, 0xB7072F64, 0xA457DC90, 0x563C5F93, + 0x082F63B7, 0xFA44E0B4, 0xE9141340, 0x1B7F9043, 0xCFB5F4A8, 0x3DDE77AB, 0x2E8E845F, 0xDCE5075C, + 0x92A8FC17, 0x60C37F14, 0x73938CE0, 0x81F80FE3, 0x55326B08, 0xA759E80B, 0xB4091BFF, 0x466298FC, + 0x1871A4D8, 0xEA1A27DB, 0xF94AD42F, 0x0B21572C, 0xDFEB33C7, 0x2D80B0C4, 0x3ED04330, 0xCCBBC033, + 0xA24BB5A6, 0x502036A5, 0x4370C551, 0xB11B4652, 0x65D122B9, 0x97BAA1BA, 0x84EA524E, 0x7681D14D, + 0x2892ED69, 0xDAF96E6A, 0xC9A99D9E, 0x3BC21E9D, 0xEF087A76, 0x1D63F975, 0x0E330A81, 0xFC588982, + 0xB21572C9, 0x407EF1CA, 0x532E023E, 0xA145813D, 0x758FE5D6, 0x87E466D5, 0x94B49521, 0x66DF1622, + 0x38CC2A06, 0xCAA7A905, 0xD9F75AF1, 0x2B9CD9F2, 0xFF56BD19, 0x0D3D3E1A, 0x1E6DCDEE, 0xEC064EED, + 0xC38D26C4, 0x31E6A5C7, 0x22B65633, 0xD0DDD530, 0x0417B1DB, 0xF67C32D8, 0xE52CC12C, 0x1747422F, + 0x49547E0B, 0xBB3FFD08, 0xA86F0EFC, 0x5A048DFF, 0x8ECEE914, 0x7CA56A17, 0x6FF599E3, 0x9D9E1AE0, + 0xD3D3E1AB, 0x21B862A8, 0x32E8915C, 0xC083125F, 0x144976B4, 0xE622F5B7, 0xF5720643, 0x07198540, + 0x590AB964, 0xAB613A67, 0xB831C993, 0x4A5A4A90, 0x9E902E7B, 0x6CFBAD78, 0x7FAB5E8C, 0x8DC0DD8F, + 0xE330A81A, 0x115B2B19, 0x020BD8ED, 0xF0605BEE, 0x24AA3F05, 0xD6C1BC06, 0xC5914FF2, 0x37FACCF1, + 0x69E9F0D5, 0x9B8273D6, 0x88D28022, 0x7AB90321, 0xAE7367CA, 0x5C18E4C9, 0x4F48173D, 0xBD23943E, + 0xF36E6F75, 0x0105EC76, 0x12551F82, 0xE03E9C81, 0x34F4F86A, 0xC69F7B69, 0xD5CF889D, 0x27A40B9E, + 0x79B737BA, 0x8BDCB4B9, 0x988C474D, 0x6AE7C44E, 0xBE2DA0A5, 0x4C4623A6, 0x5F16D052, 0xAD7D5351 }; + +uint32_t csp_crc32_memory(const uint8_t * data, uint32_t length) { + uint32_t crc; + + crc = 0xFFFFFFFF; + while (length--) +#ifdef __AVR__ + crc = pgm_read_dword(&crc_tab[(crc ^ *data++) & 0xFFL]) ^ (crc >> 8); +#else + crc = crc_tab[(crc ^ *data++) & 0xFFL] ^ (crc >> 8); +#endif + + return (crc ^ 0xFFFFFFFF); +} + +int csp_crc32_append(csp_packet_t * packet, bool include_header) { + + uint32_t crc; + + /* NULL pointer check */ + if (packet == NULL) + return CSP_ERR_INVAL; + + /* Calculate CRC32, convert to network byte order */ + if (include_header) { + crc = csp_crc32_memory((uint8_t *) &packet->id, packet->length + sizeof(packet->id)); + } else { + crc = csp_crc32_memory(packet->data, packet->length); + } + crc = csp_hton32(crc); + + /* Copy checksum to packet */ + memcpy(&packet->data[packet->length], &crc, sizeof(uint32_t)); + packet->length += sizeof(uint32_t); + + return CSP_ERR_NONE; + +} + +int csp_crc32_verify(csp_packet_t * packet, bool include_header) { + + uint32_t crc; + + /* NULL pointer check */ + if (packet == NULL) + return CSP_ERR_INVAL; + + if (packet->length < sizeof(uint32_t)) + return CSP_ERR_INVAL; + + /* Calculate CRC32, convert to network byte order */ + if (include_header) { + crc = csp_crc32_memory((uint8_t *) &packet->id, packet->length + sizeof(packet->id) - sizeof(uint32_t)); + } else { + crc = csp_crc32_memory(packet->data, packet->length - sizeof(uint32_t)); + } + crc = csp_hton32(crc); + + /* Compare calculated checksum with packet header */ + if (memcmp(&packet->data[packet->length] - sizeof(uint32_t), &crc, sizeof(uint32_t)) != 0) { + /* CRC32 failed */ + return CSP_ERR_INVAL; + } else { + /* Strip CRC32 */ + packet->length -= sizeof(uint32_t); + return CSP_ERR_NONE; + } + +} + +#endif // CSP_USE_CRC32 diff --git a/thirdparty/libcsp/src/csp_debug.c b/thirdparty/libcsp/src/csp_debug.c new file mode 100644 index 00000000..2e710cb3 --- /dev/null +++ b/thirdparty/libcsp/src/csp_debug.c @@ -0,0 +1,133 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include +#include +#include +#include + +#ifdef __AVR__ +#include +#endif + +/* CSP includes */ +#include + +#include + +/* Custom debug function */ +csp_debug_hook_func_t csp_debug_hook_func = NULL; + +/* Debug levels */ +static bool csp_debug_level_enabled[] = { + [CSP_ERROR] = true, + [CSP_WARN] = true, + [CSP_INFO] = false, + [CSP_BUFFER] = false, + [CSP_PACKET] = false, + [CSP_PROTOCOL] = false, + [CSP_LOCK] = false, +}; + +/* Some compilers do not support weak symbols, so this function + * can be used instead to set a custom debug hook */ +void csp_debug_hook_set(csp_debug_hook_func_t f) +{ + csp_debug_hook_func = f; +} + +void do_csp_debug(csp_debug_level_t level, const char *format, ...) +{ + int color = COLOR_RESET; + va_list args; + + /* Don't print anything if log level is disabled */ + if (level > CSP_LOCK || !csp_debug_level_enabled[level]) + return; + + switch(level) { + case CSP_INFO: + color = COLOR_GREEN | COLOR_BOLD; + break; + case CSP_ERROR: + color = COLOR_RED | COLOR_BOLD; + break; + case CSP_WARN: + color = COLOR_YELLOW | COLOR_BOLD; + break; + case CSP_BUFFER: + color = COLOR_MAGENTA; + break; + case CSP_PACKET: + color = COLOR_GREEN; + break; + case CSP_PROTOCOL: + color = COLOR_BLUE; + break; + case CSP_LOCK: + color = COLOR_CYAN; + break; + default: + return; + } + + va_start(args, format); + + /* If csp_debug_hook symbol is defined, pass on the message. + * Otherwise, just print with pretty colors ... */ + if (csp_debug_hook_func) { + csp_debug_hook_func(level, format, args); + } else { + csp_sys_set_color(color); +#ifdef __AVR__ + vfprintf_P(stdout, format, args); +#else + vprintf(format, args); +#endif + printf("\r\n"); + csp_sys_set_color(COLOR_RESET); + } + + va_end(args); +} + +void csp_debug_set_level(csp_debug_level_t level, bool value) +{ + if (level > CSP_LOCK) + return; + csp_debug_level_enabled[level] = value; +} + +int csp_debug_get_level(csp_debug_level_t level) +{ + if (level > CSP_LOCK) + return 0; + return csp_debug_level_enabled[level]; +} + +void csp_debug_toggle_level(csp_debug_level_t level) +{ + if (level > CSP_LOCK) { + printf("Max level is 6\r\n"); + return; + } + csp_debug_level_enabled[level] = (csp_debug_level_enabled[level]) ? false : true; + printf("Level %u: value %u\r\n", level, csp_debug_level_enabled[level]); +} diff --git a/thirdparty/libcsp/src/csp_dedup.c b/thirdparty/libcsp/src/csp_dedup.c new file mode 100644 index 00000000..d263c7a4 --- /dev/null +++ b/thirdparty/libcsp/src/csp_dedup.c @@ -0,0 +1,66 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include +#include +#include +#include + +#include +#include +#include + +#include "csp_dedup.h" + +/* Check the last CSP_DEDUP_COUNT packets for duplicates */ +#define CSP_DEDUP_COUNT 16 + +/* Only consider packet a duplicate if received under CSP_DEDUP_WINDOW_MS ago */ +#define CSP_DEDUP_WINDOW_MS 1000 + +/* Store packet CRC's in a ringbuffer */ +static uint32_t csp_dedup_array[CSP_DEDUP_COUNT] = {}; +static uint32_t csp_dedup_timestamp[CSP_DEDUP_COUNT] = {}; +static int csp_dedup_in = 0; + +bool csp_dedup_is_duplicate(csp_packet_t *packet) +{ + /* Calculate CRC32 for packet */ + uint32_t crc = csp_crc32_memory((const uint8_t *) &packet->id, packet->length + sizeof(packet->id)); + + /* Check if we have received this packet before */ + for (int i = 0; i < CSP_DEDUP_COUNT; i++) { + + /* Check for match */ + if (crc == csp_dedup_array[i]) { + + /* Check the timestamp */ + if (csp_get_ms() < csp_dedup_timestamp[i] + CSP_DEDUP_WINDOW_MS) + return true; + } + } + + /* If not, insert packet into duplicate list */ + csp_dedup_array[csp_dedup_in] = crc; + csp_dedup_timestamp[csp_dedup_in] = csp_get_ms(); + csp_dedup_in = (csp_dedup_in + 1) % CSP_DEDUP_COUNT; + + return false; +} diff --git a/thirdparty/libcsp/src/csp_dedup.h b/thirdparty/libcsp/src/csp_dedup.h new file mode 100644 index 00000000..75a3f124 --- /dev/null +++ b/thirdparty/libcsp/src/csp_dedup.h @@ -0,0 +1,31 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef CSP_DEDUP_H_ +#define CSP_DEDUP_H_ + +/** + * Check for a duplicate packet + * @param packet pointer to packet + * @return false if not a duplicate, true if duplicate + */ +bool csp_dedup_is_duplicate(csp_packet_t *packet); + +#endif /* CSP_DEDUP_H_ */ diff --git a/thirdparty/libcsp/src/csp_endian.c b/thirdparty/libcsp/src/csp_endian.c new file mode 100644 index 00000000..6d0ef226 --- /dev/null +++ b/thirdparty/libcsp/src/csp_endian.c @@ -0,0 +1,204 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include + +/* CSP includes */ +#include +#include + +/* Convert 16-bit number from host byte order to network byte order */ +inline uint16_t __attribute__ ((__const__)) csp_hton16(uint16_t h16) { +#ifdef CSP_BIG_ENDIAN + return h16; +#else + return (((h16 & 0xff00) >> 8) | + ((h16 & 0x00ff) << 8)); +#endif +} + +/* Convert 16-bit number from network byte order to host byte order */ +inline uint16_t __attribute__ ((__const__)) csp_ntoh16(uint16_t n16) { + return csp_hton16(n16); +} + +/* Convert 32-bit number from host byte order to network byte order */ +inline uint32_t __attribute__ ((__const__)) csp_hton32(uint32_t h32) { +#ifdef CSP_BIG_ENDIAN + return h32; +#else + return (((h32 & 0xff000000) >> 24) | + ((h32 & 0x000000ff) << 24) | + ((h32 & 0x0000ff00) << 8) | + ((h32 & 0x00ff0000) >> 8)); +#endif +} + +/* Convert 32-bit number from network byte order to host byte order */ +inline uint32_t __attribute__ ((__const__)) csp_ntoh32(uint32_t n32) { + return csp_hton32(n32); +} + +/* Convert 64-bit number from host byte order to network byte order */ +inline uint64_t __attribute__ ((__const__)) csp_hton64(uint64_t h64) { +#ifdef CSP_BIG_ENDIAN + return h64; +#else + return (((h64 & 0xff00000000000000LL) >> 56) | + ((h64 & 0x00000000000000ffLL) << 56) | + ((h64 & 0x00ff000000000000LL) >> 40) | + ((h64 & 0x000000000000ff00LL) << 40) | + ((h64 & 0x0000ff0000000000LL) >> 24) | + ((h64 & 0x0000000000ff0000LL) << 24) | + ((h64 & 0x000000ff00000000LL) >> 8) | + ((h64 & 0x00000000ff000000LL) << 8)); +#endif +} + +/* Convert 64-bit number from host byte order to network byte order */ +inline uint64_t __attribute__ ((__const__)) csp_ntoh64(uint64_t n64) { + return csp_hton64(n64); +} + +/* Convert 16-bit number from host byte order to big endian byte order */ +inline uint16_t __attribute__ ((__const__)) csp_htobe16(uint16_t h16) { + return csp_hton16(h16); +} + +/* Convert 16-bit number from host byte order to little endian byte order */ +inline uint16_t __attribute__ ((__const__)) csp_htole16(uint16_t h16) { +#ifdef CSP_LITTLE_ENDIAN + return h16; +#else + return (((h16 & 0xff00) >> 8) | + ((h16 & 0x00ff) << 8)); +#endif +} + +/* Convert 16-bit number from big endian byte order to little endian byte order */ +inline uint16_t __attribute__ ((__const__)) csp_betoh16(uint16_t be16) { + return csp_ntoh16(be16); +} + +/* Convert 16-bit number from little endian byte order to host byte order */ +inline uint16_t __attribute__ ((__const__)) csp_letoh16(uint16_t le16) { + return csp_htole16(le16); +} + +/* Convert 32-bit number from host byte order to big endian byte order */ +inline uint32_t __attribute__ ((__const__)) csp_htobe32(uint32_t h32) { + return csp_hton32(h32); +} + +/* Convert 32-bit number from little endian byte order to host byte order */ +inline uint32_t __attribute__ ((__const__)) csp_htole32(uint32_t h32) { +#ifdef CSP_LITTLE_ENDIAN + return h32; +#else + return (((h32 & 0xff000000) >> 24) | + ((h32 & 0x000000ff) << 24) | + ((h32 & 0x0000ff00) << 8) | + ((h32 & 0x00ff0000) >> 8)); +#endif +} + +/* Convert 32-bit number from big endian byte order to host byte order */ +inline uint32_t __attribute__ ((__const__)) csp_betoh32(uint32_t be32) { + return csp_ntoh32(be32); +} + +/* Convert 32-bit number from little endian byte order to host byte order */ +inline uint32_t __attribute__ ((__const__)) csp_letoh32(uint32_t le32) { + return csp_htole32(le32); +} + +/* Convert 64-bit number from host byte order to big endian byte order */ +inline uint64_t __attribute__ ((__const__)) csp_htobe64(uint64_t h64) { + return csp_hton64(h64); +} + +/* Convert 64-bit number from host byte order to little endian byte order */ +inline uint64_t __attribute__ ((__const__)) csp_htole64(uint64_t h64) { +#ifdef CSP_LITTLE_ENDIAN + return h64; +#else + return (((h64 & 0xff00000000000000LL) >> 56) | + ((h64 & 0x00000000000000ffLL) << 56) | + ((h64 & 0x00ff000000000000LL) >> 40) | + ((h64 & 0x000000000000ff00LL) << 40) | + ((h64 & 0x0000ff0000000000LL) >> 24) | + ((h64 & 0x0000000000ff0000LL) << 24) | + ((h64 & 0x000000ff00000000LL) >> 8) | + ((h64 & 0x00000000ff000000LL) << 8)); +#endif +} + +/* Convert 64-bit number from big endian byte order to host byte order */ +inline uint64_t __attribute__ ((__const__)) csp_betoh64(uint64_t be64) { + return csp_ntoh64(be64); +} + +/* Convert 64-bit number from little endian byte order to host byte order */ +inline uint64_t __attribute__ ((__const__)) csp_letoh64(uint64_t le64) { + return csp_htole64(le64); +} + + +/* Convert float from host byte order to network byte order */ +inline float __attribute__ ((__const__)) csp_htonflt(float f) { +#ifdef CSP_BIG_ENDIAN + return f; +#else + union v { + float f; + uint32_t i; + }; + union v val; + val.f = f; + val.i = csp_hton32(val.i); + return val.f; +#endif +} + +/* Convert float from host byte order to network byte order */ +inline float __attribute__ ((__const__)) csp_ntohflt(float f) { + return csp_htonflt(f); +} + +/* Convert double from host byte order to network byte order */ +inline double __attribute__ ((__const__)) csp_htondbl(double d) { +#ifdef CSP_BIG_ENDIAN + return d; +#else + union v { + double d; + uint64_t i; + }; + union v val; + val.d = d; + val.i = csp_hton64(val.i); + return val.d; +#endif +} + +/* Convert float from host byte order to network byte order */ +inline double __attribute__ ((__const__)) csp_ntohdbl(double d) { + return csp_htondbl(d); +} diff --git a/thirdparty/libcsp/src/csp_hex_dump.c b/thirdparty/libcsp/src/csp_hex_dump.c new file mode 100644 index 00000000..af0a2660 --- /dev/null +++ b/thirdparty/libcsp/src/csp_hex_dump.c @@ -0,0 +1,55 @@ +#include +#include + +void csp_hex_dump (const char *desc, void *addr, int len) +{ + int i; + unsigned char buff[17]; + unsigned char *pc = (unsigned char*)addr; + + // Output description if given. + if (desc != NULL) + printf ("%s:\r\n", desc); + + if (len == 0) { + printf(" ZERO LENGTH\r\n"); + return; + } + if (len < 0) { + printf(" NEGATIVE LENGTH: %i\r\n",len); + return; + } + + // Process every byte in the data. + for (i = 0; i < len; i++) { + // Multiple of 16 means new line (with line offset). + + if ((i % 16) == 0) { + // Just don't print ASCII for the zeroth line. + if (i != 0) + printf (" %s\r\n", buff); + + // Output the offset. + printf (" %p ", addr + i); + } + + // Now the hex code for the specific character. + printf (" %02x", pc[i]); + + // And store a printable ASCII character for later. + if ((pc[i] < 0x20) || (pc[i] > 0x7e)) + buff[i % 16] = '.'; + else + buff[i % 16] = pc[i]; + buff[(i % 16) + 1] = '\0'; + } + + // Pad out last line if not exactly 16 characters. + while ((i % 16) != 0) { + printf (" "); + i++; + } + + // And print the final ASCII bit. + printf (" %s\r\n", buff); +} diff --git a/thirdparty/libcsp/src/csp_iflist.c b/thirdparty/libcsp/src/csp_iflist.c new file mode 100644 index 00000000..2bfef422 --- /dev/null +++ b/thirdparty/libcsp/src/csp_iflist.c @@ -0,0 +1,100 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include +#include + +/* Interfaces are stored in a linked list*/ +static csp_iface_t * interfaces = NULL; + +csp_iface_t * csp_iflist_get_by_name(const char *name) { + csp_iface_t *ifc = interfaces; + while(ifc) { + if (strncmp(ifc->name, name, 10) == 0) + break; + ifc = ifc->next; + } + return ifc; +} + +void csp_iflist_add(csp_iface_t *ifc) { + + /* Add interface to pool */ + if (interfaces == NULL) { + /* This is the first interface to be added */ + interfaces = ifc; + ifc->next = NULL; + } else { + /* One or more interfaces were already added */ + csp_iface_t * i = interfaces; + while (i != ifc && i->next) + i = i->next; + + /* Insert interface last if not already in pool */ + if (i != ifc && i->next == NULL) { + i->next = ifc; + ifc->next = NULL; + } + } + +} + +csp_iface_t * csp_iflist_get(void) +{ + return interfaces; +} + +#ifdef CSP_DEBUG +static int csp_bytesize(char *buf, int len, unsigned long int n) { + char postfix; + double size; + + if (n >= 1048576) { + size = n/1048576.0; + postfix = 'M'; + } else if (n >= 1024) { + size = n/1024.; + postfix = 'K'; + } else { + size = n; + postfix = 'B'; + } + + return snprintf(buf, len, "%.1f%c", size, postfix); +} + +void csp_iflist_print(void) { + csp_iface_t * i = interfaces; + char txbuf[25], rxbuf[25]; + + while (i) { + csp_bytesize(txbuf, 25, i->txbytes); + csp_bytesize(rxbuf, 25, i->rxbytes); + printf("%-5s tx: %05"PRIu32" rx: %05"PRIu32" txe: %05"PRIu32" rxe: %05"PRIu32"\r\n" + " drop: %05"PRIu32" autherr: %05"PRIu32 " frame: %05"PRIu32"\r\n" + " txb: %"PRIu32" (%s) rxb: %"PRIu32" (%s)\r\n\r\n", + i->name, i->tx, i->rx, i->tx_error, i->rx_error, i->drop, + i->autherr, i->frame, i->txbytes, txbuf, i->rxbytes, rxbuf); + i = i->next; + } + +} +#endif + diff --git a/thirdparty/libcsp/src/csp_io.c b/thirdparty/libcsp/src/csp_io.c new file mode 100644 index 00000000..3d7f614a --- /dev/null +++ b/thirdparty/libcsp/src/csp_io.c @@ -0,0 +1,502 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include +#include +#include +#include + +/* CSP includes */ +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +#include +#include + +#include "csp_io.h" +#include "csp_port.h" +#include "csp_conn.h" +#include "csp_route.h" +#include "csp_promisc.h" +#include "csp_qfifo.h" +#include "transport/csp_transport.h" + +/** CSP address of this node */ +static uint8_t csp_my_address; + +/* Hostname, model and build revision */ +static const char *csp_hostname = NULL; +static const char *csp_model = NULL; +static const char *csp_revision = GIT_REV; + +#ifdef CSP_USE_PROMISC +extern csp_queue_handle_t csp_promisc_queue; +#endif + +void csp_set_address(uint8_t addr) +{ + csp_my_address = addr; +} + +uint8_t csp_get_address(void) +{ + return csp_my_address; +} + +void csp_set_hostname(const char *hostname) +{ + csp_hostname = hostname; +} + +const char *csp_get_hostname(void) +{ + return csp_hostname; +} + +void csp_set_model(const char *model) +{ + csp_model = model; +} + +const char *csp_get_model(void) +{ + return csp_model; +} + +void csp_set_revision(const char *revision) +{ + csp_revision = revision; +} + +const char *csp_get_revision(void) +{ + return csp_revision; +} + +int csp_init(unsigned char address) { + + int ret; + + /* Initialize CSP */ + csp_set_address(address); + + ret = csp_conn_init(); + if (ret != CSP_ERR_NONE) + return ret; + + ret = csp_port_init(); + if (ret != CSP_ERR_NONE) + return ret; + + ret = csp_qfifo_init(); + if (ret != CSP_ERR_NONE) + return ret; + + /* Loopback */ + csp_iflist_add(&csp_if_lo); + + /* Register loopback route */ + csp_route_set(csp_get_address(), &csp_if_lo, CSP_NODE_MAC); + + /* Also register loopback as default, until user redefines default route */ + csp_route_set(CSP_DEFAULT_ROUTE, &csp_if_lo, CSP_NODE_MAC); + + return CSP_ERR_NONE; + +} + +csp_socket_t * csp_socket(uint32_t opts) { + + /* Validate socket options */ +#ifndef CSP_USE_RDP + if (opts & CSP_SO_RDPREQ) { + csp_log_error("Attempt to create socket that requires RDP, but CSP was compiled without RDP support"); + return NULL; + } +#endif + +#ifndef CSP_USE_XTEA + if (opts & CSP_SO_XTEAREQ) { + csp_log_error("Attempt to create socket that requires XTEA, but CSP was compiled without XTEA support"); + return NULL; + } +#endif + +#ifndef CSP_USE_HMAC + if (opts & CSP_SO_HMACREQ) { + csp_log_error("Attempt to create socket that requires HMAC, but CSP was compiled without HMAC support"); + return NULL; + } +#endif + +#ifndef CSP_USE_CRC32 + if (opts & CSP_SO_CRC32REQ) { + csp_log_error("Attempt to create socket that requires CRC32, but CSP was compiled without CRC32 support"); + return NULL; + } +#endif + + /* Drop packet if reserved flags are set */ + if (opts & ~(CSP_SO_RDPREQ | CSP_SO_XTEAREQ | CSP_SO_HMACREQ | CSP_SO_CRC32REQ | CSP_SO_CONN_LESS)) { + csp_log_error("Invalid socket option"); + return NULL; + } + + /* Use CSP buffers instead? */ + csp_socket_t * sock = csp_conn_allocate(CONN_SERVER); + if (sock == NULL) + return NULL; + + /* If connectionless, init the queue to a pre-defined size + * if not, the user must init the queue using csp_listen */ + if (opts & CSP_SO_CONN_LESS) { + sock->socket = csp_queue_create(CSP_CONN_QUEUE_LENGTH, sizeof(csp_packet_t *)); + if (sock->socket == NULL) { + csp_close(sock); + return NULL; + } + } else { + sock->socket = NULL; + } + sock->opts = opts; + + return sock; + +} + +csp_conn_t * csp_accept(csp_socket_t * sock, uint32_t timeout) { + + if (sock == NULL) + return NULL; + + if (sock->socket == NULL) + return NULL; + + csp_conn_t * conn; + if (csp_queue_dequeue(sock->socket, &conn, timeout) == CSP_QUEUE_OK) + return conn; + + return NULL; + +} + +csp_packet_t * csp_read(csp_conn_t * conn, uint32_t timeout) { + + csp_packet_t * packet = NULL; + + if (conn == NULL || conn->state != CONN_OPEN) + return NULL; + +#ifdef CSP_USE_QOS + int prio, event; + if (csp_queue_dequeue(conn->rx_event, &event, timeout) != CSP_QUEUE_OK) + return NULL; + + for (prio = 0; prio < CSP_RX_QUEUES; prio++) + if (csp_queue_dequeue(conn->rx_queue[prio], &packet, 0) == CSP_QUEUE_OK) + break; +#else + if (csp_queue_dequeue(conn->rx_queue[0], &packet, timeout) != CSP_QUEUE_OK) + return NULL; +#endif + +#ifdef CSP_USE_RDP + /* Packet read could trigger ACK transmission */ + if (conn->idin.flags & CSP_FRDP && conn->rdp.delayed_acks) + csp_rdp_check_ack(conn); + +#endif + + return packet; + +} + +int csp_send_direct(csp_id_t idout, csp_packet_t * packet, csp_iface_t * ifout, uint32_t timeout) { + + if (packet == NULL) { + csp_log_error("csp_send_direct called with NULL packet"); + goto err; + } + + if ((ifout == NULL) || (ifout->nexthop == NULL)) { + csp_log_error("No route to host: %#08x", idout.ext); + goto err; + } + + csp_log_packet("OUT: S %u, D %u, Dp %u, Sp %u, Pr %u, Fl 0x%02X, Sz %u VIA: %s", + idout.src, idout.dst, idout.dport, idout.sport, idout.pri, idout.flags, packet->length, ifout->name); + + /* Copy identifier to packet (before crc, xtea and hmac) */ + packet->id.ext = idout.ext; + +#ifdef CSP_USE_PROMISC + /* Loopback traffic is added to promisc queue by the router */ + if (idout.dst != csp_get_address() && idout.src == csp_get_address()) { + packet->id.ext = idout.ext; + csp_promisc_add(packet); + } +#endif + + /* Only encrypt packets from the current node */ + if (idout.src == csp_get_address()) { + /* Append HMAC */ + if (idout.flags & CSP_FHMAC) { +#ifdef CSP_USE_HMAC + /* Calculate and add HMAC (does not include header for backwards compatability with csp1.x) */ + if (csp_hmac_append(packet, false) != 0) { + /* HMAC append failed */ + csp_log_warn("HMAC append failed!"); + goto tx_err; + } +#else + csp_log_warn("Attempt to send packet with HMAC, but CSP was compiled without HMAC support. Discarding packet"); + goto tx_err; +#endif + } + + /* Append CRC32 */ + if (idout.flags & CSP_FCRC32) { +#ifdef CSP_USE_CRC32 + /* Calculate and add CRC32 (does not include header for backwards compatability with csp1.x) */ + if (csp_crc32_append(packet, false) != 0) { + /* CRC32 append failed */ + csp_log_warn("CRC32 append failed!"); + goto tx_err; + } +#else + csp_log_warn("Attempt to send packet with CRC32, but CSP was compiled without CRC32 support. Sending without CRC32r"); + idout.flags &= ~(CSP_FCRC32); +#endif + } + + if (idout.flags & CSP_FXTEA) { +#ifdef CSP_USE_XTEA + /* Create nonce */ + uint32_t nonce, nonce_n; + nonce = (uint32_t)rand(); + nonce_n = csp_hton32(nonce); + memcpy(&packet->data[packet->length], &nonce_n, sizeof(nonce_n)); + + /* Create initialization vector */ + uint32_t iv[2] = {nonce, 1}; + + /* Encrypt data */ + if (csp_xtea_encrypt(packet->data, packet->length, iv) != 0) { + /* Encryption failed */ + csp_log_warn("Encryption failed! Discarding packet"); + goto tx_err; + } + + packet->length += sizeof(nonce_n); +#else + csp_log_warn("Attempt to send XTEA encrypted packet, but CSP was compiled without XTEA support. Discarding packet"); + goto tx_err; +#endif + } + } + + /* Store length before passing to interface */ + uint16_t bytes = packet->length; + uint16_t mtu = ifout->mtu; + + if (mtu > 0 && bytes > mtu) + goto tx_err; + + if ((*ifout->nexthop)(ifout, packet, timeout) != CSP_ERR_NONE) + goto tx_err; + + ifout->tx++; + ifout->txbytes += bytes; + return CSP_ERR_NONE; + +tx_err: + ifout->tx_error++; +err: + return CSP_ERR_TX; + +} + +int csp_send(csp_conn_t * conn, csp_packet_t * packet, uint32_t timeout) { + + int ret; + + if ((conn == NULL) || (packet == NULL) || (conn->state != CONN_OPEN)) { + csp_log_error("Invalid call to csp_send"); + return 0; + } + +#ifdef CSP_USE_RDP + if (conn->idout.flags & CSP_FRDP) { + if (csp_rdp_send(conn, packet, timeout) != CSP_ERR_NONE) { + csp_iface_t * ifout = csp_rtable_find_iface(conn->idout.dst); + if (ifout != NULL) + ifout->tx_error++; + csp_log_warn("RDP send failed!"); + return 0; + } + } +#endif + + csp_iface_t * ifout = csp_rtable_find_iface(conn->idout.dst); + ret = csp_send_direct(conn->idout, packet, ifout, timeout); + + return (ret == CSP_ERR_NONE) ? 1 : 0; + +} + +int csp_send_prio(uint8_t prio, csp_conn_t * conn, csp_packet_t * packet, uint32_t timeout) { + conn->idout.pri = prio; + return csp_send(conn, packet, timeout); +} + +int csp_transaction_persistent(csp_conn_t * conn, uint32_t timeout, void * outbuf, int outlen, void * inbuf, int inlen) { + + int size = (inlen > outlen) ? inlen : outlen; + csp_packet_t * packet = csp_buffer_get(size); + if (packet == NULL) + return 0; + + /* Copy the request */ + if (outlen > 0 && outbuf != NULL) + memcpy(packet->data, outbuf, outlen); + packet->length = outlen; + + if (!csp_send(conn, packet, timeout)) { + csp_buffer_free(packet); + return 0; + } + + /* If no reply is expected, return now */ + if (inlen == 0) + return 1; + + packet = csp_read(conn, timeout); + if (packet == NULL) + return 0; + + if ((inlen != -1) && ((int)packet->length != inlen)) { + csp_log_error("Reply length %u expected %u", packet->length, inlen); + csp_buffer_free(packet); + return 0; + } + + memcpy(inbuf, packet->data, packet->length); + int length = packet->length; + csp_buffer_free(packet); + return length; + +} + +int csp_transaction(uint8_t prio, uint8_t dest, uint8_t port, uint32_t timeout, void * outbuf, int outlen, void * inbuf, int inlen) { + return csp_transaction2(prio, dest, port, timeout, outbuf, outlen, inbuf, inlen, 0); +} + +int csp_transaction2(uint8_t prio, uint8_t dest, uint8_t port, uint32_t timeout, void * outbuf, int outlen, void * inbuf, int inlen, uint32_t opts) { + + csp_conn_t * conn = csp_connect(prio, dest, port, 0, opts); + if (conn == NULL) + return 0; + + int status = csp_transaction_persistent(conn, timeout, outbuf, outlen, inbuf, inlen); + + csp_close(conn); + + return status; + +} + +csp_packet_t * csp_recvfrom(csp_socket_t * socket, uint32_t timeout) { + + if ((socket == NULL) || (!(socket->opts & CSP_SO_CONN_LESS))) + return NULL; + + csp_packet_t * packet = NULL; + csp_queue_dequeue(socket->socket, &packet, timeout); + + return packet; + +} + +int csp_sendto(uint8_t prio, uint8_t dest, uint8_t dport, uint8_t src_port, uint32_t opts, csp_packet_t * packet, uint32_t timeout) { + + packet->id.flags = 0; + + if (opts & CSP_O_RDP) { + csp_log_error("Attempt to create RDP packet on connection-less socket"); + return CSP_ERR_INVAL; + } + + if (opts & CSP_O_HMAC) { +#ifdef CSP_USE_HMAC + packet->id.flags |= CSP_FHMAC; +#else + csp_log_error("Attempt to create HMAC authenticated packet, but CSP was compiled without HMAC support"); + return CSP_ERR_NOTSUP; +#endif + } + + if (opts & CSP_O_XTEA) { +#ifdef CSP_USE_XTEA + packet->id.flags |= CSP_FXTEA; +#else + csp_log_error("Attempt to create XTEA encrypted packet, but CSP was compiled without XTEA support"); + return CSP_ERR_NOTSUP; +#endif + } + + if (opts & CSP_O_CRC32) { +#ifdef CSP_USE_CRC32 + packet->id.flags |= CSP_FCRC32; +#else + csp_log_error("Attempt to create CRC32 validated packet, but CSP was compiled without CRC32 support"); + return CSP_ERR_NOTSUP; +#endif + } + + packet->id.dst = dest; + packet->id.dport = dport; + packet->id.src = csp_get_address(); + packet->id.sport = src_port; + packet->id.pri = prio; + + csp_iface_t * ifout = csp_rtable_find_iface(dest); + if (csp_send_direct(packet->id, packet, ifout, timeout) != CSP_ERR_NONE) + return CSP_ERR_NOTSUP; + + return CSP_ERR_NONE; + +} + +int csp_sendto_reply(csp_packet_t * request_packet, csp_packet_t * reply_packet, uint32_t opts, uint32_t timeout) { + if (request_packet == NULL) + return CSP_ERR_INVAL; + + return csp_sendto(request_packet->id.pri, request_packet->id.src, request_packet->id.sport, request_packet->id.dport, opts, reply_packet, timeout); +} diff --git a/thirdparty/libcsp/src/csp_io.h b/thirdparty/libcsp/src/csp_io.h new file mode 100644 index 00000000..6ea8dfec --- /dev/null +++ b/thirdparty/libcsp/src/csp_io.h @@ -0,0 +1,47 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef _CSP_IO_H_ +#define _CSP_IO_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +#include + +#include + +/** + * Function to transmit a frame without an existing connection structure. + * This function is used for stateless transmissions + * @param idout 32bit CSP identifier + * @param packet pointer to packet, + * @param ifout pointer to output interface + * @param timeout a timeout to wait for TX to complete. NOTE: not all underlying drivers supports flow-control. + * @return returns 1 if successful and 0 otherwise. you MUST free the frame yourself if the transmission was not successful. + */ +int csp_send_direct(csp_id_t idout, csp_packet_t * packet, csp_iface_t * ifout, uint32_t timeout); + +#ifdef __cplusplus +} /* extern "C" */ +#endif + +#endif // _CSP_IO_H_ diff --git a/thirdparty/libcsp/src/csp_port.c b/thirdparty/libcsp/src/csp_port.c new file mode 100644 index 00000000..2a4ac2a9 --- /dev/null +++ b/thirdparty/libcsp/src/csp_port.c @@ -0,0 +1,105 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include +#include +#include + +/* CSP includes */ +#include +#include + +#include +#include +#include + +#include "csp_port.h" +#include "csp_conn.h" + +/* Allocation of ports */ +static csp_port_t ports[CSP_MAX_BIND_PORT + 2]; + +csp_socket_t * csp_port_get_socket(unsigned int port) { + + csp_socket_t * ret = NULL; + + if (port >= CSP_ANY) + return NULL; + + /* Match dport to socket or local "catch all" port number */ + if (ports[port].state == PORT_OPEN) + ret = ports[port].socket; + else if (ports[CSP_ANY].state == PORT_OPEN) + ret = ports[CSP_ANY].socket; + + return ret; + +} + +int csp_port_init(void) { + + memset(ports, PORT_CLOSED, sizeof(csp_port_t) * (CSP_MAX_BIND_PORT + 2)); + + return CSP_ERR_NONE; + +} + +int csp_listen(csp_socket_t * socket, size_t conn_queue_length) { + + if (socket == NULL) + return CSP_ERR_INVAL; + + socket->socket = csp_queue_create(conn_queue_length, sizeof(csp_conn_t *)); + if (socket->socket == NULL) + return CSP_ERR_NOMEM; + + socket->opts |= CSP_SO_INTERNAL_LISTEN; + + return CSP_ERR_NONE; + +} + +int csp_bind(csp_socket_t * socket, uint8_t port) { + + if (socket == NULL) + return CSP_ERR_INVAL; + + if (port > CSP_ANY) { + csp_log_error("Only ports from 0-%u (and CSP_ANY for default) are available for incoming ports", CSP_ANY); + return CSP_ERR_INVAL; + } + + /* Check if port number is valid */ + if (ports[port].state != PORT_CLOSED) { + csp_log_error("Port %d is already in use", port); + return CSP_ERR_USED; + } + + csp_log_info("Binding socket %p to port %u", socket, port); + + /* Save listener */ + ports[port].socket = socket; + ports[port].state = PORT_OPEN; + + return CSP_ERR_NONE; + +} + + diff --git a/thirdparty/libcsp/src/csp_port.h b/thirdparty/libcsp/src/csp_port.h new file mode 100644 index 00000000..d2ec06e9 --- /dev/null +++ b/thirdparty/libcsp/src/csp_port.h @@ -0,0 +1,55 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef _CSP_PORT_H_ +#define _CSP_PORT_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +#include + +#include + +/** @brief Port states */ +typedef enum { + PORT_CLOSED = 0, + PORT_OPEN = 1, +} csp_port_state_t; + +/** @brief Port struct */ +typedef struct { + csp_port_state_t state; // Port state + csp_socket_t * socket; // New connections are added to this socket's conn queue +} csp_port_t; + +/** + * Init ports array + */ +int csp_port_init(void); + +csp_socket_t * csp_port_get_socket(unsigned int dport); + +#ifdef __cplusplus +} /* extern "C" */ +#endif + +#endif // _CSP_PORT_H_ diff --git a/thirdparty/libcsp/src/csp_promisc.c b/thirdparty/libcsp/src/csp_promisc.c new file mode 100644 index 00000000..5f156c33 --- /dev/null +++ b/thirdparty/libcsp/src/csp_promisc.c @@ -0,0 +1,82 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include +#include + +#ifdef CSP_USE_PROMISC + +static csp_queue_handle_t csp_promisc_queue = NULL; +static int csp_promisc_enabled = 0; + +int csp_promisc_enable(unsigned int buf_size) { + + /* If queue already initialised */ + if (csp_promisc_queue != NULL) { + csp_promisc_enabled = 1; + return CSP_ERR_NONE; + } + + /* Create packet queue */ + csp_promisc_queue = csp_queue_create(buf_size, sizeof(csp_packet_t *)); + + if (csp_promisc_queue == NULL) + return CSP_ERR_INVAL; + + csp_promisc_enabled = 1; + return CSP_ERR_NONE; + +} + +void csp_promisc_disable(void) { + csp_promisc_enabled = 0; +} + +csp_packet_t * csp_promisc_read(uint32_t timeout) { + + if (csp_promisc_queue == NULL) + return NULL; + + csp_packet_t * packet = NULL; + csp_queue_dequeue(csp_promisc_queue, &packet, timeout); + + return packet; + +} + +void csp_promisc_add(csp_packet_t * packet) { + + if (csp_promisc_enabled == 0) + return; + + if (csp_promisc_queue != NULL) { + /* Make a copy of the message and queue it to the promiscuous task */ + csp_packet_t *packet_copy = csp_buffer_clone(packet); + if (packet_copy != NULL) { + if (csp_queue_enqueue(csp_promisc_queue, &packet_copy, 0) != CSP_QUEUE_OK) { + csp_log_error("Promiscuous mode input queue full"); + csp_buffer_free(packet_copy); + } + } + } + +} + +#endif diff --git a/thirdparty/libcsp/src/csp_promisc.h b/thirdparty/libcsp/src/csp_promisc.h new file mode 100644 index 00000000..be62edda --- /dev/null +++ b/thirdparty/libcsp/src/csp_promisc.h @@ -0,0 +1,30 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef CSP_PROMISC_H_ +#define CSP_PROMISC_H_ + +/** + * Add packet to promiscuous mode packet queue + * @param packet Packet to add to the queue + */ +void csp_promisc_add(csp_packet_t * packet); + +#endif /* CSP_PROMISC_H_ */ diff --git a/thirdparty/libcsp/src/csp_qfifo.c b/thirdparty/libcsp/src/csp_qfifo.c new file mode 100644 index 00000000..9329b2ca --- /dev/null +++ b/thirdparty/libcsp/src/csp_qfifo.c @@ -0,0 +1,149 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include +#include +#include +#include "csp_qfifo.h" + +static csp_queue_handle_t qfifo[CSP_ROUTE_FIFOS]; +#ifdef CSP_USE_QOS +static csp_queue_handle_t qfifo_events; +#endif + +int csp_qfifo_init(void) { + int prio; + + /* Create router fifos for each priority */ + for (prio = 0; prio < CSP_ROUTE_FIFOS; prio++) { + if (qfifo[prio] == NULL) { + qfifo[prio] = csp_queue_create(CSP_FIFO_INPUT, sizeof(csp_qfifo_t)); + if (!qfifo[prio]) + return CSP_ERR_NOMEM; + } + } + +#ifdef CSP_USE_QOS + /* Create QoS fifo notification queue */ + qfifo_events = csp_queue_create(CSP_FIFO_INPUT, sizeof(int)); + if (!qfifo_events) + return CSP_ERR_NOMEM; +#endif + + return CSP_ERR_NONE; + +} + +int csp_qfifo_read(csp_qfifo_t * input) { + +#ifdef CSP_USE_QOS + int prio, found, event; + + /* Wait for packet in any queue */ + if (csp_queue_dequeue(qfifo_events, &event, FIFO_TIMEOUT) != CSP_QUEUE_OK) + return CSP_ERR_TIMEDOUT; + + /* Find packet with highest priority */ + found = 0; + for (prio = 0; prio < CSP_ROUTE_FIFOS; prio++) { + if (csp_queue_dequeue(qfifo[prio], input, 0) == CSP_QUEUE_OK) { + found = 1; + break; + } + } + + if (!found) { + csp_log_warn("Spurious wakeup: No packet found"); + return CSP_ERR_TIMEDOUT; + } +#else + if (csp_queue_dequeue(qfifo[0], input, FIFO_TIMEOUT) != CSP_QUEUE_OK) + return CSP_ERR_TIMEDOUT; +#endif + + return CSP_ERR_NONE; + +} + +void csp_qfifo_write(csp_packet_t * packet, csp_iface_t * interface, CSP_BASE_TYPE * pxTaskWoken) { + + int result; + + if (packet == NULL) { + if (pxTaskWoken == NULL) { // Only do logging in non-ISR context + csp_log_warn("csp_new packet called with NULL packet"); + } + return; + } else if (interface == NULL) { + if (pxTaskWoken == NULL) { // Only do logging in non-ISR context + csp_log_warn("csp_new packet called with NULL interface"); + } + if (pxTaskWoken == NULL) + csp_buffer_free(packet); + else + csp_buffer_free_isr(packet); + return; + } + + csp_qfifo_t queue_element; + queue_element.interface = interface; + queue_element.packet = packet; + +#ifdef CSP_USE_QOS + int fifo = packet->id.pri; +#else + int fifo = 0; +#endif + + if (pxTaskWoken == NULL) + result = csp_queue_enqueue(qfifo[fifo], &queue_element, 0); + else + result = csp_queue_enqueue_isr(qfifo[fifo], &queue_element, pxTaskWoken); + +#ifdef CSP_USE_QOS + static int event = 0; + + if (result == CSP_QUEUE_OK) { + if (pxTaskWoken == NULL) + csp_queue_enqueue(qfifo_events, &event, 0); + else + csp_queue_enqueue_isr(qfifo_events, &event, pxTaskWoken); + } +#endif + + if (result != CSP_QUEUE_OK) { + if (pxTaskWoken == NULL) { // Only do logging in non-ISR context + csp_log_warn("ERROR: Routing input FIFO is FULL. Dropping packet."); + } + interface->drop++; + if (pxTaskWoken == NULL) + csp_buffer_free(packet); + else + csp_buffer_free_isr(packet); + } + +} + +void csp_qfifo_wake_up(void) { + csp_qfifo_t queue_element; + queue_element.interface = NULL; + queue_element.packet = NULL; + csp_queue_enqueue(qfifo[0], &queue_element, 0); +} diff --git a/thirdparty/libcsp/src/csp_qfifo.h b/thirdparty/libcsp/src/csp_qfifo.h new file mode 100644 index 00000000..2910c48d --- /dev/null +++ b/thirdparty/libcsp/src/csp_qfifo.h @@ -0,0 +1,54 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef CSP_QFIFO_H_ +#define CSP_QFIFO_H_ + +#ifdef CSP_USE_RDP +#define FIFO_TIMEOUT 100 //! If RDP is enabled, the router needs to awake some times to check timeouts +#else +#define FIFO_TIMEOUT CSP_MAX_DELAY //! If no RDP, the router can sleep untill data arrives +#endif + +/** + * Init FIFO/QOS queues + * @return CSP_ERR type + */ +int csp_qfifo_init(void); + +typedef struct { + csp_iface_t * interface; + csp_packet_t * packet; +} csp_qfifo_t; + +/** + * Read next packet from router input queue + * @param input pointer to router queue item element + * @return CSP_ERR type + */ +int csp_qfifo_read(csp_qfifo_t * input); + +/** + * Wake up any task (e.g. router) waiting on messages. + * For testing. + */ +void csp_qfifo_wake_up(void); + +#endif /* CSP_QFIFO_H_ */ diff --git a/thirdparty/libcsp/src/csp_route.c b/thirdparty/libcsp/src/csp_route.c new file mode 100644 index 00000000..bc843577 --- /dev/null +++ b/thirdparty/libcsp/src/csp_route.c @@ -0,0 +1,346 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include +#include +#include + +/* CSP includes */ +#include +#include +#include + +#include +#include + +#include +#include + +#include "csp_port.h" +#include "csp_conn.h" +#include "csp_io.h" +#include "csp_promisc.h" +#include "csp_qfifo.h" +#include "csp_dedup.h" +#include "transport/csp_transport.h" + +/** + * Check supported packet options + * @param interface pointer to incoming interface + * @param packet pointer to packet + * @return CSP_ERR_NONE is all options are supported, CSP_ERR_NOTSUP if not + */ +static int csp_route_check_options(csp_iface_t *interface, csp_packet_t *packet) +{ +#ifndef CSP_USE_XTEA + /* Drop XTEA packets */ + if (packet->id.flags & CSP_FXTEA) { + csp_log_error("Received XTEA encrypted packet, but CSP was compiled without XTEA support. Discarding packet"); + interface->autherr++; + return CSP_ERR_NOTSUP; + } +#endif + +#ifndef CSP_USE_HMAC + /* Drop HMAC packets */ + if (packet->id.flags & CSP_FHMAC) { + csp_log_error("Received packet with HMAC, but CSP was compiled without HMAC support. Discarding packet"); + interface->autherr++; + return CSP_ERR_NOTSUP; + } +#endif + +#ifndef CSP_USE_RDP + /* Drop RDP packets */ + if (packet->id.flags & CSP_FRDP) { + csp_log_error("Received RDP packet, but CSP was compiled without RDP support. Discarding packet"); + interface->rx_error++; + return CSP_ERR_NOTSUP; + } +#endif + return CSP_ERR_NONE; +} + +/** + * Helper function to decrypt, check auth and CRC32 + * @param security_opts either socket_opts or conn_opts + * @param interface pointer to incoming interface + * @param packet pointer to packet + * @return -1 Missing feature, -2 XTEA error, -3 CRC error, -4 HMAC error, 0 = OK. + */ +static int csp_route_security_check(uint32_t security_opts, csp_iface_t * interface, csp_packet_t * packet) { + +#ifdef CSP_USE_XTEA + /* XTEA encrypted packet */ + if (packet->id.flags & CSP_FXTEA) { + /* Read nonce */ + uint32_t nonce; + memcpy(&nonce, &packet->data[packet->length - sizeof(nonce)], sizeof(nonce)); + nonce = csp_ntoh32(nonce); + packet->length -= sizeof(nonce); + + /* Create initialization vector */ + uint32_t iv[2] = {nonce, 1}; + + /* Decrypt data */ + if (csp_xtea_decrypt(packet->data, packet->length, iv) != 0) { + /* Decryption failed */ + csp_log_error("Decryption failed! Discarding packet"); + interface->autherr++; + return CSP_ERR_XTEA; + } + } else if (security_opts & CSP_SO_XTEAREQ) { + csp_log_warn("Received packet without XTEA encryption. Discarding packet"); + interface->autherr++; + return CSP_ERR_XTEA; + } +#endif + + /* CRC32 verified packet */ + if (packet->id.flags & CSP_FCRC32) { +#ifdef CSP_USE_CRC32 + if (packet->length < 4) + csp_log_error("Too short packet for CRC32, %u", packet->length); + /* Verify CRC32 (does not include header for backwards compatability with csp1.x) */ + if (csp_crc32_verify(packet, false) != 0) { + /* Checksum failed */ + csp_log_error("CRC32 verification error! Discarding packet"); + interface->rx_error++; + return CSP_ERR_CRC32; + } + } else if (security_opts & CSP_SO_CRC32REQ) { + csp_log_warn("Received packet without CRC32. Accepting packet"); +#else + /* Strip CRC32 field and accept the packet */ + csp_log_warn("Received packet with CRC32, but CSP was compiled without CRC32 support. Accepting packet"); + packet->length -= sizeof(uint32_t); +#endif + } + +#ifdef CSP_USE_HMAC + /* HMAC authenticated packet */ + if (packet->id.flags & CSP_FHMAC) { + /* Verify HMAC (does not include header for backwards compatability with csp1.x) */ + if (csp_hmac_verify(packet, false) != 0) { + /* HMAC failed */ + csp_log_error("HMAC verification error! Discarding packet"); + interface->autherr++; + return CSP_ERR_HMAC; + } + } else if (security_opts & CSP_SO_HMACREQ) { + csp_log_warn("Received packet without HMAC. Discarding packet"); + interface->autherr++; + return CSP_ERR_HMAC; + } +#endif + +#ifdef CSP_USE_RDP + /* RDP packet */ + if (!(packet->id.flags & CSP_FRDP)) { + if (security_opts & CSP_SO_RDPREQ) { + csp_log_warn("Received packet without RDP header. Discarding packet"); + interface->rx_error++; + return CSP_ERR_INVAL; + } + } +#endif + + return CSP_ERR_NONE; + +} + +int csp_route_work(uint32_t timeout) { + + csp_qfifo_t input; + csp_packet_t * packet; + csp_conn_t * conn; + csp_socket_t * socket; + +#ifdef CSP_USE_RDP + /* Check connection timeouts (currently only for RDP) */ + csp_conn_check_timeouts(); +#endif + + /* Get next packet to route */ + if (csp_qfifo_read(&input) != CSP_ERR_NONE) + return -1; + + packet = input.packet; + if (!packet) + return -1; + + csp_log_packet("INP: S %u, D %u, Dp %u, Sp %u, Pr %u, Fl 0x%02X, Sz %"PRIu16" VIA: %s", + packet->id.src, packet->id.dst, packet->id.dport, + packet->id.sport, packet->id.pri, packet->id.flags, packet->length, input.interface->name); + + /* Here there be promiscuous mode */ +#ifdef CSP_USE_PROMISC + csp_promisc_add(packet); +#endif + +#ifdef CSP_USE_DEDUP + /* Check for duplicates */ + if (csp_dedup_is_duplicate(packet)) { + /* Discard packet */ + csp_log_packet("Duplicate packet discarded"); + input.interface->drop++; + csp_buffer_free(packet); + return 0; + } +#endif + + /* Now we count the message (since its deduplicated) */ + input.interface->rx++; + input.interface->rxbytes += packet->length; + + /* If the message is not to me, route the message to the correct interface */ + if ((packet->id.dst != csp_get_address()) && (packet->id.dst != CSP_BROADCAST_ADDR)) { + + /* Find the destination interface */ + csp_iface_t * dstif = csp_rtable_find_iface(packet->id.dst); + + /* If the message resolves to the input interface, don't loop it back out */ + if ((dstif == NULL) || ((dstif == input.interface) && (input.interface->split_horizon_off == 0))) { + csp_buffer_free(packet); + return 0; + } + + /* Otherwise, actually send the message */ + if (csp_send_direct(packet->id, packet, dstif, 0) != CSP_ERR_NONE) { + csp_log_warn("Router failed to send"); + csp_buffer_free(packet); + } + + /* Next message, please */ + return 0; + } + + /* Discard packets with unsupported options */ + if (csp_route_check_options(input.interface, packet) != CSP_ERR_NONE) { + csp_buffer_free(packet); + return 0; + } + + /* The message is to me, search for incoming socket */ + socket = csp_port_get_socket(packet->id.dport); + + /* If the socket is connection-less, deliver now */ + if (socket && (socket->opts & CSP_SO_CONN_LESS)) { + if (csp_route_security_check(socket->opts, input.interface, packet) < 0) { + csp_buffer_free(packet); + return 0; + } + if (csp_queue_enqueue(socket->socket, &packet, 0) != CSP_QUEUE_OK) { + csp_log_error("Conn-less socket queue full"); + csp_buffer_free(packet); + return 0; + } + return 0; + } + + /* Search for an existing connection */ + conn = csp_conn_find(packet->id.ext, CSP_ID_CONN_MASK); + + /* If this is an incoming packet on a new connection */ + if (conn == NULL) { + + /* Reject packet if no matching socket is found */ + if (!socket) { + csp_buffer_free(packet); + return 0; + } + + /* Run security check on incoming packet */ + if (csp_route_security_check(socket->opts, input.interface, packet) < 0) { + csp_buffer_free(packet); + return 0; + } + + /* New incoming connection accepted */ + csp_id_t idout; + idout.pri = packet->id.pri; + idout.src = csp_get_address(); + + idout.dst = packet->id.src; + idout.dport = packet->id.sport; + idout.sport = packet->id.dport; + idout.flags = packet->id.flags; + + /* Create connection */ + conn = csp_conn_new(packet->id, idout); + + if (!conn) { + csp_log_error("No more connections available"); + csp_buffer_free(packet); + return 0; + } + + /* Store the socket queue and options */ + conn->socket = socket->socket; + conn->opts = socket->opts; + + /* Packet to existing connection */ + } else { + + /* Run security check on incoming packet */ + if (csp_route_security_check(conn->opts, input.interface, packet) < 0) { + csp_buffer_free(packet); + return 0; + } + + } + +#ifdef CSP_USE_RDP + /* Pass packet to RDP module */ + if (packet->id.flags & CSP_FRDP) { + csp_rdp_new_packet(conn, packet); + return 0; + } +#endif + + /* Pass packet to UDP module */ + csp_udp_new_packet(conn, packet); + return 0; +} + +static CSP_DEFINE_TASK(csp_task_router) { + + /* Here there be routing */ + while (1) { + csp_route_work(FIFO_TIMEOUT); + } + + return CSP_TASK_RETURN; + +} + +int csp_route_start_task(unsigned int task_stack_size, unsigned int priority) { + + static csp_thread_handle_t handle_router; + int ret = csp_thread_create(csp_task_router, "RTE", task_stack_size, NULL, priority, &handle_router); + + if (ret != 0) { + csp_log_error("Failed to start router task"); + return CSP_ERR_NOMEM; + } + + return CSP_ERR_NONE; + +} diff --git a/thirdparty/libcsp/src/csp_route.h b/thirdparty/libcsp/src/csp_route.h new file mode 100644 index 00000000..2a20f49f --- /dev/null +++ b/thirdparty/libcsp/src/csp_route.h @@ -0,0 +1,24 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef _CSP_ROUTE_H_ +#define _CSP_ROUTE_H_ + +#endif // _CSP_ROUTE_H_ diff --git a/thirdparty/libcsp/src/csp_service_handler.c b/thirdparty/libcsp/src/csp_service_handler.c new file mode 100644 index 00000000..0090afc1 --- /dev/null +++ b/thirdparty/libcsp/src/csp_service_handler.c @@ -0,0 +1,334 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include +#include +#include + +/* CSP includes */ +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include "csp_route.h" + +#define CSP_RPS_MTU 196 + +/** + * The CSP CMP mempy function is used to, override the function used to + * read/write memory by peek and poke. + */ +#ifdef __AVR__ +static uint32_t wrap_32bit_memcpy(uint32_t to, const uint32_t from, size_t size) { + return (uint32_t) (uintptr_t) memcpy((void *) (uintptr_t) to, (const void *) (uintptr_t) from, size); +} +static csp_memcpy_fnc_t csp_cmp_memcpy_fnc = wrap_32bit_memcpy; +#else +static csp_memcpy_fnc_t csp_cmp_memcpy_fnc = (csp_memcpy_fnc_t) memcpy; +#endif + + +void csp_cmp_set_memcpy(csp_memcpy_fnc_t fnc) { + csp_cmp_memcpy_fnc = fnc; +} + +static int do_cmp_ident(struct csp_cmp_message *cmp) { + + /* Copy revision */ + strncpy(cmp->ident.revision, csp_get_revision(), CSP_CMP_IDENT_REV_LEN); + cmp->ident.revision[CSP_CMP_IDENT_REV_LEN - 1] = '\0'; + + /* Copy compilation date */ + strncpy(cmp->ident.date, __DATE__, CSP_CMP_IDENT_DATE_LEN); + cmp->ident.date[CSP_CMP_IDENT_DATE_LEN - 1] = '\0'; + + /* Copy compilation time */ + strncpy(cmp->ident.time, __TIME__, CSP_CMP_IDENT_TIME_LEN); + cmp->ident.time[CSP_CMP_IDENT_TIME_LEN - 1] = '\0'; + + /* Copy hostname */ + strncpy(cmp->ident.hostname, csp_get_hostname(), CSP_HOSTNAME_LEN); + cmp->ident.hostname[CSP_HOSTNAME_LEN - 1] = '\0'; + + /* Copy model name */ + strncpy(cmp->ident.model, csp_get_model(), CSP_MODEL_LEN); + cmp->ident.model[CSP_MODEL_LEN - 1] = '\0'; + + return CSP_ERR_NONE; + +} + +static int do_cmp_route_set(struct csp_cmp_message *cmp) { + + csp_iface_t *ifc = csp_iflist_get_by_name(cmp->route_set.interface); + if (ifc == NULL) + return CSP_ERR_INVAL; + + if (csp_route_set(cmp->route_set.dest_node, ifc, cmp->route_set.next_hop_mac) != CSP_ERR_NONE) + return CSP_ERR_INVAL; + + return CSP_ERR_NONE; + +} + +static int do_cmp_if_stats(struct csp_cmp_message *cmp) { + + csp_iface_t *ifc = csp_iflist_get_by_name(cmp->if_stats.interface); + if (ifc == NULL) + return CSP_ERR_INVAL; + + cmp->if_stats.tx = csp_hton32(ifc->tx); + cmp->if_stats.rx = csp_hton32(ifc->rx); + cmp->if_stats.tx_error = csp_hton32(ifc->tx_error); + cmp->if_stats.rx_error = csp_hton32(ifc->rx_error); + cmp->if_stats.drop = csp_hton32(ifc->drop); + cmp->if_stats.autherr = csp_hton32(ifc->autherr); + cmp->if_stats.frame = csp_hton32(ifc->frame); + cmp->if_stats.txbytes = csp_hton32(ifc->txbytes); + cmp->if_stats.rxbytes = csp_hton32(ifc->rxbytes); + cmp->if_stats.irq = csp_hton32(ifc->irq); + + return CSP_ERR_NONE; +} + +static int do_cmp_peek(struct csp_cmp_message *cmp) { + + cmp->peek.addr = csp_hton32(cmp->peek.addr); + if (cmp->peek.len > CSP_CMP_PEEK_MAX_LEN) + return CSP_ERR_INVAL; + + /* Dangerous, you better know what you are doing */ + csp_cmp_memcpy_fnc((csp_memptr_t) (uintptr_t) cmp->peek.data, (csp_memptr_t) (unsigned long) cmp->peek.addr, cmp->peek.len); + + return CSP_ERR_NONE; + +} + +static int do_cmp_poke(struct csp_cmp_message *cmp) { + + cmp->poke.addr = csp_hton32(cmp->poke.addr); + if (cmp->poke.len > CSP_CMP_POKE_MAX_LEN) + return CSP_ERR_INVAL; + + /* Extremely dangerous, you better know what you are doing */ + csp_cmp_memcpy_fnc((csp_memptr_t) (unsigned long) cmp->poke.addr, (csp_memptr_t) (uintptr_t) cmp->poke.data, cmp->poke.len); + + return CSP_ERR_NONE; + +} + +static int do_cmp_clock(struct csp_cmp_message *cmp) { + + cmp->clock.tv_sec = csp_ntoh32(cmp->clock.tv_sec); + cmp->clock.tv_nsec = csp_ntoh32(cmp->clock.tv_nsec); + + if ((cmp->clock.tv_sec != 0) && (clock_set_time != NULL)) { + clock_set_time(&cmp->clock); + } + + if (clock_get_time != NULL) { + clock_get_time(&cmp->clock); + } + + cmp->clock.tv_sec = csp_hton32(cmp->clock.tv_sec); + cmp->clock.tv_nsec = csp_hton32(cmp->clock.tv_nsec); + return CSP_ERR_NONE; + +} + +/* CSP Management Protocol handler */ +static int csp_cmp_handler(csp_conn_t * conn, csp_packet_t * packet) { + + int ret = CSP_ERR_INVAL; + struct csp_cmp_message * cmp = (struct csp_cmp_message *) packet->data; + + /* Ignore everything but requests */ + if (cmp->type != CSP_CMP_REQUEST) + return ret; + + switch (cmp->code) { + case CSP_CMP_IDENT: + ret = do_cmp_ident(cmp); + packet->length = CMP_SIZE(ident); + break; + + case CSP_CMP_ROUTE_SET: + ret = do_cmp_route_set(cmp); + packet->length = CMP_SIZE(route_set); + break; + + case CSP_CMP_IF_STATS: + ret = do_cmp_if_stats(cmp); + packet->length = CMP_SIZE(if_stats); + break; + + case CSP_CMP_PEEK: + ret = do_cmp_peek(cmp); + break; + + case CSP_CMP_POKE: + ret = do_cmp_poke(cmp); + break; + + case CSP_CMP_CLOCK: + ret = do_cmp_clock(cmp); + break; + + default: + ret = CSP_ERR_INVAL; + break; + } + + cmp->type = CSP_CMP_REPLY; + + return ret; +} + +void csp_service_handler(csp_conn_t * conn, csp_packet_t * packet) { + + switch (csp_conn_dport(conn)) { + + case CSP_CMP: + /* Pass to CMP handler */ + if (csp_cmp_handler(conn, packet) != CSP_ERR_NONE) { + csp_buffer_free(packet); + return; + } + break; + + case CSP_PING: + /* A ping means, just echo the packet, so no changes */ + csp_log_info("SERVICE: Ping received"); + break; + + case CSP_PS: { + /* Sanity check on request */ + if ((packet->length != 1) || (packet->data[0] != 0x55)) { + /* Sanity check failed */ + csp_buffer_free(packet); + /* Clear the packet, it has been freed */ + packet = NULL; + break; + } + /* Start by allocating just the right amount of memory */ + int task_list_size = csp_sys_tasklist_size(); + char * pslist = csp_malloc(task_list_size); + /* Check for malloc fail */ + if (pslist == NULL) { + /* Send out the data */ + strcpy((char *)packet->data, "Not enough memory"); + packet->length = strlen((char *)packet->data); + /* Break and let the default handling send packet */ + break; + } + + /* Retrieve the tasklist */ + csp_sys_tasklist(pslist); + int pslen = strnlen(pslist, task_list_size); + + /* Split the potentially very long string into packets */ + int i = 0; + while(i < pslen) { + + /* Allocate packet buffer, if need be */ + if (packet == NULL) + packet = csp_buffer_get(CSP_RPS_MTU); + if (packet == NULL) + break; + + /* Calculate length, either full MTU or the remainder */ + packet->length = (pslen - i > CSP_RPS_MTU) ? CSP_RPS_MTU : (pslen - i); + + /* Send out the data */ + memcpy(packet->data, &pslist[i], packet->length); + i += packet->length; + if (!csp_send(conn, packet, 0)) + csp_buffer_free(packet); + + /* Clear the packet reference when sent */ + packet = NULL; + + } + csp_free(pslist); + break; + } + + case CSP_MEMFREE: { + uint32_t total = csp_sys_memfree(); + + total = csp_hton32(total); + memcpy(packet->data, &total, sizeof(total)); + packet->length = sizeof(total); + + break; + } + + case CSP_REBOOT: { + uint32_t magic_word; + memcpy(&magic_word, packet->data, sizeof(magic_word)); + + magic_word = csp_ntoh32(magic_word); + + /* If the magic word is valid, reboot */ + if (magic_word == CSP_REBOOT_MAGIC) { + csp_sys_reboot(); + } else if (magic_word == CSP_REBOOT_SHUTDOWN_MAGIC) { + csp_sys_shutdown(); + } + + + + csp_buffer_free(packet); + return; + } + + case CSP_BUF_FREE: { + uint32_t size = csp_buffer_remaining(); + size = csp_hton32(size); + memcpy(packet->data, &size, sizeof(size)); + packet->length = sizeof(size); + break; + } + + case CSP_UPTIME: { + uint32_t time = csp_get_s(); + time = csp_hton32(time); + memcpy(packet->data, &time, sizeof(time)); + packet->length = sizeof(time); + break; + } + + default: + csp_buffer_free(packet); + return; + } + + if (packet != NULL) { + if (!csp_send(conn, packet, 0)) + csp_buffer_free(packet); + } + +} diff --git a/thirdparty/libcsp/src/csp_services.c b/thirdparty/libcsp/src/csp_services.c new file mode 100644 index 00000000..5392cb82 --- /dev/null +++ b/thirdparty/libcsp/src/csp_services.c @@ -0,0 +1,233 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include +#include +#include +#include + +/* CSP includes */ +#include +#include +#include + +#include + +int csp_ping(uint8_t node, uint32_t timeout, unsigned int size, uint8_t conn_options) { + + unsigned int i; + uint32_t start, time, status = 0; + + /* Counter */ + start = csp_get_ms(); + + /* Open connection */ + csp_conn_t * conn = csp_connect(CSP_PRIO_NORM, node, CSP_PING, timeout, conn_options); + if (conn == NULL) + return -1; + + /* Prepare data */ + csp_packet_t * packet; + packet = csp_buffer_get(size); + if (packet == NULL) + goto out; + + /* Set data to increasing numbers */ + packet->length = size; + for (i = 0; i < size; i++) + packet->data[i] = i; + + /* Try to send frame */ + if (!csp_send(conn, packet, 0)) + goto out; + + /* Read incoming frame */ + packet = csp_read(conn, timeout); + if (packet == NULL) + goto out; + + /* Ensure that the data was actually echoed */ + for (i = 0; i < size; i++) + if (packet->data[i] != i % (0xff + 1)) + goto out; + + status = 1; + +out: + /* Clean up */ + if (packet != NULL) + csp_buffer_free(packet); + csp_close(conn); + + /* We have a reply */ + time = (csp_get_ms() - start); + + if (status) { + return time; + } else { + return -1; + } + +} + +void csp_ping_noreply(uint8_t node) { + + /* Prepare data */ + csp_packet_t * packet; + packet = csp_buffer_get(1); + + /* Check malloc */ + if (packet == NULL) + return; + + /* Open connection */ + csp_conn_t * conn = csp_connect(CSP_PRIO_NORM, node, CSP_PING, 0, 0); + if (conn == NULL) { + csp_buffer_free(packet); + return; + } + + packet->data[0] = 0x55; + packet->length = 1; + + printf("Ping ignore reply node %u.\r\n", (unsigned int) node); + + /* Try to send frame */ + if (!csp_send(conn, packet, 0)) + csp_buffer_free(packet); + + csp_close(conn); + +} + +void csp_reboot(uint8_t node) { + uint32_t magic_word = csp_hton32(CSP_REBOOT_MAGIC); + csp_transaction(CSP_PRIO_NORM, node, CSP_REBOOT, 0, &magic_word, sizeof(magic_word), NULL, 0); +} + +void csp_shutdown(uint8_t node) { + uint32_t magic_word = csp_hton32(CSP_REBOOT_SHUTDOWN_MAGIC); + csp_transaction(CSP_PRIO_NORM, node, CSP_REBOOT, 0, &magic_word, sizeof(magic_word), NULL, 0); +} + +void csp_ps(uint8_t node, uint32_t timeout) { + + /* Open connection */ + csp_conn_t * conn = csp_connect(CSP_PRIO_NORM, node, CSP_PS, 0, 0); + if (conn == NULL) + return; + + /* Prepare data */ + csp_packet_t * packet; + packet = csp_buffer_get(95); + + /* Check malloc */ + if (packet == NULL) + goto out; + + packet->data[0] = 0x55; + packet->length = 1; + + printf("PS node %u: \r\n", (unsigned int) node); + + /* Try to send frame */ + if (!csp_send(conn, packet, 0)) + goto out; + + while(1) { + + /* Read incoming frame */ + packet = csp_read(conn, timeout); + if (packet == NULL) + break; + + /* We have a reply, add our own NULL char */ + packet->data[packet->length] = 0; + printf("%s", packet->data); + + /* Each packet from csp_read must to be freed by user */ + csp_buffer_free(packet); + } + + printf("\r\n"); + + /* Clean up */ +out: + if (packet != NULL) + csp_buffer_free(packet); + csp_close(conn); + +} + +void csp_memfree(uint8_t node, uint32_t timeout) { + + uint32_t memfree; + + int status = csp_transaction(CSP_PRIO_NORM, node, CSP_MEMFREE, timeout, NULL, 0, &memfree, sizeof(memfree)); + if (status == 0) { + printf("Network error\r\n"); + return; + } + + /* Convert from network to host order */ + memfree = csp_ntoh32(memfree); + + printf("Free Memory at node %u is %"PRIu32" bytes\r\n", (unsigned int) node, memfree); + +} + +void csp_buf_free(uint8_t node, uint32_t timeout) { + + uint32_t size = 0; + + int status = csp_transaction(CSP_PRIO_NORM, node, CSP_BUF_FREE, timeout, NULL, 0, &size, sizeof(size)); + if (status == 0) { + printf("Network error\r\n"); + return; + } + size = csp_ntoh32(size); + printf("Free buffers at node %u is %"PRIu32"\r\n", (unsigned int) node, size); + +} + +void csp_uptime(uint8_t node, uint32_t timeout) { + + uint32_t uptime = 0; + + int status = csp_transaction(CSP_PRIO_NORM, node, CSP_UPTIME, timeout, NULL, 0, &uptime, sizeof(uptime)); + if (status == 0) { + printf("Network error\r\n"); + return; + } + uptime = csp_ntoh32(uptime); + printf("Uptime of node %u is %"PRIu32" s\r\n", (unsigned int) node, uptime); + +} + +int csp_cmp(uint8_t node, uint32_t timeout, uint8_t code, int membsize, struct csp_cmp_message * msg) { + msg->type = CSP_CMP_REQUEST; + msg->code = code; + int status = csp_transaction(CSP_PRIO_NORM, node, CSP_CMP, timeout, msg, membsize, msg, membsize); + if (status == 0) + return CSP_ERR_TIMEDOUT; + + return CSP_ERR_NONE; +} + diff --git a/thirdparty/libcsp/src/csp_sfp.c b/thirdparty/libcsp/src/csp_sfp.c new file mode 100644 index 00000000..96ef36e1 --- /dev/null +++ b/thirdparty/libcsp/src/csp_sfp.c @@ -0,0 +1,170 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include +#include +#include +#include +#include +#include "csp_conn.h" + +typedef struct __attribute__((__packed__)) { + uint32_t offset; + uint32_t totalsize; +} sfp_header_t; + +/** + * SFP Headers: + * The following functions are helper functions that handles the extra SFP + * information that needs to be appended to all data packets. + */ +static sfp_header_t * csp_sfp_header_add(csp_packet_t * packet) { + sfp_header_t * header = (sfp_header_t *) &packet->data[packet->length]; + packet->length += sizeof(sfp_header_t); + memset(header, 0, sizeof(sfp_header_t)); + return header; +} + +static sfp_header_t * csp_sfp_header_remove(csp_packet_t * packet) { + sfp_header_t * header = (sfp_header_t *) &packet->data[packet->length-sizeof(sfp_header_t)]; + packet->length -= sizeof(sfp_header_t); + return header; +} + +int csp_sfp_send_own_memcpy(csp_conn_t * conn, const void * data, int totalsize, int mtu, uint32_t timeout, void * (*memcpyfcn)(void *, const void *, size_t)) { + + int count = 0; + while(count < totalsize) { + + /* Allocate packet */ + csp_packet_t * packet = csp_buffer_get(mtu); + if (packet == NULL) + return -1; + + /* Calculate sending size */ + int size = totalsize - count; + if (size > mtu) + size = mtu; + + /* Print debug */ + csp_debug(CSP_PROTOCOL, "Sending SFP at %x size %u", data + count, size); + + /* Copy data */ + (*memcpyfcn)(packet->data, data + count, size); + packet->length = size; + + /* Set fragment flag */ + conn->idout.flags |= CSP_FFRAG; + + /* Add SFP header */ + sfp_header_t * sfp_header = csp_sfp_header_add(packet); + sfp_header->totalsize = csp_hton32(totalsize); + sfp_header->offset = csp_hton32(count); + + /* Send data */ + if (!csp_send(conn, packet, timeout)) { + csp_buffer_free(packet); + return -1; + } + + /* Increment count */ + count += size; + + } + + return 0; + +} + +int csp_sfp_send(csp_conn_t * conn, const void * data, int totalsize, int mtu, uint32_t timeout) { + return csp_sfp_send_own_memcpy(conn, data, totalsize, mtu, timeout, &memcpy); +} + +int csp_sfp_recv_fp(csp_conn_t * conn, void ** dataout, int * datasize, uint32_t timeout, csp_packet_t * first_packet) { + + unsigned int last_byte = 0; + + *dataout = NULL; /* Allow caller to assume csp_free() can always be called when dataout is non-NULL */ + + /* Get first packet from user, or from connection */ + csp_packet_t * packet = NULL; + if (first_packet == NULL) { + packet = csp_read(conn, timeout); + if (packet == NULL) + return -1; + } else { + packet = first_packet; + } + + do { + + /* Check that SFP header is present */ + if ((packet->id.flags & CSP_FFRAG) == 0) { + csp_debug(CSP_ERROR, "Missing SFP header"); + csp_buffer_free(packet); + return -1; + } + + /* Read SFP header */ + sfp_header_t * sfp_header = csp_sfp_header_remove(packet); + sfp_header->offset = csp_ntoh32(sfp_header->offset); + sfp_header->totalsize = csp_ntoh32(sfp_header->totalsize); + + csp_debug(CSP_PROTOCOL, "SFP fragment %u/%u", sfp_header->offset + packet->length, sfp_header->totalsize); + + if (sfp_header->offset > last_byte + 1) { + csp_debug(CSP_ERROR, "SFP missing %u bytes", sfp_header->offset - last_byte); + csp_buffer_free(packet); + return -1; + } else { + last_byte = sfp_header->offset + packet->length; + } + + /* Allocate memory */ + if (*dataout == NULL) + *dataout = csp_malloc(sfp_header->totalsize); + if (*dataout == NULL) { + csp_debug(CSP_ERROR, "No dyn-memory for SFP fragment"); + csp_buffer_free(packet); + return -1; + } + + /* Copy data to output */ + *datasize = sfp_header->totalsize; + memcpy(*dataout + sfp_header->offset, packet->data, packet->length); + + if (sfp_header->offset + packet->length >= sfp_header->totalsize) { + csp_debug(CSP_PROTOCOL, "SFP complete"); + csp_buffer_free(packet); + return 0; + } else { + csp_buffer_free(packet); + } + + } while((packet = csp_read(conn, timeout)) != NULL); + + return -1; + +} + +int csp_sfp_recv(csp_conn_t * conn, void ** dataout, int * datasize, uint32_t timeout) { + return csp_sfp_recv_fp(conn, dataout, datasize, timeout, NULL); +} + diff --git a/thirdparty/libcsp/src/drivers/CMakeLists.txt b/thirdparty/libcsp/src/drivers/CMakeLists.txt new file mode 100644 index 00000000..e2dd440b --- /dev/null +++ b/thirdparty/libcsp/src/drivers/CMakeLists.txt @@ -0,0 +1 @@ +add_subdirectory(can) diff --git a/thirdparty/libcsp/src/drivers/can/CMakeLists.txt b/thirdparty/libcsp/src/drivers/can/CMakeLists.txt new file mode 100644 index 00000000..d291fccc --- /dev/null +++ b/thirdparty/libcsp/src/drivers/can/CMakeLists.txt @@ -0,0 +1,3 @@ +target_sources(${LIB_CSP_NAME} PRIVATE + can_socketcan.c +) diff --git a/thirdparty/libcsp/src/drivers/can/can_socketcan.c b/thirdparty/libcsp/src/drivers/can/can_socketcan.c new file mode 100644 index 00000000..94c6bdde --- /dev/null +++ b/thirdparty/libcsp/src/drivers/can/can_socketcan.c @@ -0,0 +1,201 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +/* SocketCAN driver */ +#include + +#include +#include + +#include +#include +#include +#include +#include + +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include +#include + +#ifdef CSP_HAVE_LIBSOCKETCAN +#include +#endif + +static struct can_socketcan_s { + int socket; + csp_iface_t interface; +} socketcan[1] = { + { + .interface = { + .name = "CAN", + .nexthop = csp_can_tx, + .mtu = CSP_CAN_MTU, + .driver = &socketcan[0], + }, + }, +}; + +static void * socketcan_rx_thread(void * parameters) +{ + struct can_frame frame; + int nbytes; + + while (1) { + /* Read CAN frame */ + nbytes = read(socketcan[0].socket, &frame, sizeof(frame)); + if (nbytes < 0) { + csp_log_error("read: %s", strerror(errno)); + continue; + } + + if (nbytes != sizeof(frame)) { + csp_log_warn("Read incomplete CAN frame"); + continue; + } + + /* Frame type */ + if (frame.can_id & (CAN_ERR_FLAG | CAN_RTR_FLAG) || !(frame.can_id & CAN_EFF_FLAG)) { + /* Drop error and remote frames */ + csp_log_warn("Discarding ERR/RTR/SFF frame"); + continue; + } + + /* Strip flags */ + frame.can_id &= CAN_EFF_MASK; + + /* Call RX callbacsp_can_rx_frameck */ + csp_can_rx(&socketcan[0].interface, frame.can_id, frame.data, frame.can_dlc, NULL); + } + + /* We should never reach this point */ + pthread_exit(NULL); +} + + +int csp_can_tx_frame(csp_iface_t *interface, uint32_t id, const uint8_t * data, uint8_t dlc) +{ + struct can_frame frame; + int i, tries = 0; + memset(&frame, 0, sizeof(frame)); + if (dlc > 8) + return -1; + + /* Copy identifier */ + frame.can_id = id | CAN_EFF_FLAG; + + /* Copy data to frame */ + for (i = 0; i < dlc; i++) + frame.data[i] = data[i]; + + /* Set DLC */ + frame.can_dlc = dlc; + + /* Send frame */ + while (write(socketcan[0].socket, &frame, sizeof(frame)) != sizeof(frame)) { + if (++tries < 1000 && errno == ENOBUFS) { + /* Wait 10 ms and try again */ + usleep(10000); + } else { + csp_log_error("write: %s", strerror(errno)); + break; + } + } + + return 0; +} + +csp_iface_t * csp_can_socketcan_init(const char * ifc, int bitrate, int promisc) +{ + struct ifreq ifr; + struct sockaddr_can addr; + pthread_t rx_thread; + + printf("-I-: Initiating CAN interface %s\n", ifc); + +#ifdef CSP_HAVE_LIBSOCKETCAN + /* Set interface up */ + if (bitrate > 0) { + can_do_stop(ifc); + can_set_bitrate(ifc, bitrate); + can_set_restart_ms(ifc, 100); + can_do_start(ifc); + } +#endif + + /* Create socket */ + if ((socketcan[0].socket = socket(PF_CAN, SOCK_RAW, CAN_RAW)) < 0) { + csp_log_error("socket: %s", strerror(errno)); + return NULL; + } + + /* Locate interface */ + strncpy(ifr.ifr_name, ifc, IFNAMSIZ - 1); + if (ioctl(socketcan[0].socket, SIOCGIFINDEX, &ifr) < 0) { + csp_log_error("ioctl: %s", strerror(errno)); + return NULL; + } + memset(&addr, 0, sizeof(addr)); + /* Bind the socket to CAN interface */ + addr.can_family = AF_CAN; + addr.can_ifindex = ifr.ifr_ifindex; + if (bind(socketcan[0].socket, (struct sockaddr *)&addr, sizeof(addr)) < 0) { + csp_log_error("bind: %s", strerror(errno)); + return NULL; + } + + /* Set filter mode */ + if (promisc == 0) { + + struct can_filter filter; + filter.can_id = CFP_MAKE_DST(csp_get_address()); + filter.can_mask = CFP_MAKE_DST((1 << CFP_HOST_SIZE) - 1); + + if (setsockopt(socketcan[0].socket, SOL_CAN_RAW, CAN_RAW_FILTER, &filter, sizeof(filter)) < 0) { + csp_log_error("setsockopt: %s", strerror(errno)); + return NULL; + } + + } + + /* Create receive thread */ + if (pthread_create(&rx_thread, NULL, socketcan_rx_thread, NULL) != 0) { + csp_log_error("pthread_create: %s", strerror(errno)); + return NULL; + } + + csp_iflist_add(&socketcan[0].interface); + + return &socketcan[0].interface; +} diff --git a/thirdparty/libcsp/src/drivers/usart/usart_linux.c b/thirdparty/libcsp/src/drivers/usart/usart_linux.c new file mode 100644 index 00000000..c4ceeb27 --- /dev/null +++ b/thirdparty/libcsp/src/drivers/usart/usart_linux.c @@ -0,0 +1,254 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +int fd; +usart_callback_t usart_callback = NULL; + +static void *serial_rx_thread(void *vptr_args); + +int getbaud(int ifd) { + struct termios termAttr; + int inputSpeed = -1; + speed_t baudRate; + tcgetattr(ifd, &termAttr); + /* Get the input speed. */ + baudRate = cfgetispeed(&termAttr); + switch (baudRate) { + case B0: + inputSpeed = 0; + break; + case B50: + inputSpeed = 50; + break; + case B110: + inputSpeed = 110; + break; + case B134: + inputSpeed = 134; + break; + case B150: + inputSpeed = 150; + break; + case B200: + inputSpeed = 200; + break; + case B300: + inputSpeed = 300; + break; + case B600: + inputSpeed = 600; + break; + case B1200: + inputSpeed = 1200; + break; + case B1800: + inputSpeed = 1800; + break; + case B2400: + inputSpeed = 2400; + break; + case B4800: + inputSpeed = 4800; + break; + case B9600: + inputSpeed = 9600; + break; + case B19200: + inputSpeed = 19200; + break; + case B38400: + inputSpeed = 38400; + break; + case B57600: + inputSpeed = 57600; + break; + case B115200: + inputSpeed = 115200; + break; + case B230400: + inputSpeed = 230400; + break; +#ifndef CSP_MACOSX + case B460800: + inputSpeed = 460800; + break; + case B500000: + inputSpeed = 500000; + break; + case B576000: + inputSpeed = 576000; + break; + case B921600: + inputSpeed = 921600; + break; + case B1000000: + inputSpeed = 1000000; + break; + case B1152000: + inputSpeed = 1152000; + break; + case B1500000: + inputSpeed = 1500000; + break; + case B2000000: + inputSpeed = 2000000; + break; + case B2500000: + inputSpeed = 2500000; + break; + case B3000000: + inputSpeed = 3000000; + break; + case B3500000: + inputSpeed = 3500000; + break; + case B4000000: + inputSpeed = 4000000; + break; +#endif + } + + return inputSpeed; + +} + +void usart_init(struct usart_conf * conf) { + + struct termios options; + pthread_t rx_thread; + + fd = open(conf->device, O_RDWR | O_NOCTTY | O_NONBLOCK); + + if (fd < 0) { + printf("Failed to open %s: %s\r\n", conf->device, strerror(errno)); + return; + } + + int brate = 0; + switch(conf->baudrate) { + case 4800: brate=B4800; break; + case 9600: brate=B9600; break; + case 19200: brate=B19200; break; + case 38400: brate=B38400; break; + case 57600: brate=B57600; break; + case 115200: brate=B115200; break; + case 230400: brate=B230400; break; +#ifndef CSP_MACOSX + case 460800: brate=B460800; break; + case 500000: brate=B500000; break; + case 576000: brate=B576000; break; + case 921600: brate=B921600; break; + case 1000000: brate=B1000000; break; + case 1152000: brate=B1152000; break; + case 1500000: brate=B1500000; break; + case 2000000: brate=B2000000; break; + case 2500000: brate=B2500000; break; + case 3000000: brate=B3000000; break; + case 3500000: brate=B3500000; break; + case 4000000: brate=B4000000; break; +#endif + default: + printf("Unsupported baudrate requested, defaulting to 500000, requested baudrate=%u\n", conf->baudrate); + brate=B500000; + break; + } + + tcgetattr(fd, &options); + cfsetispeed(&options, brate); + cfsetospeed(&options, brate); + options.c_cflag |= (CLOCAL | CREAD); + options.c_cflag &= ~PARENB; + options.c_cflag &= ~CSTOPB; + options.c_cflag &= ~CSIZE; + options.c_cflag |= CS8; + options.c_lflag &= ~(ECHO | ECHONL | ICANON | IEXTEN | ISIG); + options.c_iflag &= ~(IGNBRK | BRKINT | ICRNL | INLCR | PARMRK | INPCK | ISTRIP | IXON); + options.c_oflag &= ~(OCRNL | ONLCR | ONLRET | ONOCR | OFILL | OPOST); + options.c_cc[VTIME] = 0; + options.c_cc[VMIN] = 1; + tcsetattr(fd, TCSANOW, &options); + if (tcgetattr(fd, &options) == -1) + perror("error setting options"); + fcntl(fd, F_SETFL, 0); + + /* Flush old transmissions */ + if (tcflush(fd, TCIOFLUSH) == -1) + printf("Error flushing serial port - %s(%d).\n", strerror(errno), errno); + + if (pthread_create(&rx_thread, NULL, serial_rx_thread, NULL) != 0) + return; + +} + +void usart_set_callback(usart_callback_t callback) { + usart_callback = callback; +} + +void usart_insert(char c, void * pxTaskWoken) { + printf("%c", c); +} + +void usart_putstr(char * buf, int len) { + if (write(fd, buf, len) != len) + return; +} + +void usart_putc(char c) { + if (write(fd, &c, 1) != 1) + return; +} + +char usart_getc(void) { + char c; + if (read(fd, &c, 1) != 1) return 0; + return c; +} + +static void *serial_rx_thread(void *vptr_args) { + unsigned int length; + uint8_t * cbuf = malloc(100000); + + // Receive loop + while (1) { + length = read(fd, cbuf, 300); + if (length <= 0) { + perror("Error: "); + exit(1); + } + if (usart_callback) + usart_callback(cbuf, length, NULL); + } + return NULL; +} diff --git a/thirdparty/libcsp/src/drivers/usart/usart_windows.c b/thirdparty/libcsp/src/drivers/usart/usart_windows.c new file mode 100644 index 00000000..91ffe87d --- /dev/null +++ b/thirdparty/libcsp/src/drivers/usart/usart_windows.c @@ -0,0 +1,230 @@ +#include +#include +#include + +#include +#include + +static HANDLE portHandle = INVALID_HANDLE_VALUE; +static HANDLE rxThread = INVALID_HANDLE_VALUE; +static CRITICAL_SECTION txSection; +static LONG isListening = 0; +static usart_callback_t usart_callback = NULL; + +static void prvSendData(char *buf, int bufsz); +static int prvTryOpenPort(const char* intf); +static int prvTryConfigurePort(const struct usart_conf*); +static int prvTrySetPortTimeouts(void); +static const char* prvParityToStr(BYTE paritySetting); + +#ifdef CSP_DEBUG +static void prvPrintError(void) { + char *messageBuffer = NULL; + DWORD errorCode = GetLastError(); + DWORD formatMessageRet; + formatMessageRet = FormatMessageA( + FORMAT_MESSAGE_ALLOCATE_BUFFER | + FORMAT_MESSAGE_FROM_SYSTEM, + NULL, + errorCode, + MAKELANGID(LANG_NEUTRAL, SUBLANG_DEFAULT), + (char*)&messageBuffer, + 0, + NULL); + + if( !formatMessageRet ) { + csp_log_error("FormatMessage error, code: %lu", GetLastError()); + return; + } + csp_log_error("%s", messageBuffer); + LocalFree(messageBuffer); +} +#endif + +#ifdef CSP_DEBUG +#define printError() prvPrintError() +#else +#define printError() do {} while(0) +#endif + +static int prvTryOpenPort(const char *intf) { + portHandle = CreateFileA( + intf, + GENERIC_READ|GENERIC_WRITE, + 0, + NULL, + OPEN_EXISTING, + 0, + NULL); + + if( portHandle == INVALID_HANDLE_VALUE ) { + DWORD errorCode = GetLastError(); + if( errorCode == ERROR_FILE_NOT_FOUND ) { + csp_log_error("Could not open serial port, because it didn't exist!"); + } + else + csp_log_error("Failure opening serial port! Code: %lu", errorCode); + return 1; + } + return 0; +} + +static int prvTryConfigurePort(const struct usart_conf * conf) { + DCB portSettings = {0}; + portSettings.DCBlength = sizeof(DCB); + if(!GetCommState(portHandle, &portSettings) ) { + csp_log_error("Could not get default settings for open COM port! Code: %lu", GetLastError()); + return -1; + } + portSettings.BaudRate = conf->baudrate; + portSettings.Parity = conf->paritysetting; + portSettings.StopBits = conf->stopbits; + portSettings.fParity = conf->checkparity; + portSettings.fBinary = TRUE; + portSettings.ByteSize = conf->databits; + if( !SetCommState(portHandle, &portSettings) ) { + csp_log_error("Error when setting COM port settings! Code:%lu", GetLastError()); + return 1; + } + + GetCommState(portHandle, &portSettings); + + csp_log_info("Port: %s, Baudrate: %lu, Data bits: %d, Stop bits: %d, Parity: %s", + conf->device, conf->baudrate, conf->databits, conf->stopbits, prvParityToStr(conf->paritysetting)); + return 0; +} + +static const char* prvParityToStr(BYTE paritySetting) { + static const char *parityStr[] = { + "None", + "Odd", + "Even", + "N/A" + }; + char const *resultStr = NULL; + + switch(paritySetting) { + case NOPARITY: + resultStr = parityStr[0]; + break; + case ODDPARITY: + resultStr = parityStr[1]; + break; + case EVENPARITY: + resultStr = parityStr[2]; + break; + default: + resultStr = parityStr[3]; + }; + return resultStr; +} + +static int prvTrySetPortTimeouts(void) { + COMMTIMEOUTS timeouts = {0}; + + if( !GetCommTimeouts(portHandle, &timeouts) ) { + csp_log_error("Error gettings current timeout settings"); + return 1; + } + + timeouts.ReadIntervalTimeout = 5; + timeouts.ReadTotalTimeoutMultiplier = 1; + timeouts.ReadTotalTimeoutConstant = 5; + timeouts.WriteTotalTimeoutMultiplier = 1; + timeouts.WriteTotalTimeoutConstant = 5; + + if(!SetCommTimeouts(portHandle, &timeouts)) { + csp_log_error("Error setting timeouts!"); + return 1; + } + + return 0; +} + +unsigned WINAPI prvRxTask(void* params) { + DWORD bytesRead; + DWORD eventStatus; + uint8_t recvBuffer[24]; + SetCommMask(portHandle, EV_RXCHAR); + + while(isListening) { + WaitCommEvent(portHandle, &eventStatus, NULL); + if( !(eventStatus & EV_RXCHAR) ) { + continue; + } + if( !ReadFile(portHandle, recvBuffer, 24, &bytesRead, NULL)) { + csp_log_warn("Error receiving data! Code: %lu", GetLastError()); + continue; + } + if( usart_callback != NULL ) + usart_callback(recvBuffer, (size_t)bytesRead, NULL); + } + return 0; +} + +static void prvSendData(char *buf, int bufsz) { + DWORD bytesTotal = 0; + DWORD bytesActual; + if( !WriteFile(portHandle, buf, bufsz-bytesTotal, &bytesActual, NULL) ) { + csp_log_error("Could not write data. Code: %lu", GetLastError()); + return; + } + if( !FlushFileBuffers(portHandle) ) { + csp_log_warn("Could not flush write buffer. Code: %lu", GetLastError()); + } +} + +void usart_shutdown(void) { + InterlockedExchange(&isListening, 0); + CloseHandle(portHandle); + portHandle = INVALID_HANDLE_VALUE; + if( rxThread != INVALID_HANDLE_VALUE ) { + WaitForSingleObject(rxThread, INFINITE); + rxThread = INVALID_HANDLE_VALUE; + } + DeleteCriticalSection(&txSection); +} + +void usart_listen(void) { + InterlockedExchange(&isListening, 1); + rxThread = (HANDLE)_beginthreadex(NULL, 0, &prvRxTask, NULL, 0, NULL); +} + +void usart_putstr(char* buf, int bufsz) { + EnterCriticalSection(&txSection); + prvSendData(buf, bufsz); + LeaveCriticalSection(&txSection); +} + +void usart_insert(char c, void *pxTaskWoken) { + /* redirect debug output to stdout */ + printf("%c", c); +} + +void usart_set_callback(usart_callback_t callback) { + usart_callback = callback; +} + +void usart_init(struct usart_conf * conf) { + if( prvTryOpenPort(conf->device) ) { + printError(); + return; + } + + if( prvTryConfigurePort(conf) ) { + printError(); + return; + } + + if( prvTrySetPortTimeouts() ) { + printError(); + return; + } + + InitializeCriticalSection(&txSection); + + /* Start receiver thread */ + usart_listen(); +} + + diff --git a/thirdparty/libcsp/src/interfaces/CMakeLists.txt b/thirdparty/libcsp/src/interfaces/CMakeLists.txt new file mode 100644 index 00000000..33f779e3 --- /dev/null +++ b/thirdparty/libcsp/src/interfaces/CMakeLists.txt @@ -0,0 +1,7 @@ +target_sources(${LIB_CSP_NAME} PRIVATE + csp_if_can_pbuf.c + csp_if_can.c + csp_if_i2c.c + csp_if_kiss.c + csp_if_lo.c +) diff --git a/thirdparty/libcsp/src/interfaces/csp_if_can.c b/thirdparty/libcsp/src/interfaces/csp_if_can.c new file mode 100644 index 00000000..5add8334 --- /dev/null +++ b/thirdparty/libcsp/src/interfaces/csp_if_can.c @@ -0,0 +1,279 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +/* CAN frames contains at most 8 bytes of data, so in order to transmit CSP + * packets larger than this, a fragmentation protocol is required. The CAN + * Fragmentation Protocol (CFP) header is designed to match the 29 bit CAN + * identifier. + * + * The CAN identifier is divided in these fields: + * src: 5 bits + * dst: 5 bits + * type: 1 bit + * remain: 8 bits + * identifier: 10 bits + * + * Source and Destination addresses must match the CSP packet. The type field + * is used to distinguish the first and subsequent frames in a fragmented CSP + * packet. Type is BEGIN (0) for the first fragment and MORE (1) for all other + * fragments. Remain indicates number of remaining fragments, and must be + * decremented by one for each fragment sent. The identifier field serves the + * same purpose as in the Internet Protocol, and should be an auto incrementing + * integer to uniquely separate sessions. + */ + +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +#include +#include +#include +#include + +#include "csp_if_can_pbuf.h" + +/* CFP Frame Types */ +enum cfp_frame_t { + CFP_BEGIN = 0, + CFP_MORE = 1 +}; + +int csp_can_rx(csp_iface_t *interface, uint32_t id, const uint8_t *data, uint8_t dlc, CSP_BASE_TYPE *task_woken) +{ + csp_can_pbuf_element_t *buf; + uint8_t offset; + + /* Random packet loss */ +#if 0 + int random = rand(); + if (random < RAND_MAX * 0.00005) { + csp_log_warn("Dropping frame"); + return; + } +#endif + + /* Bind incoming frame to a packet buffer */ + buf = csp_can_pbuf_find(id, CFP_ID_CONN_MASK); + + /* Check returned buffer */ + if (buf == NULL) { + if (CFP_TYPE(id) == CFP_BEGIN) { + buf = csp_can_pbuf_new(id, task_woken); + if (buf == NULL) { + //csp_log_warn("No available packet buffer for CAN"); + interface->rx_error++; + return CSP_ERR_NOMEM; + } + } else { + //csp_log_warn("Out of order id 0x%X remain %u", CFP_ID(id), CFP_REMAIN(id)); + interface->frame++; + return CSP_ERR_INVAL; + } + } + + /* Reset frame data offset */ + offset = 0; + + switch (CFP_TYPE(id)) { + + case CFP_BEGIN: + + /* Discard packet if DLC is less than CSP id + CSP length fields */ + if (dlc < sizeof(csp_id_t) + sizeof(uint16_t)) { + //csp_log_warn("Short BEGIN frame received"); + interface->frame++; + csp_can_pbuf_free(buf, task_woken); + break; + } + + /* Check for incomplete frame */ + if (buf->packet != NULL) { + /* Reuse the buffer */ + //csp_log_warn("Incomplete frame"); + interface->frame++; + } else { + /* Allocate memory for frame */ + if (task_woken == NULL) { + buf->packet = csp_buffer_get(interface->mtu); + } else { + buf->packet = csp_buffer_get_isr(interface->mtu); + } + if (buf->packet == NULL) { + //csp_log_error("Failed to get buffer for CSP_BEGIN packet"); + interface->frame++; + csp_can_pbuf_free(buf, task_woken); + break; + } + } + + /* Copy CSP identifier and length*/ + memcpy(&(buf->packet->id), data, sizeof(csp_id_t)); + buf->packet->id.ext = csp_ntoh32(buf->packet->id.ext); + memcpy(&(buf->packet->length), data + sizeof(csp_id_t), sizeof(uint16_t)); + buf->packet->length = csp_ntoh16(buf->packet->length); + + /* Reset RX count */ + buf->rx_count = 0; + + /* Set offset to prevent CSP header from being copied to CSP data */ + offset = sizeof(csp_id_t) + sizeof(uint16_t); + + /* Set remain field - increment to include begin packet */ + buf->remain = CFP_REMAIN(id) + 1; + + /* FALLTHROUGH */ + + case CFP_MORE: + + /* Check 'remain' field match */ + if (CFP_REMAIN(id) != buf->remain - 1) { + //csp_log_error("CAN frame lost in CSP packet"); + csp_can_pbuf_free(buf, task_woken); + interface->frame++; + break; + } + + /* Decrement remaining frames */ + buf->remain--; + + /* Check for overflow */ + if ((buf->rx_count + dlc - offset) > buf->packet->length) { + //csp_log_error("RX buffer overflow"); + interface->frame++; + csp_can_pbuf_free(buf, task_woken); + break; + } + + /* Copy dlc bytes into buffer */ + memcpy(&buf->packet->data[buf->rx_count], data + offset, dlc - offset); + buf->rx_count += dlc - offset; + + /* Check if more data is expected */ + if (buf->rx_count != buf->packet->length) + break; + + /* Data is available */ + csp_qfifo_write(buf->packet, interface, task_woken); + + /* Drop packet buffer reference */ + buf->packet = NULL; + + /* Free packet buffer */ + csp_can_pbuf_free(buf, task_woken); + + break; + + default: + //csp_log_warn("Received unknown CFP message type"); + csp_can_pbuf_free(buf, task_woken); + break; + + } + + return CSP_ERR_NONE; +} + +int csp_can_tx(csp_iface_t *interface, csp_packet_t *packet, uint32_t timeout) +{ + + /* CFP Identification number */ + static volatile int csp_can_frame_id = 0; + + /* Get local copy of the static frameid */ + int ident = csp_can_frame_id++; + + uint16_t tx_count; + uint8_t bytes, overhead, avail, dest; + uint8_t frame_buf[8]; + + /* Calculate overhead */ + overhead = sizeof(csp_id_t) + sizeof(uint16_t); + + /* Insert destination node mac address into the CFP destination field */ + dest = csp_rtable_find_mac(packet->id.dst); + if (dest == CSP_NODE_MAC) + dest = packet->id.dst; + + /* Create CAN identifier */ + uint32_t id = 0; + id |= CFP_MAKE_SRC(packet->id.src); + id |= CFP_MAKE_DST(dest); + id |= CFP_MAKE_ID(ident); + id |= CFP_MAKE_TYPE(CFP_BEGIN); + id |= CFP_MAKE_REMAIN((packet->length + overhead - 1) / 8); + + /* Calculate first frame data bytes */ + avail = 8 - overhead; + bytes = (packet->length <= avail) ? packet->length : avail; + + /* Copy CSP headers and data */ + uint32_t csp_id_be = csp_hton32(packet->id.ext); + uint16_t csp_length_be = csp_hton16(packet->length); + + memcpy(frame_buf, &csp_id_be, sizeof(csp_id_be)); + memcpy(frame_buf + sizeof(csp_id_be), &csp_length_be, sizeof(csp_length_be)); + memcpy(frame_buf + overhead, packet->data, bytes); + + /* Increment tx counter */ + tx_count = bytes; + + /* Send first frame */ + if (csp_can_tx_frame(interface, id, frame_buf, overhead + bytes)) { + //csp_log_warn("Failed to send CAN frame in csp_tx_can"); + interface->tx_error++; + return CSP_ERR_DRIVER; + } + + /* Send next frames if not complete */ + while (tx_count < packet->length) { + /* Calculate frame data bytes */ + bytes = (packet->length - tx_count >= 8) ? 8 : packet->length - tx_count; + + /* Prepare identifier */ + id = 0; + id |= CFP_MAKE_SRC(packet->id.src); + id |= CFP_MAKE_DST(dest); + id |= CFP_MAKE_ID(ident); + id |= CFP_MAKE_TYPE(CFP_MORE); + id |= CFP_MAKE_REMAIN((packet->length - tx_count - bytes + 7) / 8); + + /* Increment tx counter */ + tx_count += bytes; + + /* Send frame */ + if (csp_can_tx_frame(interface, id, packet->data + tx_count - bytes, bytes)) { + //csp_log_warn("Failed to send CAN frame in Tx callback"); + interface->tx_error++; + return CSP_ERR_DRIVER; + } + } + + csp_buffer_free(packet); + + return CSP_ERR_NONE; +} diff --git a/thirdparty/libcsp/src/interfaces/csp_if_can_pbuf.c b/thirdparty/libcsp/src/interfaces/csp_if_can_pbuf.c new file mode 100644 index 00000000..65f18de9 --- /dev/null +++ b/thirdparty/libcsp/src/interfaces/csp_if_can_pbuf.c @@ -0,0 +1,77 @@ +/* + * csp_if_can_pbuf.c + * + * Created on: Feb 3, 2017 + * Author: johan + */ + +#include +#include "csp_if_can_pbuf.h" + +/* Number of packet buffer elements */ +#define PBUF_ELEMENTS CSP_CONN_MAX + +/* Buffer element timeout in ms */ +#define PBUF_TIMEOUT_MS 1000 + +static csp_can_pbuf_element_t csp_can_pbuf[PBUF_ELEMENTS] = {}; + +int csp_can_pbuf_free(csp_can_pbuf_element_t *buf, CSP_BASE_TYPE *task_woken) +{ + /* Free CSP packet */ + if (buf->packet != NULL) { + if (task_woken == NULL) { + csp_buffer_free(buf->packet); + } else { + csp_buffer_free_isr(buf->packet); + } + } + + /* Mark buffer element free */ + buf->packet = NULL; + buf->rx_count = 0; + buf->cfpid = 0; + buf->last_used = 0; + buf->remain = 0; + buf->state = BUF_FREE; + + return CSP_ERR_NONE; +} + +csp_can_pbuf_element_t *csp_can_pbuf_new(uint32_t id, CSP_BASE_TYPE *task_woken) +{ + uint32_t now = csp_get_ms(); + + for (int i = 0; i < PBUF_ELEMENTS; i++) { + + /* Perform cleanup in used pbufs */ + if (csp_can_pbuf[i].state == BUF_USED) { + if (now - csp_can_pbuf[i].last_used > PBUF_TIMEOUT_MS) + csp_can_pbuf_free(&csp_can_pbuf[i], task_woken); + } + + if (csp_can_pbuf[i].state == BUF_FREE) { + csp_can_pbuf[i].state = BUF_USED; + csp_can_pbuf[i].cfpid = id; + csp_can_pbuf[i].remain = 0; + csp_can_pbuf[i].last_used = now; + return &csp_can_pbuf[i]; + } + + } + + return NULL; + +} + +csp_can_pbuf_element_t *csp_can_pbuf_find(uint32_t id, uint32_t mask) +{ + for (int i = 0; i < PBUF_ELEMENTS; i++) { + if ((csp_can_pbuf[i].state == BUF_USED) && ((csp_can_pbuf[i].cfpid & mask) == (id & mask))) { + csp_can_pbuf[i].last_used = csp_get_ms(); + return &csp_can_pbuf[i]; + } + } + return NULL; +} + diff --git a/thirdparty/libcsp/src/interfaces/csp_if_can_pbuf.h b/thirdparty/libcsp/src/interfaces/csp_if_can_pbuf.h new file mode 100644 index 00000000..3e71c26c --- /dev/null +++ b/thirdparty/libcsp/src/interfaces/csp_if_can_pbuf.h @@ -0,0 +1,31 @@ +/* + * csp_if_can_pbuf.h + * + * Created on: Feb 3, 2017 + * Author: johan + */ + +#ifndef LIB_CSP_SRC_INTERFACES_CSP_IF_CAN_PBUF_H_ +#define LIB_CSP_SRC_INTERFACES_CSP_IF_CAN_PBUF_H_ + +/* Packet buffers */ +typedef enum { + BUF_FREE = 0, /* Buffer element free */ + BUF_USED = 1, /* Buffer element used */ +} csp_can_pbuf_state_t; + +typedef struct { + uint16_t rx_count; /* Received bytes */ + uint32_t remain; /* Remaining packets */ + uint32_t cfpid; /* Connection CFP identification number */ + csp_packet_t *packet; /* Pointer to packet buffer */ + csp_can_pbuf_state_t state; /* Element state */ + uint32_t last_used; /* Timestamp in ms for last use of buffer */ +} csp_can_pbuf_element_t; + +int csp_can_pbuf_free(csp_can_pbuf_element_t *buf, CSP_BASE_TYPE *task_woken); +csp_can_pbuf_element_t *csp_can_pbuf_new(uint32_t id, CSP_BASE_TYPE *task_woken); +csp_can_pbuf_element_t *csp_can_pbuf_find(uint32_t id, uint32_t mask); +void csp_can_pbuf_cleanup(CSP_BASE_TYPE *task_woken); + +#endif /* LIB_CSP_SRC_INTERFACES_CSP_IF_CAN_PBUF_H_ */ diff --git a/thirdparty/libcsp/src/interfaces/csp_if_i2c.c b/thirdparty/libcsp/src/interfaces/csp_if_i2c.c new file mode 100644 index 00000000..c5d105df --- /dev/null +++ b/thirdparty/libcsp/src/interfaces/csp_if_i2c.c @@ -0,0 +1,116 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include +#include + +#include +#include +#include +#include +#include +#include + +static int csp_i2c_handle = 0; + +int csp_i2c_tx(csp_iface_t * interface, csp_packet_t * packet, uint32_t timeout) { + + /* Cast the CSP packet buffer into an i2c frame */ + i2c_frame_t * frame = (i2c_frame_t *) packet; + + /* Insert destination node into the i2c destination field */ + if (csp_rtable_find_mac(packet->id.dst) == CSP_NODE_MAC) { + frame->dest = packet->id.dst; + } else { + frame->dest = csp_rtable_find_mac(packet->id.dst); + } + + /* Save the outgoing id in the buffer */ + packet->id.ext = csp_hton32(packet->id.ext); + + /* Add the CSP header to the I2C length field */ + frame->len += sizeof(packet->id); + frame->len_rx = 0; + + /* Some I2C drivers support X number of retries + * CSP don't care about this. If it doesn't work the first + * time, don'y use time on it. + */ + frame->retries = 0; + + /* enqueue the frame */ + if (i2c_send(csp_i2c_handle, frame, timeout) != E_NO_ERR) + return CSP_ERR_DRIVER; + + return CSP_ERR_NONE; + +} + +/** + * When a frame is received, cast it to a csp_packet + * and send it directly to the CSP new packet function. + * Context: ISR only + * @param frame + */ +void csp_i2c_rx(i2c_frame_t * frame, void * pxTaskWoken) { + + static csp_packet_t * packet; + + /* Validate input */ + if (frame == NULL) + return; + + if ((frame->len < 4) || (frame->len > I2C_MTU)) { + csp_if_i2c.frame++; + csp_buffer_free_isr(frame); + return; + } + + /* Strip the CSP header off the length field before converting to CSP packet */ + frame->len -= sizeof(csp_id_t); + + /* Convert the packet from network to host order */ + packet = (csp_packet_t *) frame; + packet->id.ext = csp_ntoh32(packet->id.ext); + + /* Receive the packet in CSP */ + csp_qfifo_write(packet, &csp_if_i2c, pxTaskWoken); + +} + +int csp_i2c_init(uint8_t addr, int handle, int speed) { + + /* Create i2c_handle */ + csp_i2c_handle = handle; + if (i2c_init(csp_i2c_handle, I2C_MASTER, addr, speed, 10, 10, csp_i2c_rx) != E_NO_ERR) + return CSP_ERR_DRIVER; + + /* Register interface */ + csp_iflist_add(&csp_if_i2c); + + return CSP_ERR_NONE; + +} + +/** Interface definition */ +csp_iface_t csp_if_i2c = { + .name = "I2C", + .nexthop = csp_i2c_tx, +}; diff --git a/thirdparty/libcsp/src/interfaces/csp_if_kiss.c b/thirdparty/libcsp/src/interfaces/csp_if_kiss.c new file mode 100644 index 00000000..fe5707f6 --- /dev/null +++ b/thirdparty/libcsp/src/interfaces/csp_if_kiss.c @@ -0,0 +1,260 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include + +#define KISS_MTU 256 + +#define FEND 0xC0 +#define FESC 0xDB +#define TFEND 0xDC +#define TFESC 0xDD + +#define TNC_DATA 0x00 +#define TNC_SET_HARDWARE 0x06 +#define TNC_RETURN 0xFF + +static int kiss_lock_init = 0; +static csp_bin_sem_handle_t kiss_lock; + +/* Send a CSP packet over the KISS RS232 protocol */ +static int csp_kiss_tx(csp_iface_t * interface, csp_packet_t * packet, uint32_t timeout) { + + if (interface == NULL || interface->driver == NULL) + return CSP_ERR_DRIVER; + + /* Add CRC32 checksum */ + csp_crc32_append(packet, false); + + /* Save the outgoing id in the buffer */ + packet->id.ext = csp_hton32(packet->id.ext); + packet->length += sizeof(packet->id.ext); + + /* Lock */ + csp_bin_sem_wait(&kiss_lock, 1000); + + /* Transmit data */ + csp_kiss_handle_t * driver = interface->driver; + driver->kiss_putc(FEND); + driver->kiss_putc(TNC_DATA); + for (unsigned int i = 0; i < packet->length; i++) { + if (((unsigned char *) &packet->id.ext)[i] == FEND) { + ((unsigned char *) &packet->id.ext)[i] = TFEND; + driver->kiss_putc(FESC); + } else if (((unsigned char *) &packet->id.ext)[i] == FESC) { + ((unsigned char *) &packet->id.ext)[i] = TFESC; + driver->kiss_putc(FESC); + } + driver->kiss_putc(((unsigned char *) &packet->id.ext)[i]); + } + driver->kiss_putc(FEND); + + /* Free data */ + csp_buffer_free(packet); + + /* Unlock */ + csp_bin_sem_post(&kiss_lock); + + return CSP_ERR_NONE; +} + +/** + * When a frame is received, decode the kiss-stuff + * and eventually send it directly to the CSP new packet function. + */ +void csp_kiss_rx(csp_iface_t * interface, uint8_t * buf, int len, void * pxTaskWoken) { + + /* Driver handle */ + csp_kiss_handle_t * driver = interface->driver; + + while (len--) { + + /* Input */ + unsigned char inputbyte = *buf++; + + /* If packet was too long */ + if (driver->rx_length > interface->mtu) { + //csp_log_warn("KISS RX overflow"); + interface->rx_error++; + driver->rx_mode = KISS_MODE_NOT_STARTED; + driver->rx_length = 0; + } + + switch (driver->rx_mode) { + + case KISS_MODE_NOT_STARTED: + + /* Send normal chars back to usart driver */ + if (inputbyte != FEND) { + if (driver->kiss_discard != NULL) + driver->kiss_discard(inputbyte, pxTaskWoken); + break; + } + + /* Try to allocate new buffer */ + if (driver->rx_packet == NULL) { + if (pxTaskWoken == NULL) { + driver->rx_packet = csp_buffer_get(interface->mtu); + } else { + driver->rx_packet = csp_buffer_get_isr(interface->mtu); + } + } + + /* If no more memory, skip frame */ + if (driver->rx_packet == NULL) { + driver->rx_mode = KISS_MODE_SKIP_FRAME; + break; + } + + /* Start transfer */ + driver->rx_length = 0; + driver->rx_mode = KISS_MODE_STARTED; + driver->rx_first = 1; + break; + + case KISS_MODE_STARTED: + + /* Escape char */ + if (inputbyte == FESC) { + driver->rx_mode = KISS_MODE_ESCAPED; + break; + } + + /* End Char */ + if (inputbyte == FEND) { + + /* Accept message */ + if (driver->rx_length > 0) { + + /* Check for valid length */ + if (driver->rx_length < CSP_HEADER_LENGTH + sizeof(uint32_t)) { + //csp_log_warn("KISS short frame skipped, len: %u", driver->rx_length); + interface->rx_error++; + driver->rx_mode = KISS_MODE_NOT_STARTED; + break; + } + + /* Count received frame */ + interface->frame++; + + /* The CSP packet length is without the header */ + driver->rx_packet->length = driver->rx_length - CSP_HEADER_LENGTH; + + /* Convert the packet from network to host order */ + driver->rx_packet->id.ext = csp_ntoh32(driver->rx_packet->id.ext); + + /* Validate CRC */ + if (csp_crc32_verify(driver->rx_packet, false) != CSP_ERR_NONE) { + //csp_log_warn("KISS invalid crc frame skipped, len: %u", driver->rx_packet->length); + interface->rx_error++; + driver->rx_mode = KISS_MODE_NOT_STARTED; + break; + } + + /* Send back into CSP, notice calling from task so last argument must be NULL! */ + csp_qfifo_write(driver->rx_packet, interface, pxTaskWoken); + driver->rx_packet = NULL; + driver->rx_mode = KISS_MODE_NOT_STARTED; + break; + + } + + /* Break after the end char */ + break; + } + + /* Skip the first char after FEND which is TNC_DATA (0x00) */ + if (driver->rx_first) { + driver->rx_first = 0; + break; + } + + /* Valid data char */ + ((char *) &driver->rx_packet->id.ext)[driver->rx_length++] = inputbyte; + + break; + + case KISS_MODE_ESCAPED: + + /* Escaped escape char */ + if (inputbyte == TFESC) + ((char *) &driver->rx_packet->id.ext)[driver->rx_length++] = FESC; + + /* Escaped fend char */ + if (inputbyte == TFEND) + ((char *) &driver->rx_packet->id.ext)[driver->rx_length++] = FEND; + + /* Go back to started mode */ + driver->rx_mode = KISS_MODE_STARTED; + break; + + case KISS_MODE_SKIP_FRAME: + + /* Just wait for end char */ + if (inputbyte == FEND) + driver->rx_mode = KISS_MODE_NOT_STARTED; + + break; + + } + + } + +} + +void csp_kiss_init(csp_iface_t * csp_iface, csp_kiss_handle_t * csp_kiss_handle, csp_kiss_putc_f kiss_putc_f, csp_kiss_discard_f kiss_discard_f, const char * name) { + + /* Init lock only once */ + if (kiss_lock_init == 0) { + csp_bin_sem_create(&kiss_lock); + kiss_lock_init = 1; + } + + /* Register device handle as member of interface */ + csp_iface->driver = csp_kiss_handle; + csp_kiss_handle->kiss_discard = kiss_discard_f; + csp_kiss_handle->kiss_putc = kiss_putc_f; + csp_kiss_handle->rx_packet = NULL; + csp_kiss_handle->rx_mode = KISS_MODE_NOT_STARTED; + + /* Set default MTU if not given */ + if (csp_iface->mtu == 0) { + csp_iface->mtu = KISS_MTU; + } + + /* Setup other mandatories */ + csp_iface->nexthop = csp_kiss_tx; + csp_iface->name = name; + + /* Regsiter interface */ + csp_iflist_add(csp_iface); + +} diff --git a/thirdparty/libcsp/src/interfaces/csp_if_lo.c b/thirdparty/libcsp/src/interfaces/csp_if_lo.c new file mode 100644 index 00000000..f3e81b15 --- /dev/null +++ b/thirdparty/libcsp/src/interfaces/csp_if_lo.c @@ -0,0 +1,61 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +/* CSP includes */ +#include +#include +#include +#include + +#include +#include + +#include "../csp_route.h" + +/** + * Loopback interface transmit function + * @param packet Packet to transmit + * @param timeout Timout in ms + * @return 1 if packet was successfully transmitted, 0 on error + */ +static int csp_lo_tx(csp_iface_t * interface, csp_packet_t * packet, uint32_t timeout) { + + /* Drop packet silently if not destined for us. This allows + * blackhole routing addresses by setting their nexthop to + * the loopback interface. + */ + if (packet->id.dst != csp_get_address()) { + /* Consume and drop packet */ + csp_buffer_free(packet); + return CSP_ERR_NONE; + } + + /* Send back into CSP, notice calling from task so last argument must be NULL! */ + csp_qfifo_write(packet, &csp_if_lo, NULL); + + return CSP_ERR_NONE; + +} + +/* Interface definition */ +csp_iface_t csp_if_lo = { + .name = "LOOP", + .nexthop = csp_lo_tx, +}; diff --git a/thirdparty/libcsp/src/rtable/CMakeLists.txt b/thirdparty/libcsp/src/rtable/CMakeLists.txt new file mode 100644 index 00000000..101f4fb9 --- /dev/null +++ b/thirdparty/libcsp/src/rtable/CMakeLists.txt @@ -0,0 +1,3 @@ +target_sources(${LIB_CSP_NAME} PRIVATE + csp_rtable_cidr.c +) diff --git a/thirdparty/libcsp/src/rtable/csp_rtable_cidr.c b/thirdparty/libcsp/src/rtable/csp_rtable_cidr.c new file mode 100644 index 00000000..5758dc3c --- /dev/null +++ b/thirdparty/libcsp/src/rtable/csp_rtable_cidr.c @@ -0,0 +1,233 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include +#include +#include +#include +#include +#include + +/* Local typedef for routing table */ +typedef struct __attribute__((__packed__)) csp_rtable_s { + uint8_t address; + uint8_t netmask; + uint8_t mac; + csp_iface_t * interface; + struct csp_rtable_s * next; +} csp_rtable_t; + +/* Routing entries are stored in a linked list*/ +static csp_rtable_t * rtable = NULL; + +static csp_rtable_t * csp_rtable_find(uint8_t addr, uint8_t netmask, uint8_t exact) { + + /* Remember best result */ + csp_rtable_t * best_result = NULL; + uint8_t best_result_mask = 0; + + /* Start search */ + csp_rtable_t * i = rtable; + while(i) { + + /* Look for exact match */ + if (i->address == addr && i->netmask == netmask) { + best_result = i; + break; + } + + /* Try a CIDR netmask match */ + if (!exact) { + uint8_t hostbits = (1 << (CSP_ID_HOST_SIZE - i->netmask)) - 1; + uint8_t netbits = ~hostbits; + //printf("Netbits %x Hostbits %x\r\n", netbits, hostbits); + + /* Match network addresses */ + uint8_t net_a = i->address & netbits; + uint8_t net_b = addr & netbits; + //printf("A: %hhx, B: %hhx\r\n", net_a, net_b); + + /* We have a match */ + if (net_a == net_b) { + if (i->netmask >= best_result_mask) { + //printf("Match best result %u %u\r\n", best_result_mask, i->netmask); + best_result = i; + best_result_mask = i->netmask; + } + } + + } + + i = i->next; + + } + +#if 0 + if (best_result) + csp_debug(CSP_PACKET, "Using routing entry: %u/%u dev %s m:%u\r\n", best_result->address, best_result->netmask, best_result->interface->name, best_result->mac); +#endif + + return best_result; + +} + +void csp_rtable_clear(void) { + for (csp_rtable_t * i = rtable; (i);) { + void * freeme = i; + i = i->next; + csp_free(freeme); + } + rtable = NULL; + + /* Set loopback up again */ + csp_rtable_set(csp_get_address(), CSP_ID_HOST_SIZE, &csp_if_lo, CSP_NODE_MAC); + +} + +static int csp_rtable_parse(const char * buffer, int dry_run) { + + int valid_entries = 0; + + /* Copy string before running strtok */ + char * str = alloca(strlen(buffer) + 1); + memcpy(str, buffer, strlen(buffer) + 1); + + /* Get first token */ + str = strtok(str, ","); + + while ((str) && (strlen(str) > 1)) { + int address = 0, netmask = 0, mac = 255; + char name[10] = {}; + if (sscanf(str, "%u/%u %s %u", &address, &netmask, name, &mac) != 4) { + if (sscanf(str, "%u/%u %s", &address, &netmask, name) != 3) { + csp_log_error("Parse error %s", str); + return -1; + } + } + //printf("Parsed %u/%u %u %s\r\n", address, netmask, mac, name); + csp_iface_t * ifc = csp_iflist_get_by_name(name); + if (ifc) { + if (dry_run == 0) + csp_rtable_set(address, netmask, ifc, mac); + } else { + csp_log_error("Unknown interface %s", name); + return -1; + } + valid_entries++; + str = strtok(NULL, ","); + } + + return valid_entries; +} + +void csp_rtable_load(const char * buffer) { + csp_rtable_parse(buffer, 0); +} + +int csp_rtable_check(const char * buffer) { + return csp_rtable_parse(buffer, 1); +} + +int csp_rtable_save(char * buffer, int maxlen) { + int len = 0; + for (csp_rtable_t * i = rtable; (i); i = i->next) { + if (i->mac != CSP_NODE_MAC) { + len += snprintf(buffer + len, maxlen - len, "%u/%u %s %u, ", i->address, i->netmask, i->interface->name, i->mac); + } else { + len += snprintf(buffer + len, maxlen - len, "%u/%u %s, ", i->address, i->netmask, i->interface->name); + } + } + return len; +} + +csp_iface_t * csp_rtable_find_iface(uint8_t id) { + csp_rtable_t * entry = csp_rtable_find(id, CSP_ID_HOST_SIZE, 0); + if (entry == NULL) + return NULL; + return entry->interface; +} + +uint8_t csp_rtable_find_mac(uint8_t id) { + csp_rtable_t * entry = csp_rtable_find(id, CSP_ID_HOST_SIZE, 0); + if (entry == NULL) + return 255; + return entry->mac; +} + +int csp_rtable_set(uint8_t _address, uint8_t _netmask, csp_iface_t *ifc, uint8_t mac) { + + if (ifc == NULL) + return CSP_ERR_INVAL; + + /* Set default route in the old way */ + int address, netmask; + if (_address == CSP_DEFAULT_ROUTE) { + netmask = 0; + address = 0; + } else { + netmask = _netmask; + address = _address; + } + + /* Fist see if the entry exists */ + csp_rtable_t * entry = csp_rtable_find(address, netmask, 1); + + /* If not, create a new one */ + if (!entry) { + entry = csp_malloc(sizeof(csp_rtable_t)); + if (entry == NULL) + return CSP_ERR_NOMEM; + + entry->next = NULL; + /* Add entry to linked-list */ + if (rtable == NULL) { + /* This is the first interface to be added */ + rtable = entry; + } else { + /* One or more interfaces were already added */ + csp_rtable_t * i = rtable; + while (i->next) + i = i->next; + i->next = entry; + } + } + + /* Fill in the data */ + entry->address = address; + entry->netmask = netmask; + entry->interface = ifc; + entry->mac = mac; + + return CSP_ERR_NONE; +} + +#ifdef CSP_DEBUG +void csp_rtable_print(void) { + + for (csp_rtable_t * i = rtable; (i); i = i->next) { + if (i->mac == 255) { + printf("%u/%u %s\r\n", i->address, i->netmask, i->interface->name); + } else { + printf("%u/%u %s %u\r\n", i->address, i->netmask, i->interface->name, i->mac); + } + } + +} +#endif diff --git a/thirdparty/libcsp/src/rtable/csp_rtable_static.c b/thirdparty/libcsp/src/rtable/csp_rtable_static.c new file mode 100644 index 00000000..ea993027 --- /dev/null +++ b/thirdparty/libcsp/src/rtable/csp_rtable_static.c @@ -0,0 +1,128 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include +#include +#include + +/* Local typedef for routing table */ +typedef struct __attribute__((__packed__)) csp_rtable_s { + csp_iface_t * interface; + uint8_t mac; +} csp_rtable_t; + +/* Static storage context for routing table */ +static csp_rtable_t routes[CSP_ROUTE_COUNT] = {}; + +/** + * Find entry in static routing table + * This is done by table lookup with fallback to the default route + * The reason why the csp_rtable_t struct is not returned directly + * is that we wish to hide the storage format, mainly because of + * the alternative routing table storage (cidr). + * @param id Node + * @return pointer to found routing entry + */ +static csp_rtable_t * csp_rtable_find(uint8_t id) { + + if (routes[id].interface != NULL) { + return &routes[id]; + } else if (routes[CSP_DEFAULT_ROUTE].interface != NULL) { + return &routes[CSP_DEFAULT_ROUTE]; + } + return NULL; + +} + +csp_iface_t * csp_rtable_find_iface(uint8_t id) { + csp_rtable_t * route = csp_rtable_find(id); + if (route == NULL) + return NULL; + return route->interface; +} + +uint8_t csp_rtable_find_mac(uint8_t id) { + csp_rtable_t * route = csp_rtable_find(id); + if (route == NULL) + return 255; + return route->mac; +} + +void csp_rtable_clear(void) { + memset(routes, 0, sizeof(routes[0]) * CSP_ROUTE_COUNT); +} + +void csp_route_table_load(uint8_t route_table_in[CSP_ROUTE_TABLE_SIZE]) { + memcpy(routes, route_table_in, sizeof(routes[0]) * CSP_ROUTE_COUNT); +} + +void csp_route_table_save(uint8_t route_table_out[CSP_ROUTE_TABLE_SIZE]) { + memcpy(route_table_out, routes, sizeof(routes[0]) * CSP_ROUTE_COUNT); +} + +int csp_rtable_set(uint8_t node, uint8_t mask, csp_iface_t *ifc, uint8_t mac) { + + /* Don't add nothing */ + if (ifc == NULL) + return CSP_ERR_INVAL; + + /** + * Check if the interface has been added. + * + * NOTE: For future implementations, interfaces should call + * csp_route_add_if in its csp_if__init function, instead + * of registering at first route_set, in order to make the interface + * available to network based (CMP) route configuration. + */ + csp_iflist_add(ifc); + + /* Set route */ + if (node <= CSP_DEFAULT_ROUTE) { + routes[node].interface = ifc; + routes[node].mac = mac; + } else { + csp_log_error("Failed to set route: invalid node id %u", node); + return CSP_ERR_INVAL; + } + + return CSP_ERR_NONE; + +} + +void csp_rtable_load(const char * buffer) { +} + +int csp_rtable_check(const char * buffer) { + return -1; +} + +#ifdef CSP_DEBUG +void csp_rtable_print(void) { + int i; + printf("Node Interface Address\r\n"); + for (i = 0; i < CSP_DEFAULT_ROUTE; i++) + if (routes[i].interface != NULL) + printf("%4u %-9s %u\r\n", i, + routes[i].interface->name, + routes[i].mac == CSP_NODE_MAC ? i : routes[i].mac); + printf(" * %-9s %u\r\n", routes[CSP_DEFAULT_ROUTE].interface->name, routes[CSP_DEFAULT_ROUTE].mac); + +} +#endif diff --git a/thirdparty/libcsp/src/transport/CMakeLists.txt b/thirdparty/libcsp/src/transport/CMakeLists.txt new file mode 100644 index 00000000..c509b755 --- /dev/null +++ b/thirdparty/libcsp/src/transport/CMakeLists.txt @@ -0,0 +1,4 @@ +target_sources(${LIB_CSP_NAME} PRIVATE + csp_rdp.c + csp_udp.c +) diff --git a/thirdparty/libcsp/src/transport/csp_rdp.c b/thirdparty/libcsp/src/transport/csp_rdp.c new file mode 100644 index 00000000..e19968e2 --- /dev/null +++ b/thirdparty/libcsp/src/transport/csp_rdp.c @@ -0,0 +1,1102 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +/* + * This is a implementation of the seq/ack handling taken from the Reliable Datagram Protocol (RDP) + * For more information read RFC 908/1151. The implementation has been extended to include support for + * delayed acknowledgments, to improve performance over half-duplex links. + */ + +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include "../csp_port.h" +#include "../csp_conn.h" +#include "../csp_io.h" +#include "csp_transport.h" + +#ifdef CSP_USE_RDP + +#define RDP_SYN 0x01 +#define RDP_ACK 0x02 +#define RDP_EAK 0x04 +#define RDP_RST 0x08 + +static uint32_t csp_rdp_window_size = 4; +static uint32_t csp_rdp_conn_timeout = 10000; +static uint32_t csp_rdp_packet_timeout = 1000; +static uint32_t csp_rdp_delayed_acks = 1; +static uint32_t csp_rdp_ack_timeout = 1000 / 4; +static uint32_t csp_rdp_ack_delay_count = 4 / 2; + +/* Used for queue calls */ +static CSP_BASE_TYPE pdTrue = 1; + +typedef struct __attribute__((__packed__)) { + /* The timestamp is placed in the padding bytes */ + uint8_t padding[CSP_PADDING_BYTES - 2 * sizeof(uint32_t)]; + uint32_t quarantine; // EACK quarantine period + uint32_t timestamp; // Time the message was sent + uint16_t length; // Length field must be just before CSP ID + csp_id_t id; // CSP id must be just before data + uint8_t data[]; // This just points to the rest of the buffer, without a size indication. +} rdp_packet_t; + +typedef struct __attribute__((__packed__)) { + union __attribute__((__packed__)) { + uint8_t flags; + struct __attribute__((__packed__)) { +#if defined(CSP_BIG_ENDIAN) && !defined(CSP_LITTLE_ENDIAN) + unsigned int res : 4; + unsigned int syn : 1; + unsigned int ack : 1; + unsigned int eak : 1; + unsigned int rst : 1; +#elif defined(CSP_LITTLE_ENDIAN) && !defined(CSP_BIG_ENDIAN) + unsigned int rst : 1; + unsigned int eak : 1; + unsigned int ack : 1; + unsigned int syn : 1; + unsigned int res : 4; +#else + #error "Must define one of CSP_BIG_ENDIAN or CSP_LITTLE_ENDIAN in csp_platform.h" +#endif + }; + }; + uint16_t seq_nr; + uint16_t ack_nr; +} rdp_header_t; + +/** + * RDP Headers: + * The following functions are helper functions that handles the extra RDP + * information that needs to be appended to all data packets. + */ +static rdp_header_t * csp_rdp_header_add(csp_packet_t * packet) { + rdp_header_t * header = (rdp_header_t *) &packet->data[packet->length]; + packet->length += sizeof(rdp_header_t); + memset(header, 0, sizeof(rdp_header_t)); + return header; +} + +static rdp_header_t * csp_rdp_header_remove(csp_packet_t * packet) { + rdp_header_t * header = (rdp_header_t *) &packet->data[packet->length-sizeof(rdp_header_t)]; + packet->length -= sizeof(rdp_header_t); + return header; +} + +static rdp_header_t * csp_rdp_header_ref(csp_packet_t * packet) { + rdp_header_t * header = (rdp_header_t *) &packet->data[packet->length-sizeof(rdp_header_t)]; + return header; +} + +/* Functions for comparing wrapping sequence numbers and timestamps */ + +/* Return 1 if seq is between start and end (both inclusive) */ +static inline int csp_rdp_seq_between(uint16_t seq, uint16_t start, uint16_t end) { + return (uint16_t)(end - start) >= (uint16_t)(seq - start); +} + +/* Return 1 if seq is before cmp */ +static inline int csp_rdp_seq_before(uint16_t seq, uint16_t cmp) { + return (int16_t)(seq - cmp) < 0; +} + +/* Return 1 if seq is after cmp */ +static inline int csp_rdp_seq_after(uint16_t seq, uint16_t cmp) { + return csp_rdp_seq_before(cmp, seq); +} + +/* Return 1 if time is between start and end (both inclusive) */ +static inline int csp_rdp_time_between(uint32_t time, uint32_t start, uint32_t end) { + return (uint32_t)(end - start) >= (uint32_t)(time - start); +} + +/* Return 1 if time is before cmp */ +static inline int csp_rdp_time_before(uint32_t time, uint32_t cmp) { + return (int32_t)(time - cmp) < 0; +} + +/* Return 1 if time is after cmp */ +static inline int csp_rdp_time_after(uint32_t time, uint32_t cmp) { + return csp_rdp_time_before(cmp, time); +} + +/** + * CONTROL MESSAGES + * The following function is used to send empty messages, + * with ACK, SYN or RST flag. + */ +static int csp_rdp_send_cmp(csp_conn_t * conn, csp_packet_t * packet, int flags, int seq_nr, int ack_nr) { + + csp_id_t idout; + + /* Generate message */ + if (!packet) { + packet = csp_buffer_get(20); + if (!packet) + return CSP_ERR_NOMEM; + packet->length = 0; + } + + /* Add RDP header */ + rdp_header_t * header = csp_rdp_header_add(packet); + header->seq_nr = csp_hton16(seq_nr); + header->ack_nr = csp_hton16(ack_nr); + header->ack = (flags & RDP_ACK) ? 1 : 0; + header->eak = (flags & RDP_EAK) ? 1 : 0; + header->syn = (flags & RDP_SYN) ? 1 : 0; + header->rst = (flags & RDP_RST) ? 1 : 0; + + /* Send copy to tx_queue, before sending packet to IF */ + if (flags & RDP_SYN) { + rdp_packet_t * rdp_packet = csp_buffer_clone(packet); + if (rdp_packet == NULL) return CSP_ERR_NOMEM; + rdp_packet->timestamp = csp_get_ms(); + if (csp_queue_enqueue(conn->rdp.tx_queue, &rdp_packet, 0) != CSP_QUEUE_OK) + csp_buffer_free(rdp_packet); + } + + /* Send control messages with high priority */ + idout = conn->idout; + idout.pri = conn->idout.pri < CSP_PRIO_HIGH ? conn->idout.pri : CSP_PRIO_HIGH; + + /* Send packet to IF */ + csp_iface_t * ifout = csp_rtable_find_iface(idout.dst); + if (csp_send_direct(idout, packet, ifout, 0) != CSP_ERR_NONE) { + csp_log_error("INTERFACE ERROR: not possible to send"); + csp_buffer_free(packet); + return CSP_ERR_BUSY; + } + + /* Update last ACK time stamp */ + if (flags & RDP_ACK) { + conn->rdp.rcv_lsa = ack_nr; + conn->rdp.ack_timestamp = csp_get_ms(); + } + + return CSP_ERR_NONE; + +} + +/** + * EXTENDED ACKNOWLEDGEMENTS + * The following function sends an extended ACK packet + */ +static int csp_rdp_send_eack(csp_conn_t * conn) { + + /* Allocate message */ + csp_packet_t * packet_eack = csp_buffer_get(100); + if (packet_eack == NULL) return CSP_ERR_NOMEM; + packet_eack->length = 0; + + /* Loop through RX queue */ + int i, count; + csp_packet_t * packet; + count = csp_queue_size(conn->rdp.rx_queue); + for (i = 0; i < count; i++) { + + if (csp_queue_dequeue_isr(conn->rdp.rx_queue, &packet, &pdTrue) != CSP_QUEUE_OK) { + csp_log_error("Cannot dequeue from rx_queue in queue deliver"); + break; + } + + /* Add seq nr to EACK packet */ + rdp_header_t * header = csp_rdp_header_ref(packet); + packet_eack->data16[packet_eack->length/sizeof(uint16_t)] = csp_hton16(header->seq_nr); + packet_eack->length += sizeof(uint16_t); + csp_log_protocol("Added EACK nr %u", header->seq_nr); + + /* Requeue */ + csp_queue_enqueue_isr(conn->rdp.rx_queue, &packet, &pdTrue); + + } + + return csp_rdp_send_cmp(conn, packet_eack, RDP_ACK | RDP_EAK, conn->rdp.snd_nxt, conn->rdp.rcv_cur); + +} + + +/** + * SYN Packet + * The following function sends a SYN packet + */ +static int csp_rdp_send_syn(csp_conn_t * conn) { + + /* Allocate message */ + csp_packet_t * packet = csp_buffer_get(100); + if (packet == NULL) return CSP_ERR_NOMEM; + + /* Generate contents */ + packet->data32[0] = csp_hton32(csp_rdp_window_size); + packet->data32[1] = csp_hton32(csp_rdp_conn_timeout); + packet->data32[2] = csp_hton32(csp_rdp_packet_timeout); + packet->data32[3] = csp_hton32(csp_rdp_delayed_acks); + packet->data32[4] = csp_hton32(csp_rdp_ack_timeout); + packet->data32[5] = csp_hton32(csp_rdp_ack_delay_count); + packet->length = 6 * sizeof(uint32_t); + + return csp_rdp_send_cmp(conn, packet, RDP_SYN, conn->rdp.snd_iss, 0); + +} + +static inline int csp_rdp_receive_data(csp_conn_t * conn, csp_packet_t * packet) { + + /* Remove RDP header before passing to userspace */ + csp_rdp_header_remove(packet); + + /* Enqueue data */ + if (csp_conn_enqueue_packet(conn, packet) < 0) { + csp_log_warn("Conn RX buffer full"); + return CSP_ERR_NOBUFS; + } + + return CSP_ERR_NONE; + +} + +static inline void csp_rdp_rx_queue_flush(csp_conn_t * conn) { + + /* Loop through RX queue */ + int i, count; + csp_packet_t * packet; + +front: + count = csp_queue_size(conn->rdp.rx_queue); + for (i = 0; i < count; i++) { + + if (csp_queue_dequeue_isr(conn->rdp.rx_queue, &packet, &pdTrue) != CSP_QUEUE_OK) { + csp_log_error("Cannot dequeue from rx_queue in queue deliver"); + break; + } + + rdp_header_t * header = csp_rdp_header_ref(packet); + csp_log_protocol("RX Queue deliver matching Element, seq %u", header->seq_nr); + + /* If the matching packet was found: */ + if (header->seq_nr == (uint16_t)(conn->rdp.rcv_cur + 1)) { + csp_log_protocol("Deliver seq %u", header->seq_nr); + csp_rdp_receive_data(conn, packet); + conn->rdp.rcv_cur++; + /* Loop from first element again */ + goto front; + + /* Otherwise, requeue */ + } else { + csp_queue_enqueue_isr(conn->rdp.rx_queue, &packet, &pdTrue); + } + + } + +} + +static inline bool csp_rdp_seq_in_rx_queue(csp_conn_t * conn, uint16_t seq_nr) { + + /* Loop through RX queue */ + int i, count; + rdp_packet_t * packet; + count = csp_queue_size(conn->rdp.rx_queue); + for (i = 0; i < count; i++) { + + if (csp_queue_dequeue_isr(conn->rdp.rx_queue, &packet, &pdTrue) != CSP_QUEUE_OK) { + csp_log_error("Cannot dequeue from rx_queue in queue exists"); + break; + } + + csp_queue_enqueue_isr(conn->rdp.rx_queue, &packet, &pdTrue); + + rdp_header_t * header = csp_rdp_header_ref((csp_packet_t *) packet); + csp_log_protocol("RX Queue exists matching Element, seq %u", header->seq_nr); + + /* If the matching packet was found, deliver */ + if (header->seq_nr == seq_nr) { + csp_log_protocol("We have a match"); + return true; + } + + } + + return false; + +} + +static inline int csp_rdp_rx_queue_add(csp_conn_t * conn, csp_packet_t * packet, uint16_t seq_nr) { + + if (csp_rdp_seq_in_rx_queue(conn, seq_nr)) + return CSP_QUEUE_ERROR; + return csp_queue_enqueue_isr(conn->rdp.rx_queue, &packet, &pdTrue); + +} + +static void csp_rdp_flush_eack(csp_conn_t * conn, csp_packet_t * eack_packet) { + + /* Loop through TX queue */ + int i, j, count; + rdp_packet_t * packet; + count = csp_queue_size(conn->rdp.tx_queue); + for (i = 0; i < count; i++) { + + if (csp_queue_dequeue(conn->rdp.tx_queue, &packet, 0) != CSP_QUEUE_OK) { + csp_log_error("Cannot dequeue from tx_queue in flush EACK"); + break; + } + + rdp_header_t * header = csp_rdp_header_ref((csp_packet_t *) packet); + csp_log_protocol("EACK compare element, time %u, seq %u", packet->timestamp, csp_ntoh16(header->seq_nr)); + + /* Look for this element in EACKs */ + int match = 0; + for (j = 0; j < (int)((eack_packet->length - sizeof(rdp_header_t)) / sizeof(uint16_t)); j++) { + if (csp_ntoh16(eack_packet->data16[j]) == csp_ntoh16(header->seq_nr)) + match = 1; + + /* Enable this if you want EACK's to trigger retransmission */ + if (csp_ntoh16(eack_packet->data16[j]) > csp_ntoh16(header->seq_nr)) { + uint32_t time_now = csp_get_ms(); + if (csp_rdp_time_after(time_now, packet->quarantine)) { + packet->timestamp = time_now - conn->rdp.packet_timeout - 1; + packet->quarantine = time_now + conn->rdp.packet_timeout / 2; + } + } + } + + if (match == 0) { + /* If not found, put back on tx queue */ + csp_queue_enqueue(conn->rdp.tx_queue, &packet, 0); + } else { + /* Found, free */ + csp_log_protocol("TX Element %u freed", csp_ntoh16(header->seq_nr)); + csp_buffer_free(packet); + } + + } + +} + +static inline bool csp_rdp_should_ack(csp_conn_t * conn) { + + /* If delayed ACKs are not used, always ACK */ + if (!conn->rdp.delayed_acks) { + return true; + } + + /* ACK if time since last ACK is greater than ACK timeout */ + uint32_t time_now = csp_get_ms(); + if (csp_rdp_time_after(time_now, conn->rdp.ack_timestamp + conn->rdp.ack_timeout)) + return true; + + /* ACK if number of unacknowledged packets is greater than delay count */ + if (csp_rdp_seq_after(conn->rdp.rcv_cur, conn->rdp.rcv_lsa + conn->rdp.ack_delay_count)) + return true; + + return false; + +} + +void csp_rdp_flush_all(csp_conn_t * conn) { + + if ((conn == NULL) || conn->rdp.tx_queue == NULL) { + csp_log_error("Null pointer passed to rdp flush all"); + return; + } + + rdp_packet_t * packet; + + /* Empty TX queue */ + while (csp_queue_dequeue_isr(conn->rdp.tx_queue, &packet, &pdTrue) == CSP_QUEUE_OK) { + if (packet != NULL) { + csp_log_protocol("RDP %p: Flush TX Element, time %u, seq %u", conn, packet->timestamp, csp_ntoh16(csp_rdp_header_ref((csp_packet_t *) packet)->seq_nr)); + csp_buffer_free(packet); + } + } + + /* Empty RX queue */ + while (csp_queue_dequeue_isr(conn->rdp.rx_queue, &packet, &pdTrue) == CSP_QUEUE_OK) { + if (packet != NULL) { + csp_log_protocol("RDP %p: Flush RX Element, time %u, seq %u", conn, packet->timestamp, csp_ntoh16(csp_rdp_header_ref((csp_packet_t *) packet)->seq_nr)); + csp_buffer_free(packet); + } + } + +} + + +int csp_rdp_check_ack(csp_conn_t * conn) { + + /* Check all RX queues for spare capacity */ + int prio, avail = 1; + for (prio = 0; prio < CSP_RX_QUEUES; prio++) { + if (CSP_RX_QUEUE_LENGTH - csp_queue_size(conn->rx_queue[prio]) <= 2 * (int32_t)conn->rdp.window_size) { + avail = 0; + break; + } + } + + /* If more space available, only send after ack timeout or immediately if delay_acks is zero */ + if (avail && csp_rdp_should_ack(conn)) + csp_rdp_send_cmp(conn, NULL, RDP_ACK, conn->rdp.snd_nxt, conn->rdp.rcv_cur); + + return CSP_ERR_NONE; + +} + +static inline bool csp_rdp_is_conn_ready_for_tx(csp_conn_t * conn) +{ + // Check Tx window (messages waiting for acks) + if (csp_rdp_seq_after(conn->rdp.snd_nxt, conn->rdp.snd_una + conn->rdp.window_size - 1)) { + return false; + } + return true; +} + +/** + * This function must be called with regular intervals for the + * RDP protocol to work as expected. This takes care of closing + * stale connections and retransmitting traffic. A good place to + * call this function is from the CSP router task. + */ +void csp_rdp_check_timeouts(csp_conn_t * conn) { + + rdp_packet_t * packet; + + /** + * CONNECTION TIMEOUT: + * Check that connection has not timed out inside the network stack + * */ + uint32_t time_now = csp_get_ms(); + if (conn->socket != NULL) { + if (csp_rdp_time_after(time_now, conn->timestamp + conn->rdp.conn_timeout)) { + csp_log_warn("RDP %p: Found a lost connection (now: %u, ts: %u, to: %u), closing now", + conn, time_now, conn->timestamp, conn->rdp.conn_timeout); + csp_close(conn); + return; + } + } + + /** + * CLOSE-WAIT TIMEOUT: + * After waiting a while in CLOSE-WAIT, the connection should be closed. + */ + if (conn->rdp.state == RDP_CLOSE_WAIT) { + if (csp_rdp_time_after(time_now, conn->timestamp + conn->rdp.conn_timeout)) { + csp_log_protocol("RDP %p: CLOSE_WAIT timeout", conn); + csp_close(conn); + } + return; + } + + /** + * MESSAGE TIMEOUT: + * Check each outgoing message for TX timeout + */ + int i, count; + count = csp_queue_size(conn->rdp.tx_queue); + for (i = 0; i < count; i++) { + + if ((csp_queue_dequeue_isr(conn->rdp.tx_queue, &packet, &pdTrue) != CSP_QUEUE_OK) || packet == NULL) { + csp_log_warn("Cannot dequeue from tx_queue in check timeout"); + break; + } + + /* Get header */ + rdp_header_t * header = csp_rdp_header_ref((csp_packet_t *) packet); + + /* If acked, do not retransmit */ + if (csp_rdp_seq_before(csp_ntoh16(header->seq_nr), conn->rdp.snd_una)) { + csp_log_protocol("TX Element Free, time %u, seq %u, una %u", packet->timestamp, csp_ntoh16(header->seq_nr), conn->rdp.snd_una); + csp_buffer_free(packet); + continue; + } + + /* Check timestamp and retransmit if needed */ + if (csp_rdp_time_after(time_now, packet->timestamp + conn->rdp.packet_timeout)) { + csp_log_protocol("TX Element timed out, retransmitting seq %u", csp_ntoh16(header->seq_nr)); + + /* Update to latest outgoing ACK */ + header->ack_nr = csp_hton16(conn->rdp.rcv_cur); + + /* Send copy to tx_queue */ + packet->timestamp = csp_get_ms(); + csp_packet_t * new_packet = csp_buffer_clone(packet); + csp_iface_t * ifout = csp_rtable_find_iface(conn->idout.dst); + if (csp_send_direct(conn->idout, new_packet, ifout, 0) != CSP_ERR_NONE) { + csp_log_warn("Retransmission failed"); + csp_buffer_free(new_packet); + } + + } + + /* Requeue the TX element */ + csp_queue_enqueue_isr(conn->rdp.tx_queue, &packet, &pdTrue); + + } + + /** + * ACK TIMEOUT: + * Check ACK timeouts, if we have unacknowledged segments + */ + if (conn->rdp.delayed_acks) { + csp_rdp_check_ack(conn); + } + + /* Wake user task if connection is open and additional Tx can be done */ + if ((conn->rdp.state == RDP_OPEN) && csp_rdp_is_conn_ready_for_tx(conn)) { + csp_log_protocol("RDP %p: Wake Tx task (check timeouts)", conn); + csp_bin_sem_post(&conn->rdp.tx_wait); + } +} + +void csp_rdp_new_packet(csp_conn_t * conn, csp_packet_t * packet) { + + /* Get RX header and convert to host byte-order */ + rdp_header_t * rx_header = csp_rdp_header_ref(packet); + rx_header->ack_nr = csp_ntoh16(rx_header->ack_nr); + rx_header->seq_nr = csp_ntoh16(rx_header->seq_nr); + + csp_log_protocol("RDP %p: Received in S %u: syn %u, ack %u, eack %u, " + "rst %u, seq_nr %5u, ack_nr %5u, packet_len %u (%u)", + conn, conn->rdp.state, rx_header->syn, rx_header->ack, rx_header->eak, + rx_header->rst, rx_header->seq_nr, rx_header->ack_nr, + packet->length, packet->length - sizeof(rdp_header_t)); + + /* If a RESET was received. */ + if (rx_header->rst) { + + if (rx_header->ack) { + /* Store current ack'ed sequence number */ + conn->rdp.snd_una = rx_header->ack_nr + 1; + } + + if (conn->rdp.state == RDP_CLOSE_WAIT || conn->rdp.state == RDP_CLOSED) { + csp_log_protocol("RDP %p: RST received in CLOSE_WAIT or CLOSED. Now closing connection", conn); + goto discard_close; + } else { + csp_log_protocol("RDP %p: Got RESET in state %u", conn, conn->rdp.state); + + if (rx_header->seq_nr == (uint16_t)(conn->rdp.rcv_cur + 1)) { + csp_log_protocol("RDP %p: RESET in sequence, no more data incoming, reply with RESET", conn); + conn->rdp.state = RDP_CLOSE_WAIT; + conn->timestamp = csp_get_ms(); + csp_rdp_send_cmp(conn, NULL, RDP_ACK | RDP_RST, conn->rdp.snd_nxt, conn->rdp.rcv_cur); + goto discard_close; + } else { + csp_log_protocol("RDP %p: RESET out of sequence, keep connection open", conn); + goto discard_open; + } + } + } + + /* The BIG FAT switch (state-machine) */ + switch(conn->rdp.state) { + + /** + * STATE == CLOSED + */ + case RDP_CLOSED: { + + /* No SYN flag set while in closed. Inform by sending back RST */ + if (!rx_header->syn) { + csp_log_protocol("Not SYN received in CLOSED state. Discarding packet"); + csp_rdp_send_cmp(conn, NULL, RDP_RST, conn->rdp.snd_nxt, conn->rdp.rcv_cur); + goto discard_close; + } + + csp_log_protocol("RDP: SYN-Received"); + + /* Setup TX seq. */ + conn->rdp.snd_iss = (uint16_t)rand(); + conn->rdp.snd_nxt = conn->rdp.snd_iss + 1; + conn->rdp.snd_una = conn->rdp.snd_iss; + + /* Store RX seq. */ + conn->rdp.rcv_cur = rx_header->seq_nr; + conn->rdp.rcv_irs = rx_header->seq_nr; + conn->rdp.rcv_lsa = rx_header->seq_nr; + + /* Store RDP options */ + conn->rdp.window_size = csp_ntoh32(packet->data32[0]); + conn->rdp.conn_timeout = csp_ntoh32(packet->data32[1]); + conn->rdp.packet_timeout = csp_ntoh32(packet->data32[2]); + conn->rdp.delayed_acks = csp_ntoh32(packet->data32[3]); + conn->rdp.ack_timeout = csp_ntoh32(packet->data32[4]); + conn->rdp.ack_delay_count = csp_ntoh32(packet->data32[5]); + csp_log_protocol("RDP: Window Size %u, conn timeout %u, packet timeout %u", + conn->rdp.window_size, conn->rdp.conn_timeout, conn->rdp.packet_timeout); + csp_log_protocol("RDP: Delayed acks: %u, ack timeout %u, ack each %u packet", + conn->rdp.delayed_acks, conn->rdp.ack_timeout, conn->rdp.ack_delay_count); + + /* Connection accepted */ + conn->rdp.state = RDP_SYN_RCVD; + + /* Send SYN/ACK */ + csp_rdp_send_cmp(conn, NULL, RDP_ACK | RDP_SYN, conn->rdp.snd_iss, conn->rdp.rcv_irs); + + goto discard_open; + + } + break; + + /** + * STATE == SYN-SENT + */ + case RDP_SYN_SENT: { + + /* First check SYN/ACK */ + if (rx_header->syn && rx_header->ack) { + + conn->rdp.rcv_cur = rx_header->seq_nr; + conn->rdp.rcv_irs = rx_header->seq_nr; + conn->rdp.rcv_lsa = rx_header->seq_nr - 1; + conn->rdp.snd_una = rx_header->ack_nr + 1; + conn->rdp.ack_timestamp = csp_get_ms(); + conn->rdp.state = RDP_OPEN; + + csp_log_protocol("RDP: NP: Connection OPEN"); + + /* Send ACK */ + csp_rdp_send_cmp(conn, NULL, RDP_ACK, conn->rdp.snd_nxt, conn->rdp.rcv_cur); + + /* Wake TX task */ + csp_log_protocol("RDP %p: Wake Tx task (ack)", conn); + csp_bin_sem_post(&conn->rdp.tx_wait); + + goto discard_open; + } + + /* If there was no SYN in the reply, our SYN message hit an already open connection + * This is handled by sending a RST. + * Normally this would be followed up by a new connection attempt, however + * we don't have a method for signaling this to the user space. + */ + if (rx_header->ack) { + csp_log_error("Half-open connection found, sending RST"); + csp_rdp_send_cmp(conn, NULL, RDP_RST, conn->rdp.snd_nxt, conn->rdp.rcv_cur); + csp_log_protocol("RDP %p: Wake Tx task (rst)", conn); + csp_bin_sem_post(&conn->rdp.tx_wait); + + goto discard_open; + } + + /* Otherwise we have an invalid command, such as a SYN reply to a SYN command, + * indicating simultaneous connections, which is not possible in the way CSP + * reserves some ports for server and some for clients. + */ + csp_log_error("Invalid reply to SYN request"); + goto discard_close; + + } + break; + + /** + * STATE == OPEN + */ + case RDP_SYN_RCVD: + case RDP_OPEN: + { + + /* SYN or !ACK is invalid */ + if (rx_header->syn || !rx_header->ack) { + if (rx_header->seq_nr != conn->rdp.rcv_irs) { + csp_log_error("Invalid SYN or no ACK, resetting!"); + goto discard_close; + } else { + csp_log_protocol("Ignoring duplicate SYN packet!"); + goto discard_open; + } + } + + /* Check sequence number */ + if (!csp_rdp_seq_between(rx_header->seq_nr, conn->rdp.rcv_cur + 1, conn->rdp.rcv_cur + conn->rdp.window_size * 2)) { + csp_log_protocol("Invalid sequence number! %"PRIu16" not between %"PRIu16" and %"PRIu16, + rx_header->seq_nr, conn->rdp.rcv_cur + 1, conn->rdp.rcv_cur + 1 + conn->rdp.window_size * 2); + /* If duplicate SYN received, send another SYN/ACK */ + if (conn->rdp.state == RDP_SYN_RCVD) + csp_rdp_send_cmp(conn, NULL, RDP_ACK | RDP_SYN, conn->rdp.snd_iss, conn->rdp.rcv_irs); + /* If duplicate data packet received, send EACK back */ + if (conn->rdp.state == RDP_OPEN) + csp_rdp_send_eack(conn); + + goto discard_open; + } + + /* Check ACK number */ + if (!csp_rdp_seq_between(rx_header->ack_nr, conn->rdp.snd_una - 1 - (conn->rdp.window_size * 2), conn->rdp.snd_nxt - 1)) { + csp_log_error("Invalid ACK number! %u not between %u and %u", + rx_header->ack_nr, conn->rdp.snd_una - 1 - (conn->rdp.window_size * 2), conn->rdp.snd_nxt - 1); + goto discard_open; + } + + /* Check SYN_RCVD ACK */ + if (conn->rdp.state == RDP_SYN_RCVD) { + if (rx_header->ack_nr != conn->rdp.snd_iss) { + csp_log_error("SYN-RCVD: Wrong ACK number"); + goto discard_close; + } + csp_log_protocol("RDP: NC: Connection OPEN"); + conn->rdp.state = RDP_OPEN; + + /* If a socket is set, this message is the first in a new connection + * so the connection must be queued to the socket. */ + if (conn->socket != NULL) { + + /* Try queueing */ + if (csp_queue_enqueue(conn->socket, &conn, 0) == CSP_QUEUE_FULL) { + csp_log_error("ERROR socket cannot accept more connections"); + goto discard_close; + } + + /* Ensure that this connection will not be posted to this socket again + * and remember that the connection handle has been passed to userspace + * by setting the socket = NULL */ + conn->socket = NULL; + } + + } + + /* Store current ack'ed sequence number */ + conn->rdp.snd_una = rx_header->ack_nr + 1; + + /* We have an EACK */ + if (rx_header->eak) { + if (packet->length > sizeof(rdp_header_t)) + csp_rdp_flush_eack(conn, packet); + goto discard_open; + } + + /* If no data, return here */ + if (packet->length <= sizeof(rdp_header_t)) + goto discard_open; + + /* If message is not in sequence, send EACK and store packet */ + if (rx_header->seq_nr != (uint16_t)(conn->rdp.rcv_cur + 1)) { + if (csp_rdp_rx_queue_add(conn, packet, rx_header->seq_nr) != CSP_QUEUE_OK) { + csp_log_protocol("Duplicate sequence number"); + csp_rdp_check_ack(conn); + goto discard_open; + } + csp_rdp_send_eack(conn); + goto accepted_open; + } + + /* Store sequence number before stripping RDP header */ + uint16_t seq_nr = rx_header->seq_nr; + + /* Receive data */ + if (csp_rdp_receive_data(conn, packet) != CSP_ERR_NONE) + goto discard_open; + + /* Update last received packet */ + conn->rdp.rcv_cur = seq_nr; + + /* Only ACK the message if there is room for a full window in the RX buffer. + * Unacknowledged segments are ACKed by csp_rdp_check_timeouts when the buffer is + * no longer full. */ + csp_rdp_check_ack(conn); + + /* Flush RX queue */ + csp_rdp_rx_queue_flush(conn); + + goto accepted_open; + + } + break; + + case RDP_CLOSE_WAIT: + + /* Ignore SYN or !ACK */ + if (rx_header->syn || !rx_header->ack) { + csp_log_protocol("Invalid SYN or no ACK in CLOSE-WAIT"); + goto discard_open; + } + + /* Check ACK number */ + if (!csp_rdp_seq_between(rx_header->ack_nr, conn->rdp.snd_una - 1 - (conn->rdp.window_size * 2), conn->rdp.snd_nxt - 1)) { + csp_log_error("Invalid ACK number! %u not between %u and %u", + rx_header->ack_nr, conn->rdp.snd_una - 1 - (conn->rdp.window_size * 2), conn->rdp.snd_nxt - 1); + goto discard_open; + } + + /* Store current ack'ed sequence number */ + conn->rdp.snd_una = rx_header->ack_nr + 1; + + /* Send back a reset */ + csp_rdp_send_cmp(conn, NULL, RDP_ACK | RDP_RST, conn->rdp.snd_nxt, conn->rdp.rcv_cur); + + goto discard_open; + + default: + csp_log_error("RDP: ERROR default state!"); + goto discard_close; + } + +discard_close: + /* If user-space has received the connection handle, wake it up, + * by sending a NULL pointer, user-space should close connection */ + if (conn->socket == NULL) { + csp_log_protocol("RDP %p: Waiting for userspace to close", conn); + csp_conn_enqueue_packet(conn, NULL); + } else { + csp_close(conn); + } + +discard_open: + csp_buffer_free(packet); +accepted_open: + return; + +} + +int csp_rdp_connect(csp_conn_t * conn, uint32_t timeout) { + + int retry = 1; + + conn->rdp.window_size = csp_rdp_window_size; + conn->rdp.conn_timeout = csp_rdp_conn_timeout; + conn->rdp.packet_timeout = csp_rdp_packet_timeout; + conn->rdp.delayed_acks = csp_rdp_delayed_acks; + conn->rdp.ack_timeout = csp_rdp_ack_timeout; + conn->rdp.ack_delay_count = csp_rdp_ack_delay_count; + conn->rdp.ack_timestamp = csp_get_ms(); + +retry: + csp_log_protocol("RDP %p: Active connect, conn state %u", conn, conn->rdp.state); + + if (conn->rdp.state == RDP_OPEN) { + csp_log_error("RDP %p: Connection already open", conn); + return CSP_ERR_ALREADY; + } + + /* Randomize ISS */ + conn->rdp.snd_iss = (uint16_t)rand(); + + conn->rdp.snd_nxt = conn->rdp.snd_iss + 1; + conn->rdp.snd_una = conn->rdp.snd_iss; + + csp_log_protocol("RDP %p: AC: Sending SYN", conn); + + /* Ensure semaphore is busy, so router task can release it */ + csp_bin_sem_wait(&conn->rdp.tx_wait, 0); + + /* Send SYN message */ + conn->rdp.state = RDP_SYN_SENT; + if (csp_rdp_send_syn(conn) != CSP_ERR_NONE) + goto error; + + /* Wait for router task to release semaphore */ + csp_log_protocol("RDP %p: AC: Waiting for SYN/ACK reply...", conn); + int result = csp_bin_sem_wait(&conn->rdp.tx_wait, conn->rdp.conn_timeout); + + if (result == CSP_SEMAPHORE_OK) { + if (conn->rdp.state == RDP_OPEN) { + csp_log_protocol("RDP %p: AC: Connection OPEN", conn); + return CSP_ERR_NONE; + } else if(conn->rdp.state == RDP_SYN_SENT) { + if (retry) { + csp_log_warn("RDP %p: Half-open connection detected, RST sent, now retrying", conn); + csp_rdp_flush_all(conn); + retry = 0; + goto retry; + } else { + csp_log_error("RDP %p: Connection stayed half-open, even after RST and retry!", conn); + goto error; + } + } + } else { + csp_log_protocol("RDP %p: AC: Connection Failed", conn); + goto error; + } + +error: + conn->rdp.state = RDP_CLOSE_WAIT; + return CSP_ERR_TIMEDOUT; + +} + +int csp_rdp_send(csp_conn_t * conn, csp_packet_t * packet, uint32_t timeout) { + + if (conn->rdp.state != RDP_OPEN) { + csp_log_error("RDP: ERROR cannot send, connection reset"); + return CSP_ERR_RESET; + } + + while ((conn->rdp.state == RDP_OPEN) && (csp_rdp_is_conn_ready_for_tx(conn) == false)) { + csp_log_protocol("RDP %p: Waiting for window update before sending seq %u", conn, conn->rdp.snd_nxt); + if ((csp_bin_sem_wait(&conn->rdp.tx_wait, conn->rdp.conn_timeout)) != CSP_SEMAPHORE_OK) { + csp_log_error("RDP %p: Timeout during send", conn); + return CSP_ERR_TIMEDOUT; + } + } + + if (conn->rdp.state != RDP_OPEN) { + csp_log_error("RDP: ERROR cannot send, connection reset"); + return CSP_ERR_RESET; + } + + /* Add RDP header */ + rdp_header_t * tx_header = csp_rdp_header_add(packet); + tx_header->ack_nr = csp_hton16(conn->rdp.rcv_cur); + tx_header->seq_nr = csp_hton16(conn->rdp.snd_nxt); + tx_header->ack = 1; + + /* Send copy to tx_queue */ + rdp_packet_t * rdp_packet = csp_buffer_clone(packet); + if (rdp_packet == NULL) { + csp_log_error("Failed to allocate packet buffer"); + return CSP_ERR_NOMEM; + } + + rdp_packet->timestamp = csp_get_ms(); + rdp_packet->quarantine = 0; + if (csp_queue_enqueue(conn->rdp.tx_queue, &rdp_packet, 0) != CSP_QUEUE_OK) { + csp_log_error("No more space in RDP retransmit queue"); + csp_buffer_free(rdp_packet); + return CSP_ERR_NOBUFS; + } + + csp_log_protocol("RDP: Sending in S %u: syn %u, ack %u, eack %u, " + "rst %u, seq_nr %5u, ack_nr %5u, packet_len %u (%u)", + conn->rdp.state, tx_header->syn, tx_header->ack, tx_header->eak, + tx_header->rst, csp_ntoh16(tx_header->seq_nr), csp_ntoh16(tx_header->ack_nr), + packet->length, packet->length - sizeof(rdp_header_t)); + + conn->rdp.snd_nxt++; + return CSP_ERR_NONE; + +} + +int csp_rdp_allocate(csp_conn_t * conn) { + + csp_log_protocol("RDP: Creating RDP queues for conn %p", conn); + + /* Set initial state */ + conn->rdp.state = RDP_CLOSED; + conn->rdp.conn_timeout = csp_rdp_conn_timeout; + conn->rdp.packet_timeout = csp_rdp_packet_timeout; + + /* Create a binary semaphore to wait on for tasks */ + if (csp_bin_sem_create(&conn->rdp.tx_wait) != CSP_SEMAPHORE_OK) { + csp_log_error("Failed to initialize semaphore"); + return CSP_ERR_NOMEM; + } + + /* Create TX queue */ + conn->rdp.tx_queue = csp_queue_create(CSP_RDP_MAX_WINDOW, sizeof(csp_packet_t *)); + if (conn->rdp.tx_queue == NULL) { + csp_log_error("Failed to create TX queue for conn"); + csp_bin_sem_remove(&conn->rdp.tx_wait); + return CSP_ERR_NOMEM; + } + + /* Create RX queue */ + conn->rdp.rx_queue = csp_queue_create(CSP_RDP_MAX_WINDOW * 2, sizeof(csp_packet_t *)); + if (conn->rdp.rx_queue == NULL) { + csp_log_error("Failed to create RX queue for conn"); + csp_bin_sem_remove(&conn->rdp.tx_wait); + csp_queue_remove(conn->rdp.tx_queue); + return CSP_ERR_NOMEM; + } + + return CSP_ERR_NONE; + +} + +/** + * @note This function may only be called from csp_close, and is therefore + * without any checks for null pointers. + */ +int csp_rdp_close(csp_conn_t * conn) { + + if (conn->rdp.state == RDP_CLOSED) + return CSP_ERR_NONE; + + /* If message is open, send reset */ + if (conn->rdp.state != RDP_CLOSE_WAIT) { + conn->rdp.state = RDP_CLOSE_WAIT; + conn->timestamp = csp_get_ms(); + csp_rdp_send_cmp(conn, NULL, RDP_ACK | RDP_RST, conn->rdp.snd_nxt, conn->rdp.rcv_cur); + csp_log_protocol("RDP %p: Close, sent RST", conn); + csp_bin_sem_post(&conn->rdp.tx_wait); // wake up any pendng Tx + return CSP_ERR_AGAIN; + } + + csp_log_protocol("RDP %p: Close in CLOSE_WAIT, now closing", conn); + conn->rdp.state = RDP_CLOSED; + return CSP_ERR_NONE; + +} + +/** + * RDP Set socket options + * Controls important parameters of the RDP protocol. + * These settings will be applied to all new outgoing connections. + * The settings are global, so be sure no other task are conflicting with your settings. + */ +void csp_rdp_set_opt(unsigned int window_size, unsigned int conn_timeout_ms, + unsigned int packet_timeout_ms, unsigned int delayed_acks, + unsigned int ack_timeout, unsigned int ack_delay_count) { + csp_rdp_window_size = window_size; + csp_rdp_conn_timeout = conn_timeout_ms; + csp_rdp_packet_timeout = packet_timeout_ms; + csp_rdp_delayed_acks = delayed_acks; + csp_rdp_ack_timeout = ack_timeout; + csp_rdp_ack_delay_count = ack_delay_count; +} + +void csp_rdp_get_opt(unsigned int * window_size, unsigned int * conn_timeout_ms, + unsigned int * packet_timeout_ms, unsigned int * delayed_acks, + unsigned int * ack_timeout, unsigned int * ack_delay_count) { + + if (window_size) + *window_size = csp_rdp_window_size; + if (conn_timeout_ms) + *conn_timeout_ms = csp_rdp_conn_timeout; + if (packet_timeout_ms) + *packet_timeout_ms = csp_rdp_packet_timeout; + if (delayed_acks) + *delayed_acks = csp_rdp_delayed_acks; + if (ack_timeout) + *ack_timeout = csp_rdp_ack_timeout; + if (ack_delay_count) + *ack_delay_count = csp_rdp_ack_delay_count; +} + +#ifdef CSP_DEBUG +void csp_rdp_conn_print(csp_conn_t * conn) { + + if (conn == NULL) + return; + + printf("\tRDP: State %"PRIu16", rcv %"PRIu16", snd %"PRIu16", win %"PRIu32"\r\n", + conn->rdp.state, conn->rdp.rcv_cur, conn->rdp.snd_una, conn->rdp.window_size); + +} +#endif + +#endif diff --git a/thirdparty/libcsp/src/transport/csp_transport.h b/thirdparty/libcsp/src/transport/csp_transport.h new file mode 100644 index 00000000..7fcda3dc --- /dev/null +++ b/thirdparty/libcsp/src/transport/csp_transport.h @@ -0,0 +1,46 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef _CSP_TRANSPORT_H_ +#define _CSP_TRANSPORT_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +/** ARRIVING SEGMENT */ +void csp_udp_new_packet(csp_conn_t * conn, csp_packet_t * packet); +void csp_rdp_new_packet(csp_conn_t * conn, csp_packet_t * packet); + +/** RDP: USER REQUESTS */ +int csp_rdp_connect(csp_conn_t * conn, uint32_t timeout); +int csp_rdp_allocate(csp_conn_t * conn); +int csp_rdp_close(csp_conn_t * conn); +void csp_rdp_conn_print(csp_conn_t * conn); +int csp_rdp_send(csp_conn_t * conn, csp_packet_t * packet, uint32_t timeout); +int csp_rdp_check_ack(csp_conn_t * conn); +void csp_rdp_check_timeouts(csp_conn_t * conn); +void csp_rdp_flush_all(csp_conn_t * conn); + +#ifdef __cplusplus +} /* extern "C" */ +#endif + +#endif /* _CSP_TRANSPORT_H_ */ diff --git a/thirdparty/libcsp/src/transport/csp_udp.c b/thirdparty/libcsp/src/transport/csp_udp.c new file mode 100644 index 00000000..61732703 --- /dev/null +++ b/thirdparty/libcsp/src/transport/csp_udp.c @@ -0,0 +1,49 @@ +/* +Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) + +This library is free software; you can redistribute it and/or +modify it under the terms of the GNU Lesser General Public +License as published by the Free Software Foundation; either +version 2.1 of the License, or (at your option) any later version. + +This library is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +Lesser General Public License for more details. + +You should have received a copy of the GNU Lesser General Public +License along with this library; if not, write to the Free Software +Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include +#include +#include "../csp_port.h" +#include "../csp_conn.h" +#include "csp_transport.h" + +void csp_udp_new_packet(csp_conn_t * conn, csp_packet_t * packet) { + + /* Enqueue */ + if (csp_conn_enqueue_packet(conn, packet) < 0) { + csp_log_error("Connection buffer queue full!"); + csp_buffer_free(packet); + return; + } + + /* Try to queue up the new connection pointer */ + if (conn->socket != NULL) { + if (csp_queue_enqueue(conn->socket, &conn, 0) != CSP_QUEUE_OK) { + csp_log_warn("Warning socket connection queue full"); + csp_close(conn); + return; + } + + /* Ensure that this connection will not be posted to this socket again */ + conn->socket = NULL; + } + +} + diff --git a/thirdparty/libcsp/utils/cfpsplit.py b/thirdparty/libcsp/utils/cfpsplit.py new file mode 100644 index 00000000..9a350e3e --- /dev/null +++ b/thirdparty/libcsp/utils/cfpsplit.py @@ -0,0 +1,52 @@ +#!/usr/bin/env python + +# Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +# Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +# Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) +# +# This library is free software; you can redistribute it and/or +# modify it under the terms of the GNU Lesser General Public +# License as published by the Free Software Foundation; either +# version 2.1 of the License, or (at your option) any later version. +# +# This library is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +# Lesser General Public License for more details. +# +# You should have received a copy of the GNU Lesser General Public +# License along with this library; if not, write to the Free Software +# Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + +# Split CFP header in protocol fields + +import sys + +def usage(): + print("usage: cfpsplit.py HEADER") + +def main(): + try: + hdr = sys.argv[1] + except: + usage() + sys.exit(-1) + + try: + hdrhex = int(hdr, 16) + except: + print("HEADER must be in hexadecimal format") + sys.exit(-1) + + if hdrhex > 0x1fffffff: + print("HEADER is not a valid CFP header") + sys.exit(-1) + + print("Source: {0}".format((hdrhex >> 24) & 0x1f)) + print("Destination: {0}".format((hdrhex >> 19) & 0x1f)) + print("Type: {0}".format("MORE" if ((hdrhex >> 18) & 0x01) else "BEGIN")) + print("Remain: {0}".format((hdrhex >> 10) & 0xff)) + print("Identifier: {0}".format((hdrhex >> 0) & 0x3ff)) + +if __name__ == "__main__": + main() diff --git a/thirdparty/libcsp/utils/cspsplit.py b/thirdparty/libcsp/utils/cspsplit.py new file mode 100644 index 00000000..f4ed942f --- /dev/null +++ b/thirdparty/libcsp/utils/cspsplit.py @@ -0,0 +1,52 @@ +#!/usr/bin/env python + +# Cubesat Space Protocol - A small network-layer protocol designed for Cubesats +# Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) +# Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) +# +# This library is free software; you can redistribute it and/or +# modify it under the terms of the GNU Lesser General Public +# License as published by the Free Software Foundation; either +# version 2.1 of the License, or (at your option) any later version. +# +# This library is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +# Lesser General Public License for more details. +# +# You should have received a copy of the GNU Lesser General Public +# License along with this library; if not, write to the Free Software +# Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + +# Split CSP header in protocol fields + +import sys + +def usage(): + print("usage: cspsplit.py HEADER") + +def main(): + try: + hdr = sys.argv[1] + except: + usage() + sys.exit(-1) + + try: + hdrhex = int(hdr, 16) + except: + print("HEADER must be in hexadecimal format") + sys.exit(-1) + + print("Priotity: {0}".format((hdrhex >> 30) & 0x03)) + print("Source: {0}".format((hdrhex >> 25) & 0x1f)) + print("Destination: {0}".format((hdrhex >> 20) & 0x1f)) + print("Destination port: {0}".format((hdrhex >> 14) & 0x3f)) + print("Source port: {0}".format((hdrhex >> 8) & 0x3f)) + print("HMAC: {0}".format("Yes" if ((hdrhex >> 3) & 0x01) else "No")) + print("XTEA: {0}".format("Yes" if ((hdrhex >> 2) & 0x01) else "No")) + print("RDP: {0}".format("Yes" if ((hdrhex >> 1) & 0x01) else "No")) + print("CRC32: {0}".format("Yes" if ((hdrhex >> 0) & 0x01) else "No")) + +if __name__ == "__main__": + main() From d1eaa8877284ad2ed3e06874909db3a1f545288d Mon Sep 17 00:00:00 2001 From: "Jakob.Meier" Date: Fri, 5 Mar 2021 12:57:42 +0100 Subject: [PATCH 14/79] fixed merge conflict and copied max13865 code --- CMakeLists.txt | 35 +- bsp_q7s/InitMission.cpp | 255 ++-- bsp_q7s/ObjectFactory.cpp | 68 +- bsp_q7s/boardtest/LibgpiodTest.cpp | 37 - bsp_rpi/boardtest/SpiTest.cpp | 61 - bsp_rpi/boardtest/SpiTest.h | 45 - fsfw | 2 +- fsfwconfig/OBSWConfig.h | 13 +- fsfwconfig/objects/systemObjectList.h | 15 +- .../PollingSequenceFactory.cpp | 135 +- fsfwconfig/returnvalues/classIds.h | 1 + libcsp/CMakeLists.txt | 12 - libcsp/bindings/python/libcsp/__init__.py | 6 - libcsp/doc/example.rst | 123 -- libcsp/doc/history.rst | 17 - libcsp/doc/interfaces.rst | 95 -- libcsp/doc/libcsp.rst | 21 - libcsp/doc/memory.rst | 28 - libcsp/doc/mtu.rst | 19 - libcsp/doc/protocolstack.rst | 54 - libcsp/doc/structure.rst | 27 - libcsp/doc/topology.rst | 26 - libcsp/examples/csp_if_fifo.c | 165 --- libcsp/examples/csp_if_fifo_windows.c | 225 ---- libcsp/examples/kiss.c | 151 --- .../python_bindings_example_client.py | 42 - .../python_bindings_example_client_can.py | 30 - .../python_bindings_example_server.py | 72 -- libcsp/examples/simple.c | 200 --- libcsp/examples/zmqproxy.c | 82 -- libcsp/include/CMakeLists.txt | 9 - libcsp/include/csp/arch/csp_clock.h | 60 - libcsp/include/csp/arch/csp_malloc.h | 39 - libcsp/include/csp/arch/csp_queue.h | 49 - libcsp/include/csp/arch/csp_semaphore.h | 109 -- libcsp/include/csp/arch/csp_system.h | 74 -- libcsp/include/csp/arch/csp_thread.h | 100 -- libcsp/include/csp/arch/csp_time.h | 57 - libcsp/include/csp/arch/posix/pthread_queue.h | 118 -- libcsp/include/csp/crypto/csp_hmac.h | 73 -- libcsp/include/csp/crypto/csp_sha1.h | 81 -- libcsp/include/csp/crypto/csp_xtea.h | 52 - libcsp/include/csp/csp.h | 545 -------- libcsp/include/csp/csp_autoconfig.h | 48 - libcsp/include/csp/csp_buffer.h | 92 -- libcsp/include/csp/csp_cmp.h | 189 --- libcsp/include/csp/csp_crc32.h | 63 - libcsp/include/csp/csp_debug.h | 150 --- libcsp/include/csp/csp_endian.h | 170 --- libcsp/include/csp/csp_error.h | 50 - libcsp/include/csp/csp_iflist.h | 56 - libcsp/include/csp/csp_interface.h | 54 - libcsp/include/csp/csp_platform.h | 56 - libcsp/include/csp/csp_rtable.h | 149 --- libcsp/include/csp/csp_types.h | 235 ---- libcsp/include/csp/drivers/can_socketcan.h | 22 - libcsp/include/csp/drivers/i2c.h | 120 -- libcsp/include/csp/drivers/usart.h | 107 -- libcsp/include/csp/interfaces/csp_if_can.h | 76 -- libcsp/include/csp/interfaces/csp_if_i2c.h | 51 - libcsp/include/csp/interfaces/csp_if_kiss.h | 110 -- libcsp/include/csp/interfaces/csp_if_lo.h | 38 - libcsp/include/csp/interfaces/csp_if_zmqhub.h | 26 - libcsp/libcsp.mk | 12 - libcsp/src/CMakeLists.txt | 27 - libcsp/src/arch/CMakeLists.txt | 3 - libcsp/src/arch/freertos/csp_malloc.c | 33 - libcsp/src/arch/freertos/csp_queue.c | 66 - libcsp/src/arch/freertos/csp_semaphore.c | 96 -- libcsp/src/arch/freertos/csp_system.c | 139 --- libcsp/src/arch/freertos/csp_thread.c | 38 - libcsp/src/arch/freertos/csp_time.c | 46 - libcsp/src/arch/macosx/csp_malloc.c | 31 - libcsp/src/arch/macosx/csp_queue.c | 64 - libcsp/src/arch/macosx/csp_semaphore.c | 105 -- libcsp/src/arch/macosx/csp_system.c | 99 -- libcsp/src/arch/macosx/csp_thread.c | 31 - libcsp/src/arch/macosx/csp_time.c | 65 - libcsp/src/arch/macosx/pthread_queue.c | 179 --- libcsp/src/arch/posix/CMakeLists.txt | 9 - libcsp/src/arch/posix/csp_malloc.c | 31 - libcsp/src/arch/posix/csp_queue.c | 64 - libcsp/src/arch/posix/csp_semaphore.c | 164 --- libcsp/src/arch/posix/csp_system.c | 131 -- libcsp/src/arch/posix/csp_thread.c | 55 - libcsp/src/arch/posix/csp_time.c | 54 - libcsp/src/arch/posix/pthread_queue.c | 243 ---- libcsp/src/arch/windows/README | 18 - libcsp/src/arch/windows/csp_malloc.c | 9 - libcsp/src/arch/windows/csp_queue.c | 40 - libcsp/src/arch/windows/csp_semaphore.c | 74 -- libcsp/src/arch/windows/csp_system.c | 60 - libcsp/src/arch/windows/csp_thread.c | 11 - libcsp/src/arch/windows/csp_time.c | 20 - libcsp/src/arch/windows/windows_glue.h | 23 - libcsp/src/arch/windows/windows_queue.c | 91 -- libcsp/src/arch/windows/windows_queue.h | 41 - libcsp/src/bindings/python/pycsp.c | 1052 ---------------- libcsp/src/crypto/CMakeLists.txt | 5 - libcsp/src/crypto/csp_hmac.c | 202 --- libcsp/src/crypto/csp_sha1.c | 217 ---- libcsp/src/crypto/csp_xtea.c | 134 -- libcsp/src/csp_bridge.c | 94 -- libcsp/src/csp_buffer.c | 224 ---- libcsp/src/csp_conn.c | 498 -------- libcsp/src/csp_conn.h | 112 -- libcsp/src/csp_crc32.c | 140 --- libcsp/src/csp_debug.c | 133 -- libcsp/src/csp_dedup.c | 66 - libcsp/src/csp_dedup.h | 31 - libcsp/src/csp_endian.c | 204 --- libcsp/src/csp_hex_dump.c | 55 - libcsp/src/csp_iflist.c | 100 -- libcsp/src/csp_io.c | 502 -------- libcsp/src/csp_io.h | 47 - libcsp/src/csp_port.c | 105 -- libcsp/src/csp_port.h | 55 - libcsp/src/csp_promisc.c | 82 -- libcsp/src/csp_promisc.h | 30 - libcsp/src/csp_qfifo.c | 149 --- libcsp/src/csp_qfifo.h | 54 - libcsp/src/csp_route.c | 346 ------ libcsp/src/csp_route.h | 24 - libcsp/src/csp_service_handler.c | 334 ----- libcsp/src/csp_services.c | 233 ---- libcsp/src/csp_sfp.c | 170 --- libcsp/src/drivers/CMakeLists.txt | 1 - libcsp/src/drivers/can/CMakeLists.txt | 3 - libcsp/src/drivers/can/can_socketcan.c | 201 --- libcsp/src/drivers/usart/usart_linux.c | 254 ---- libcsp/src/drivers/usart/usart_windows.c | 230 ---- libcsp/src/interfaces/CMakeLists.txt | 7 - libcsp/src/interfaces/csp_if_can.c | 279 ----- libcsp/src/interfaces/csp_if_can_pbuf.c | 77 -- libcsp/src/interfaces/csp_if_can_pbuf.h | 31 - libcsp/src/interfaces/csp_if_i2c.c | 116 -- libcsp/src/interfaces/csp_if_kiss.c | 260 ---- libcsp/src/interfaces/csp_if_lo.c | 61 - libcsp/src/rtable/CMakeLists.txt | 3 - libcsp/src/rtable/csp_rtable_cidr.c | 233 ---- libcsp/src/rtable/csp_rtable_static.c | 128 -- libcsp/src/transport/CMakeLists.txt | 4 - libcsp/src/transport/csp_rdp.c | 1102 ----------------- libcsp/src/transport/csp_transport.h | 46 - libcsp/src/transport/csp_udp.c | 49 - libcsp/utils/cfpsplit.py | 52 - libcsp/utils/cspsplit.py | 52 - linux/CMakeLists.txt | 2 + linux/csp/CspComIF.h | 6 +- linux/gpio/LinuxLibgpioIF.cpp | 354 ++++-- linux/i2c/I2cComIF.cpp | 289 +++-- linux/i2c/I2cCookie.h | 6 +- mission/devices/CMakeLists.txt | 2 - mission/devices/HeaterHandler.cpp | 355 ------ mission/devices/HeaterHandler.h | 177 --- mission/devices/Max31865PT1000Handler.cpp | 357 ++++++ mission/devices/Max31865PT100Handler.h | 104 ++ mission/devices/PDU1Handler.cpp | 2 +- .../devices/SolarArrayDeploymentHandler.cpp | 197 --- mission/devices/SolarArrayDeploymentHandler.h | 158 --- .../devicedefinitions/ThermalSensorPacket.h | 60 + etl => thirdparty/etl | 0 thirdparty/lwgps | 1 + 163 files changed, 1207 insertions(+), 16912 deletions(-) delete mode 100644 bsp_q7s/boardtest/LibgpiodTest.cpp delete mode 100644 bsp_rpi/boardtest/SpiTest.cpp delete mode 100644 bsp_rpi/boardtest/SpiTest.h delete mode 100644 libcsp/CMakeLists.txt delete mode 100644 libcsp/bindings/python/libcsp/__init__.py delete mode 100644 libcsp/doc/example.rst delete mode 100644 libcsp/doc/history.rst delete mode 100644 libcsp/doc/interfaces.rst delete mode 100644 libcsp/doc/libcsp.rst delete mode 100644 libcsp/doc/memory.rst delete mode 100644 libcsp/doc/mtu.rst delete mode 100644 libcsp/doc/protocolstack.rst delete mode 100644 libcsp/doc/structure.rst delete mode 100644 libcsp/doc/topology.rst delete mode 100644 libcsp/examples/csp_if_fifo.c delete mode 100644 libcsp/examples/csp_if_fifo_windows.c delete mode 100644 libcsp/examples/kiss.c delete mode 100644 libcsp/examples/python_bindings_example_client.py delete mode 100644 libcsp/examples/python_bindings_example_client_can.py delete mode 100644 libcsp/examples/python_bindings_example_server.py delete mode 100644 libcsp/examples/simple.c delete mode 100644 libcsp/examples/zmqproxy.c delete mode 100644 libcsp/include/CMakeLists.txt delete mode 100644 libcsp/include/csp/arch/csp_clock.h delete mode 100644 libcsp/include/csp/arch/csp_malloc.h delete mode 100644 libcsp/include/csp/arch/csp_queue.h delete mode 100644 libcsp/include/csp/arch/csp_semaphore.h delete mode 100644 libcsp/include/csp/arch/csp_system.h delete mode 100644 libcsp/include/csp/arch/csp_thread.h delete mode 100644 libcsp/include/csp/arch/csp_time.h delete mode 100644 libcsp/include/csp/arch/posix/pthread_queue.h delete mode 100644 libcsp/include/csp/crypto/csp_hmac.h delete mode 100644 libcsp/include/csp/crypto/csp_sha1.h delete mode 100644 libcsp/include/csp/crypto/csp_xtea.h delete mode 100644 libcsp/include/csp/csp.h delete mode 100644 libcsp/include/csp/csp_autoconfig.h delete mode 100644 libcsp/include/csp/csp_buffer.h delete mode 100644 libcsp/include/csp/csp_cmp.h delete mode 100644 libcsp/include/csp/csp_crc32.h delete mode 100644 libcsp/include/csp/csp_debug.h delete mode 100644 libcsp/include/csp/csp_endian.h delete mode 100644 libcsp/include/csp/csp_error.h delete mode 100644 libcsp/include/csp/csp_iflist.h delete mode 100644 libcsp/include/csp/csp_interface.h delete mode 100644 libcsp/include/csp/csp_platform.h delete mode 100644 libcsp/include/csp/csp_rtable.h delete mode 100644 libcsp/include/csp/csp_types.h delete mode 100644 libcsp/include/csp/drivers/can_socketcan.h delete mode 100644 libcsp/include/csp/drivers/i2c.h delete mode 100644 libcsp/include/csp/drivers/usart.h delete mode 100644 libcsp/include/csp/interfaces/csp_if_can.h delete mode 100644 libcsp/include/csp/interfaces/csp_if_i2c.h delete mode 100644 libcsp/include/csp/interfaces/csp_if_kiss.h delete mode 100644 libcsp/include/csp/interfaces/csp_if_lo.h delete mode 100644 libcsp/include/csp/interfaces/csp_if_zmqhub.h delete mode 100644 libcsp/libcsp.mk delete mode 100644 libcsp/src/CMakeLists.txt delete mode 100644 libcsp/src/arch/CMakeLists.txt delete mode 100644 libcsp/src/arch/freertos/csp_malloc.c delete mode 100644 libcsp/src/arch/freertos/csp_queue.c delete mode 100644 libcsp/src/arch/freertos/csp_semaphore.c delete mode 100644 libcsp/src/arch/freertos/csp_system.c delete mode 100644 libcsp/src/arch/freertos/csp_thread.c delete mode 100644 libcsp/src/arch/freertos/csp_time.c delete mode 100644 libcsp/src/arch/macosx/csp_malloc.c delete mode 100644 libcsp/src/arch/macosx/csp_queue.c delete mode 100644 libcsp/src/arch/macosx/csp_semaphore.c delete mode 100644 libcsp/src/arch/macosx/csp_system.c delete mode 100644 libcsp/src/arch/macosx/csp_thread.c delete mode 100644 libcsp/src/arch/macosx/csp_time.c delete mode 100644 libcsp/src/arch/macosx/pthread_queue.c delete mode 100644 libcsp/src/arch/posix/CMakeLists.txt delete mode 100644 libcsp/src/arch/posix/csp_malloc.c delete mode 100644 libcsp/src/arch/posix/csp_queue.c delete mode 100644 libcsp/src/arch/posix/csp_semaphore.c delete mode 100644 libcsp/src/arch/posix/csp_system.c delete mode 100644 libcsp/src/arch/posix/csp_thread.c delete mode 100644 libcsp/src/arch/posix/csp_time.c delete mode 100644 libcsp/src/arch/posix/pthread_queue.c delete mode 100644 libcsp/src/arch/windows/README delete mode 100644 libcsp/src/arch/windows/csp_malloc.c delete mode 100644 libcsp/src/arch/windows/csp_queue.c delete mode 100644 libcsp/src/arch/windows/csp_semaphore.c delete mode 100644 libcsp/src/arch/windows/csp_system.c delete mode 100644 libcsp/src/arch/windows/csp_thread.c delete mode 100644 libcsp/src/arch/windows/csp_time.c delete mode 100644 libcsp/src/arch/windows/windows_glue.h delete mode 100644 libcsp/src/arch/windows/windows_queue.c delete mode 100644 libcsp/src/arch/windows/windows_queue.h delete mode 100644 libcsp/src/bindings/python/pycsp.c delete mode 100644 libcsp/src/crypto/CMakeLists.txt delete mode 100644 libcsp/src/crypto/csp_hmac.c delete mode 100644 libcsp/src/crypto/csp_sha1.c delete mode 100644 libcsp/src/crypto/csp_xtea.c delete mode 100644 libcsp/src/csp_bridge.c delete mode 100644 libcsp/src/csp_buffer.c delete mode 100644 libcsp/src/csp_conn.c delete mode 100644 libcsp/src/csp_conn.h delete mode 100644 libcsp/src/csp_crc32.c delete mode 100644 libcsp/src/csp_debug.c delete mode 100644 libcsp/src/csp_dedup.c delete mode 100644 libcsp/src/csp_dedup.h delete mode 100644 libcsp/src/csp_endian.c delete mode 100644 libcsp/src/csp_hex_dump.c delete mode 100644 libcsp/src/csp_iflist.c delete mode 100644 libcsp/src/csp_io.c delete mode 100644 libcsp/src/csp_io.h delete mode 100644 libcsp/src/csp_port.c delete mode 100644 libcsp/src/csp_port.h delete mode 100644 libcsp/src/csp_promisc.c delete mode 100644 libcsp/src/csp_promisc.h delete mode 100644 libcsp/src/csp_qfifo.c delete mode 100644 libcsp/src/csp_qfifo.h delete mode 100644 libcsp/src/csp_route.c delete mode 100644 libcsp/src/csp_route.h delete mode 100644 libcsp/src/csp_service_handler.c delete mode 100644 libcsp/src/csp_services.c delete mode 100644 libcsp/src/csp_sfp.c delete mode 100644 libcsp/src/drivers/CMakeLists.txt delete mode 100644 libcsp/src/drivers/can/CMakeLists.txt delete mode 100644 libcsp/src/drivers/can/can_socketcan.c delete mode 100644 libcsp/src/drivers/usart/usart_linux.c delete mode 100644 libcsp/src/drivers/usart/usart_windows.c delete mode 100644 libcsp/src/interfaces/CMakeLists.txt delete mode 100644 libcsp/src/interfaces/csp_if_can.c delete mode 100644 libcsp/src/interfaces/csp_if_can_pbuf.c delete mode 100644 libcsp/src/interfaces/csp_if_can_pbuf.h delete mode 100644 libcsp/src/interfaces/csp_if_i2c.c delete mode 100644 libcsp/src/interfaces/csp_if_kiss.c delete mode 100644 libcsp/src/interfaces/csp_if_lo.c delete mode 100644 libcsp/src/rtable/CMakeLists.txt delete mode 100644 libcsp/src/rtable/csp_rtable_cidr.c delete mode 100644 libcsp/src/rtable/csp_rtable_static.c delete mode 100644 libcsp/src/transport/CMakeLists.txt delete mode 100644 libcsp/src/transport/csp_rdp.c delete mode 100644 libcsp/src/transport/csp_transport.h delete mode 100644 libcsp/src/transport/csp_udp.c delete mode 100644 libcsp/utils/cfpsplit.py delete mode 100644 libcsp/utils/cspsplit.py delete mode 100644 mission/devices/HeaterHandler.cpp delete mode 100644 mission/devices/HeaterHandler.h create mode 100644 mission/devices/Max31865PT1000Handler.cpp create mode 100644 mission/devices/Max31865PT100Handler.h delete mode 100644 mission/devices/SolarArrayDeploymentHandler.cpp delete mode 100644 mission/devices/SolarArrayDeploymentHandler.h create mode 100644 mission/devices/devicedefinitions/ThermalSensorPacket.h rename etl => thirdparty/etl (100%) create mode 160000 thirdparty/lwgps diff --git a/CMakeLists.txt b/CMakeLists.txt index 5107b573..5699d12e 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -15,6 +15,7 @@ cmake_minimum_required(VERSION 3.13) set(CMAKE_SCRIPT_PATH "${CMAKE_CURRENT_SOURCE_DIR}/cmake") +option(ADD_ETL_LIB "Add ETL library" ON) if(NOT OS_FSFW) set(OS_FSFW host CACHE STRING "OS for the FSFW.") endif() @@ -37,14 +38,21 @@ set(CMAKE_CXX_STANDARD_REQUIRED True) # Set names and variables set(TARGET_NAME ${CMAKE_PROJECT_NAME}) set(LIB_FSFW_NAME fsfw) +set(LIB_ETL_NAME etl) set(LIB_CSP_NAME libcsp) +set(LIB_LWGPS_NAME lwgps) +set(THIRD_PARTY_FOLDER thirdparty) # Set path names set(FSFW_PATH fsfw) set(MISSION_PATH mission) -set(CSPLIB_PATH libcsp) set(TEST_PATH test/testtasks) set(LINUX_PATH linux) +set(COMMON_PATH common) + +set(CSP_LIB_PATH ${THIRD_PARTY_FOLDER}/libcsp) +set(ETL_LIB_PATH ${THIRD_PARTY_FOLDER}/etl) +set(LWGPS_LIB_PATH ${THIRD_PARTY_FOLDER}/lwgps) set(FSFW_WARNING_SHADOW_LOCAL_GCC OFF) set(ADD_LINUX_FILES TRUE) @@ -61,10 +69,20 @@ if(TGT_BSP) set(ADD_LINUX_FILES TRUE) set(ADD_CSP_LIB TRUE) endif() + + if(${TGT_BSP} MATCHES "arm/raspberrypi") + add_definitions(-DRASPBERRY_PI) + endif() + + if(${TGT_BSP} MATCHES "arm/q7s") + add_definitions(-DXIPHOS_Q7S) + endif() else() # Required by FSFW library set(FSFW_CONFIG_PATH "${BSP_PATH}/fsfwconfig") endif() +# Set for lwgps library +set(LWGPS_CONFIG_PATH "${COMMON_PATH}/config") ################################################################################ # Executable and Sources @@ -79,17 +97,23 @@ if(ROOT_CONFIG_FOLDER) endif() if(ADD_CSP_LIB) - add_subdirectory(${CSPLIB_PATH}) + add_subdirectory(${CSP_LIB_PATH}) +endif() + +if(ADD_ETL_LIB) + add_subdirectory(${ETL_LIB_PATH}) endif() if(ADD_LINUX_FILES) add_subdirectory(${LINUX_PATH}) endif() +add_subdirectory(${LWGPS_LIB_PATH}) add_subdirectory(${BSP_PATH}) add_subdirectory(${FSFW_PATH}) add_subdirectory(${MISSION_PATH}) add_subdirectory(${TEST_PATH}) +add_subdirectory(${COMMON_PATH}) ################################################################################ # Post-Sources preparation @@ -101,8 +125,15 @@ set_property(CACHE OS_FSFW PROPERTY STRINGS host linux) target_link_libraries(${TARGET_NAME} PRIVATE ${LIB_FSFW_NAME} ${LIB_OS_NAME} + ${LIB_LWGPS_NAME} ) +if(ADD_ETL_LIB) + target_link_libraries(${TARGET_NAME} PRIVATE + ${LIB_ETL_NAME} + ) +endif() + if(ADD_CSP_LIB) target_link_libraries(${TARGET_NAME} PRIVATE ${LIB_CSP_NAME} diff --git a/bsp_q7s/InitMission.cpp b/bsp_q7s/InitMission.cpp index 97b18051..e55f9ae9 100644 --- a/bsp_q7s/InitMission.cpp +++ b/bsp_q7s/InitMission.cpp @@ -2,6 +2,8 @@ #include "ObjectFactory.h" #include +#include + #include #include #include @@ -13,7 +15,7 @@ #include -// This is configured for linux without \cr +/* This is configured for linux without CR */ #ifdef LINUX ServiceInterfaceStream sif::debug("DEBUG"); ServiceInterfaceStream sif::info("INFO"); @@ -28,9 +30,9 @@ ServiceInterfaceStream sif::error("ERROR", true, false, true); ObjectManagerIF *objectManager = nullptr; -void InitMission::initMission() { - sif::info << "Building global objects.." << std::endl; - /* Instantiate global object manager and also create all objects */ +void initmission::initMission() { + sif::info << "Building global objects.." << std::endl; + /* Instantiate global object manager and also create all objects */ objectManager = new ObjectManager(ObjectFactory::produce); sif::info << "Initializing all objects.." << std::endl; objectManager->initialize(); @@ -39,148 +41,151 @@ void InitMission::initMission() { initTasks(); } -void InitMission::initTasks(){ - /* TMTC Distribution */ - PeriodicTaskIF* TmTcDistributor = TaskFactory::instance()-> - createPeriodicTask("DIST", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, - 0.2, nullptr); - ReturnValue_t result = TmTcDistributor->addComponent( - objects::CCSDS_PACKET_DISTRIBUTOR); - if(result!=HasReturnvaluesIF::RETURN_OK){ - sif::error << "Object add component failed" << std::endl; - } - result = TmTcDistributor->addComponent(objects::PUS_PACKET_DISTRIBUTOR); - if(result!=HasReturnvaluesIF::RETURN_OK){ - sif::error << "Object add component failed" << std::endl; - } - result = TmTcDistributor->addComponent(objects::TM_FUNNEL); +void initmission::initTasks() { + TaskFactory* factory = TaskFactory::instance(); + if(factory == nullptr) { + /* Should never happen ! */ + return; + } +#if OBSW_PRINT_MISSED_DEADLINES == 1 + void (*missedDeadlineFunc) (void) = TaskFactory::printMissedDeadline; +#else + void (*missedDeadlineFunc) (void) = nullptr; +#endif + + /* TMTC Distribution */ + PeriodicTaskIF* tmTcDistributor = factory->createPeriodicTask( + "DIST", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc); + ReturnValue_t result = tmTcDistributor->addComponent( + objects::CCSDS_PACKET_DISTRIBUTOR); if(result != HasReturnvaluesIF::RETURN_OK) { - sif::error << "Object add component failed" << std::endl; + initmission::printAddObjectError("CCSDS_DISTRIB", objects::CCSDS_PACKET_DISTRIBUTOR); + } + result = tmTcDistributor->addComponent(objects::PUS_PACKET_DISTRIBUTOR); + if(result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS_PACKET_DISTRIB", objects::PUS_PACKET_DISTRIBUTOR); + } + result = tmTcDistributor->addComponent(objects::TM_FUNNEL); + if(result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("TM_FUNNEL", objects::TM_FUNNEL); } - /* UDP bridge */ - PeriodicTaskIF* UdpBridgeTask = TaskFactory::instance()->createPeriodicTask( - "UDP_UNIX_BRIDGE", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, - 0.2, nullptr); - result = UdpBridgeTask->addComponent(objects::UDP_BRIDGE); + PeriodicTaskIF* udpBridgeTask = factory->createPeriodicTask( + "UDP_UNIX_BRIDGE", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc); + result = udpBridgeTask->addComponent(objects::UDP_BRIDGE); if(result != HasReturnvaluesIF::RETURN_OK) { - sif::error << "Add component UDP Unix Bridge failed" << std::endl; + initmission::printAddObjectError("UDP_BRIDGE", objects::UDP_BRIDGE); } - PeriodicTaskIF* UdpPollingTask = TaskFactory::instance()-> - createPeriodicTask("UDP_POLLING", 80, - PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, nullptr); - result = UdpPollingTask->addComponent(objects::UDP_POLLING_TASK); + PeriodicTaskIF* udpPollingTask = factory->createPeriodicTask( + "UDP_POLLING", 80, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, missedDeadlineFunc); + result = udpPollingTask->addComponent(objects::UDP_POLLING_TASK); if(result != HasReturnvaluesIF::RETURN_OK) { - sif::error << "Add component UDP Polling failed" << std::endl; + initmission::printAddObjectError("UDP_POLLING", objects::UDP_POLLING_TASK); } - /* PUS Services */ - PeriodicTaskIF* PusVerification = TaskFactory::instance()-> - createPeriodicTask("PUS_VERIF_1", 40, - PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, nullptr); - result = PusVerification->addComponent(objects::PUS_SERVICE_1_VERIFICATION); - if(result != HasReturnvaluesIF::RETURN_OK){ - sif::error << "Object add component failed" << std::endl; - } + /* PUS Services */ + PeriodicTaskIF* pusVerification = factory->createPeriodicTask( + "PUS_VERIF", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc); + result = pusVerification->addComponent(objects::PUS_SERVICE_1_VERIFICATION); + if(result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS_VERIF", objects::PUS_SERVICE_1_VERIFICATION); + } - PeriodicTaskIF* PusEvents = TaskFactory::instance()-> - createPeriodicTask("PUS_VERIF_1", 60, - PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, nullptr); - result = PusVerification->addComponent(objects::PUS_SERVICE_5_EVENT_REPORTING); - if(result != HasReturnvaluesIF::RETURN_OK){ - sif::error << "Object add component failed" << std::endl; - } + PeriodicTaskIF* pusEvents = factory->createPeriodicTask( + "PUS_EVENTS", 60, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc); + result = pusVerification->addComponent(objects::PUS_SERVICE_5_EVENT_REPORTING); + if(result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS_EVENTS", objects::PUS_SERVICE_5_EVENT_REPORTING); + } - PeriodicTaskIF* PusHighPrio = TaskFactory::instance()-> - createPeriodicTask("PUS_HIGH_PRIO", 50, - PeriodicTaskIF::MINIMUM_STACK_SIZE, - 0.200, nullptr); - result = PusHighPrio->addComponent(objects::PUS_SERVICE_2_DEVICE_ACCESS); - if(result!=HasReturnvaluesIF::RETURN_OK){ - sif::error << "Object add component failed" << std::endl; - } - result = PusHighPrio->addComponent(objects::PUS_SERVICE_9_TIME_MGMT); - if(result!=HasReturnvaluesIF::RETURN_OK){ - sif::error << "Object add component failed" << std::endl; - } + PeriodicTaskIF* pusHighPrio = factory->createPeriodicTask( + "PUS_HIGH_PRIO", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc); + result = pusHighPrio->addComponent(objects::PUS_SERVICE_2_DEVICE_ACCESS); + if(result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS_2", objects::PUS_SERVICE_2_DEVICE_ACCESS); + } + result = pusHighPrio->addComponent(objects::PUS_SERVICE_9_TIME_MGMT); + if(result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS_9", objects::PUS_SERVICE_9_TIME_MGMT); + } - PeriodicTaskIF* PusMedPrio = TaskFactory::instance()-> - createPeriodicTask("PUS_MED_PRIO", 40, - PeriodicTaskIF::MINIMUM_STACK_SIZE, - 0.8, nullptr); - result = PusMedPrio->addComponent(objects::PUS_SERVICE_8_FUNCTION_MGMT); - if(result!=HasReturnvaluesIF::RETURN_OK){ - sif::error << "Object add component failed" << std::endl; - } - result = PusMedPrio->addComponent(objects::PUS_SERVICE_3_HOUSEKEEPING); - if(result!=HasReturnvaluesIF::RETURN_OK){ - sif::error << "Object add component failed" << std::endl; - } - result = PusMedPrio->addComponent(objects::PUS_SERVICE_200_MODE_MGMT); - if(result!=HasReturnvaluesIF::RETURN_OK){ - sif::error << "Object add component failed" << std::endl; - } + PeriodicTaskIF* pusMedPrio = factory->createPeriodicTask( + "PUS_MED_PRIO", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.8, missedDeadlineFunc); + result = pusMedPrio->addComponent(objects::PUS_SERVICE_8_FUNCTION_MGMT); + if(result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS_8", objects::PUS_SERVICE_8_FUNCTION_MGMT); + } + result = pusMedPrio->addComponent(objects::PUS_SERVICE_3_HOUSEKEEPING); + if(result!=HasReturnvaluesIF::RETURN_OK){ + sif::error << "Object add component failed" << std::endl; + } + result = pusMedPrio->addComponent(objects::PUS_SERVICE_200_MODE_MGMT); + if(result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS_200", objects::PUS_SERVICE_200_MODE_MGMT); + } + result = pusMedPrio->addComponent(objects::PUS_SERVICE_20_PARAMETERS); + if(result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS_20", objects::PUS_SERVICE_20_PARAMETERS); + } - PeriodicTaskIF* PusLowPrio = TaskFactory::instance()-> - createPeriodicTask("PUSB", 30, PeriodicTaskIF::MINIMUM_STACK_SIZE, - 1.6, nullptr); - result = PusLowPrio->addComponent(objects::PUS_SERVICE_17_TEST); - if(result!=HasReturnvaluesIF::RETURN_OK){ - sif::error << "Object add component failed" << std::endl; - } + PeriodicTaskIF* pusLowPrio = factory->createPeriodicTask( + "PUS_LOW_PRIO", 30, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.6, missedDeadlineFunc); + result = pusLowPrio->addComponent(objects::PUS_SERVICE_17_TEST); + if(result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("PUS_17", objects::PUS_SERVICE_17_TEST); + } - //TODO: Add handling of missed deadlines - /* Polling Sequence Table Default */ - FixedTimeslotTaskIF * PollingSequenceTableTaskDefault = - TaskFactory::instance()->createFixedTimeslotTask("PST_TASK_DEFAULT", - 50, PeriodicTaskIF::MINIMUM_STACK_SIZE*4, 4.0, - nullptr); - result = pst::pollingSequenceInitDefault(PollingSequenceTableTaskDefault); - if (result != HasReturnvaluesIF::RETURN_OK) { - sif::error << "InitMission::initTasks: Creating PST failed!" - << std::endl; - } + //TODO: Add handling of missed deadlines + /* Polling Sequence Table Default */ + FixedTimeslotTaskIF * pollingSequenceTableTaskDefault = factory->createFixedTimeslotTask( + "PST_TASK_DEFAULT", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE * 4, 3.0, + missedDeadlineFunc); + result = pst::pollingSequenceInitDefault(pollingSequenceTableTaskDefault); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::error << "InitMission::initTasks: Creating PST failed!" << std::endl; + } #if TE0720 == 0 - FixedTimeslotTaskIF* GomSpacePstTask = TaskFactory::instance()-> - createFixedTimeslotTask("GS_PST_TASK", 50, - PeriodicTaskIF::MINIMUM_STACK_SIZE*8, 3.0, nullptr); - result = pst::gomspacePstInit(GomSpacePstTask); - if(result != HasReturnvaluesIF::RETURN_OK) { - sif::error << "InitMission::initTasks: GomSpace PST initialization " - << "failed!" << std::endl; - } -#endif - -#if TE0720 == 1 && TEST_LIBGPIOD == 1 - PeriodicTaskIF* TestTask = TaskFactory::instance()-> - createPeriodicTask("Libgpiod Test Task", 60, - PeriodicTaskIF::MINIMUM_STACK_SIZE, 1, nullptr); - result = TestTask->addComponent(objects::LIBGPIOD_TEST); - if(result != HasReturnvaluesIF::RETURN_OK){ - sif::error << "Object add component libgpiod test task object" << std::endl; + FixedTimeslotTaskIF* gomSpacePstTask = factory-> + createFixedTimeslotTask("GS_PST_TASK", 50, + PeriodicTaskIF::MINIMUM_STACK_SIZE*8, 3.0, missedDeadlineFunc); + result = pst::gomspacePstInit(gomSpacePstTask); + if(result != HasReturnvaluesIF::RETURN_OK) { + sif::error << "InitMission::initTasks: GomSpace PST initialization failed!" << std::endl; } #endif - //Main thread sleep - sif::info << "Starting tasks.." << std::endl; - TmTcDistributor->startTask(); - UdpBridgeTask->startTask(); - UdpPollingTask->startTask(); + PeriodicTaskIF* testTask = factory->createPeriodicTask( + "GPIOD_TEST", 60, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1, missedDeadlineFunc); +#if OBSW_ADD_TEST_CODE == 1 + result = testTask->addComponent(objects::TEST_TASK); + if(result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("TEST_TASK", objects::TEST_TASK); + } +#endif /* OBSW_ADD_TEST_CODE == 1 */ +#if TE0720 == 1 && TEST_LIBGPIOD == 1 + result = testTask->addComponent(objects::LIBGPIOD_TEST); + if(result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("GPIOD_TEST", objects::LIBGPIOD_TEST); + } +#endif /* TE0720 == 1 && TEST_LIBGPIOD == 1 */ + + sif::info << "Starting tasks.." << std::endl; + tmTcDistributor->startTask(); + udpBridgeTask->startTask(); + udpPollingTask->startTask(); #if TE0720 == 0 - GomSpacePstTask->startTask(); + gomSpacePstTask->startTask(); #endif - PollingSequenceTableTaskDefault->startTask(); + pollingSequenceTableTaskDefault->startTask(); - PusVerification->startTask(); - PusEvents->startTask(); - PusHighPrio->startTask(); - PusMedPrio->startTask(); - PusLowPrio->startTask(); + pusVerification->startTask(); + pusEvents->startTask(); + pusHighPrio->startTask(); + pusMedPrio->startTask(); + pusLowPrio->startTask(); -#if TE0720 == 1 && TEST_LIBGPIOD == 1 - TestTask->startTask(); -#endif - sif::info << "Tasks started.." << std::endl; + testTask->startTask(); + sif::info << "Tasks started.." << std::endl; } diff --git a/bsp_q7s/ObjectFactory.cpp b/bsp_q7s/ObjectFactory.cpp index f17dadda..13f27f96 100644 --- a/bsp_q7s/ObjectFactory.cpp +++ b/bsp_q7s/ObjectFactory.cpp @@ -4,15 +4,10 @@ #include #include #include +#include -#include -#include -#include -#include -#include -#include - -#include +#include +#include #include #include @@ -21,8 +16,7 @@ #include #include #include -#include -#include + #include #include #include @@ -38,8 +32,15 @@ #include #include +#include +#include +#include +#include +#include +#include + #if TEST_LIBGPIOD == 1 -#include "LibgpiodTest.h" +#include #endif void Factory::setStaticFrameworkObjectIds() { @@ -125,48 +126,49 @@ void ObjectFactory::produce(){ new LinuxLibgpioIF(objects::GPIO_IF); #if TE0720 == 0 /* Pin H2-11 on stack connector */ - GpioConfig_t gpioConfigHeater0(std::string("gpiochip7"), 16, - std::string("Heater0"), gpio::OUT, 0); + GpiodRegular gpioConfigHeater0(std::string("gpiochip7"), 16, std::string("Heater0"), gpio::OUT, + 0); heaterGpiosCookie->addGpio(gpioIds::HEATER_0, gpioConfigHeater0); /* Pin H2-12 on stack connector */ - GpioConfig_t gpioConfigHeater1(std::string("gpiochip7"), 12, - std::string("Heater1"), gpio::OUT, 0); + GpiodRegular gpioConfigHeater1(std::string("gpiochip7"), 12, + std::string("Heater1"), gpio::OUT, 0); heaterGpiosCookie->addGpio(gpioIds::HEATER_1, gpioConfigHeater1); /* Pin H2-13 on stack connector */ - GpioConfig_t gpioConfigHeater2(std::string("gpiochip7"), 7, + GpiodRegular gpioConfigHeater2(std::string("gpiochip7"), 7, std::string("Heater2"), gpio::OUT, 0); heaterGpiosCookie->addGpio(gpioIds::HEATER_2, gpioConfigHeater2); - GpioConfig_t gpioConfigHeater3(std::string("gpiochip7"), 5, - std::string("Heater3"), gpio::OUT, 0); + GpiodRegular gpioConfigHeater3(std::string("gpiochip7"), 5, std::string("Heater3"), gpio::OUT, + 0); heaterGpiosCookie->addGpio(gpioIds::HEATER_3, gpioConfigHeater3); - GpioConfig_t gpioConfigHeater4(std::string("gpiochip7"), 3, - std::string("Heater4"), gpio::OUT, 0); + GpiodRegular gpioConfigHeater4(std::string("gpiochip7"), 3, std::string("Heater4"), gpio::OUT, + 0); heaterGpiosCookie->addGpio(gpioIds::HEATER_4, gpioConfigHeater4); - GpioConfig_t gpioConfigHeater5(std::string("gpiochip7"), 0, - std::string("Heater5"), gpio::OUT, 0); + GpiodRegular gpioConfigHeater5(std::string("gpiochip7"), 0, std::string("Heater5"), gpio::OUT, + 0); heaterGpiosCookie->addGpio(gpioIds::HEATER_5, gpioConfigHeater5); - GpioConfig_t gpioConfigHeater6(std::string("gpiochip7"), 1, - std::string("Heater6"), gpio::OUT, 0); + GpiodRegular gpioConfigHeater6(std::string("gpiochip7"), 1, std::string("Heater6"), gpio::OUT, + 0); heaterGpiosCookie->addGpio(gpioIds::HEATER_6, gpioConfigHeater6); - GpioConfig_t gpioConfigHeater7(std::string("gpiochip7"), 11, - std::string("Heater7"), gpio::OUT, 0); + GpiodRegular gpioConfigHeater7(std::string("gpiochip7"), 11, std::string("Heater7"), gpio::OUT, + 0); heaterGpiosCookie->addGpio(gpioIds::HEATER_7, gpioConfigHeater7); new HeaterHandler(objects::HEATER_HANDLER, objects::GPIO_IF, heaterGpiosCookie, objects::PCDU_HANDLER, pcduSwitches::TCS_BOARD_8V_HEATER_IN); GpioCookie* solarArrayDeplCookie = new GpioCookie; - GpioConfig_t gpioConfigDeplSA0(std::string("gpiochip7"), 4, + + GpiodRegular gpioConfigDeplSA0(std::string("gpiochip7"), 4, std::string("DeplSA1"), gpio::OUT, 0); solarArrayDeplCookie->addGpio(gpioIds::DEPLSA1, gpioConfigDeplSA0); - GpioConfig_t gpioConfigDeplSA1(std::string("gpiochip7"), 2, + GpiodRegular gpioConfigDeplSA1(std::string("gpiochip7"), 2, std::string("DeplSA2"), gpio::OUT, 0); solarArrayDeplCookie->addGpio(gpioIds::DEPLSA2, gpioConfigDeplSA1); @@ -192,17 +194,17 @@ void ObjectFactory::produce(){ #if TE0720 == 1 && TEST_LIBGPIOD == 1 /* Configure MIO0 as input */ - GpioConfig_t gpioConfigMio0(std::string("gpiochip0"), 0, + GpiodRegular gpioConfigMio0(std::string("gpiochip0"), 0, std::string("MIO0"), gpio::IN, 0); GpioCookie* gpioCookie = new GpioCookie; - gpioCookie->addGpio(gpioIds::Test_ID, gpioConfigMio0); + gpioCookie->addGpio(gpioIds::TEST_ID_0, gpioConfigMio0); new LibgpiodTest(objects::LIBGPIOD_TEST, objects::GPIO_IF, gpioCookie); #elif TE0720 == 1 /* Configuration for MIO0 on TE0720-03-1CFA */ - GpioConfig_t gpioConfigForDummyHeater(std::string("gpiochip0"), 0, + GpiodRegular gpioConfigForDummyHeater(std::string("gpiochip0"), 0, std::string("Heater0"), gpio::OUT, 0); heaterGpiosCookie->addGpio(gpioIds::HEATER_0, gpioConfigForDummyHeater); - new HeaterHandler(objects::HEATER_HANDLER, objects::GPIO_IF, heaterGpiosCookie, objects::PCDU_HANDLER, - pcduSwitches::TCS_BOARD_8V_HEATER_IN); + new HeaterHandler(objects::HEATER_HANDLER, objects::GPIO_IF, heaterGpiosCookie, + objects::PCDU_HANDLER, pcduSwitches::TCS_BOARD_8V_HEATER_IN); #endif } diff --git a/bsp_q7s/boardtest/LibgpiodTest.cpp b/bsp_q7s/boardtest/LibgpiodTest.cpp deleted file mode 100644 index 51f89abe..00000000 --- a/bsp_q7s/boardtest/LibgpiodTest.cpp +++ /dev/null @@ -1,37 +0,0 @@ -#include "LibgpiodTest.h" - -#include -#include -#include - -LibgpiodTest::LibgpiodTest(object_id_t objectId, object_id_t gpioIfobjectId, - GpioCookie* gpioCookie): - TestTask(objectId) { - - gpioInterface = objectManager->get(gpioIfobjectId); - if (gpioInterface == nullptr) { - sif::error << "LibgpiodTest::LibgpiodTest: Invalid Gpio interface." << std::endl; - } - gpioInterface->initialize(gpioCookie); -} - -LibgpiodTest::~LibgpiodTest() { -} - -ReturnValue_t LibgpiodTest::performPeriodicAction() { - int gpioState; - ReturnValue_t result; - - result = gpioInterface->readGpio(gpioIds::Test_ID, &gpioState); - if (result != RETURN_OK) { - sif::debug << "LibgpiodTest::performPeriodicAction: Failed to read gpio " - << std::endl; - return RETURN_FAILED; - } - else { - sif::debug << "LibgpiodTest::performPeriodicAction: MIO 0 state = " << gpioState - << std::endl; - } - return RETURN_OK; -} - diff --git a/bsp_rpi/boardtest/SpiTest.cpp b/bsp_rpi/boardtest/SpiTest.cpp deleted file mode 100644 index a78d0171..00000000 --- a/bsp_rpi/boardtest/SpiTest.cpp +++ /dev/null @@ -1,61 +0,0 @@ -#include "SpiTest.h" - -#include - -#include -#include - - - -SpiTest::SpiTest(object_id_t objectId): SystemObject(objectId) { - sif::info << "Setting up Raspberry Pi WiringPi library." << std::endl; -// wiringPiSetupGpio(); - -// pinMode(SS_MGM_0_LIS3, OUTPUT); -// pinMode(SS_MGM_1_RM, OUTPUT); -// pinMode(SS_GYRO_0_ADIS, OUTPUT); -// pinMode(SS_GYRO_1_L3G, OUTPUT); -// pinMode(SS_GYRO_2_L3G, OUTPUT); -// pinMode(SS_MGM_2_LIS3, OUTPUT); -// pinMode(SS_MGM_3_RM, OUTPUT); -// -// digitalWrite(SS_MGM_0_LIS3, HIGH); -// digitalWrite(SS_MGM_1_RM, HIGH); -// digitalWrite(SS_GYRO_0_ADIS, HIGH); -// digitalWrite(SS_GYRO_1_L3G, HIGH); -// digitalWrite(SS_GYRO_2_L3G, HIGH); -// digitalWrite(SS_MGM_2_LIS3, HIGH); -// digitalWrite(SS_MGM_3_RM, HIGH); - - int spiFd = open(spiDeviceName.c_str(), O_RDWR); - if (spiFd < 0){ - sif::error << "Could not open SPI device!" << std::endl; - } - - spiMode = SPI_MODE_3; - int ret = ioctl(spiFd, SPI_IOC_WR_MODE, &spiMode); - if(ret < 0) { - sif::error << "Could not set write mode!" << std::endl; - } - - /* Datenrate setzen */ - ret = ioctl(spiFd, SPI_IOC_WR_MAX_SPEED_HZ, &spiSpeed); - if(ret < 0) { - sif::error << "Could not SPI speed!" << std::endl; - } -} - -ReturnValue_t SpiTest::performOperation(uint8_t opCode) { - if(oneShot) { - - } - return HasReturnvaluesIF::RETURN_OK; -} - -ReturnValue_t SpiTest::initialize() { - //transferHandle.rx_buf = reinterpret_cast<__u64>(receiveBuffer); - //transferHandle.tx_buf = reinterpret_cast<__u64>(sendBuffer); - //transferHandle.speed_hz = 976000; - //transferHandle.len = 2; - return HasReturnvaluesIF::RETURN_OK; -} diff --git a/bsp_rpi/boardtest/SpiTest.h b/bsp_rpi/boardtest/SpiTest.h deleted file mode 100644 index b4f37fe2..00000000 --- a/bsp_rpi/boardtest/SpiTest.h +++ /dev/null @@ -1,45 +0,0 @@ -#ifndef BSP_LINUX_TEST_SPITEST_H_ -#define BSP_LINUX_TEST_SPITEST_H_ - -#include -#include -#include -#include - -class SpiTest: - public SystemObject, - public ExecutableObjectIF { -public: - SpiTest(object_id_t objectId); - - ReturnValue_t performOperation(uint8_t opCode) override; - ReturnValue_t initialize() override; -private: - // These chip selects (BCM number) will be pulled high if not used - // ACS board specific. - enum SpiChipSelects { - SS_MGM_0_LIS3 = 0, //!< MGM 0, LIS3MDLTR, U6, A side - SS_MGM_1_RM = 1, //!< MGM 1, RM3100, U7, A side - SS_GYRO_0_ADIS = 2, //!< Gyro 0, ADIS16485, U3, A side - SS_GYRO_1_L3G = 3, //!< Gyro 1, L3GD20H, U4, A side - SS_GYRO_2_L3G = 4, //!< Gyro 2, L3GD20h, U5, B side - SS_MGM_2_LIS3 = 17, //!< MGM 2, LIS3MDLTR, U8, B side - SS_MGM_3_RM = 27, //!< MGM 3, RM3100, U9, B side - }; - - const std::string spiDeviceName = "/dev/spidev0.0"; - int spiFd = 0; - - uint8_t spiMode = SPI_MODE_3; - uint32_t spiSpeed = 976000; - - uint8_t sendBuffer[32]; - uint8_t receiveBuffer[32]; - struct spi_ioc_transfer transferHandle; - - bool oneShot = true; - -}; - - -#endif /* BSP_LINUX_TEST_SPITEST_H_ */ diff --git a/fsfw b/fsfw index 7d0916a4..91f69aa3 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit 7d0916a44e18c87b00998448333023186b3d85b1 +Subproject commit 91f69aa34fcdde9d3f6ae1a71e72a084bf3bc49d diff --git a/fsfwconfig/OBSWConfig.h b/fsfwconfig/OBSWConfig.h index 69993b62..5a9106b5 100644 --- a/fsfwconfig/OBSWConfig.h +++ b/fsfwconfig/OBSWConfig.h @@ -6,13 +6,20 @@ #ifndef FSFWCONFIG_OBSWCONFIG_H_ #define FSFWCONFIG_OBSWCONFIG_H_ -#define TEST_LIBGPIOD 0 +#ifdef RASPBERRY_PI +#include +#endif +#include "commonConfig.h" +#include "OBSWVersion.h" /* These defines should be disabled for mission code but are useful for debugging. */ -#define OBSW_VERBOSE_LEVEL 1 +#define OBSW_VERBOSE_LEVEL 1 +#define OBSW_PRINT_MISSED_DEADLINES 1 +#define OBSW_ADD_TEST_CODE 1 +#define TEST_LIBGPIOD 0 -#define TE0720 0 +#define TE0720 0 #define P60DOCK_DEBUG 0 #define PDU1_DEBUG 0 diff --git a/fsfwconfig/objects/systemObjectList.h b/fsfwconfig/objects/systemObjectList.h index f05a5f6a..f05becbe 100644 --- a/fsfwconfig/objects/systemObjectList.h +++ b/fsfwconfig/objects/systemObjectList.h @@ -31,6 +31,7 @@ namespace objects { CSP_COM_IF = 0x49000002, I2C_COM_IF = 0x49000003, UART_COM_IF = 0x49000004, + SPI_COM_IF = 0x49000005, /* 0x47 ('G') for Gpio Interfaces */ GPIO_IF = 0x47000001, @@ -42,10 +43,18 @@ namespace objects { ACU_HANDLER = 0x44000004, TMP1075_HANDLER_1 = 0x44000005, TMP1075_HANDLER_2 = 0x44000006, + + MGM_0_LIS3_HANDLER = 0x4400007, + MGM_1_RM3100_HANDLER = 0x44000008, + MGM_2_LIS3_HANDLER = 0x44000009, + MGM_3_RM3100_HANDLER = 0x44000010, + GYRO_0_ADIS_HANDLER = 0x44000011, + GYRO_1_L3G_HANDLER = 0x44000012, + GYRO_2_L3G_HANDLER = 0x44000013, + /* Custom device handler */ - PCDU_HANDLER = 0x44000007, - /* Custom device handler */ - SOLAR_ARRAY_DEPL_HANDLER = 0x44000008, + PCDU_HANDLER = 0x44001000, + SOLAR_ARRAY_DEPL_HANDLER = 0x44001001, SYRLINKS_HK_HANDLER = 0x44000009, /* 0x54 ('T') for thermal objects */ diff --git a/fsfwconfig/pollingsequence/PollingSequenceFactory.cpp b/fsfwconfig/pollingsequence/PollingSequenceFactory.cpp index 00450a25..abc614c0 100644 --- a/fsfwconfig/pollingsequence/PollingSequenceFactory.cpp +++ b/fsfwconfig/pollingsequence/PollingSequenceFactory.cpp @@ -7,8 +7,8 @@ ReturnValue_t pst::pollingSequenceInitDefault(FixedTimeslotTaskIF *thisSequence) { - /* Length of a communication cycle */ - uint32_t length = thisSequence->getPeriodMs(); + /* Length of a communication cycle */ + uint32_t length = thisSequence->getPeriodMs(); thisSequence->addSlot(objects::TMP1075_HANDLER_1, length * 0, DeviceHandlerIF::PERFORM_OPERATION); @@ -36,73 +36,88 @@ ReturnValue_t pst::pollingSequenceInitDefault(FixedTimeslotTaskIF *thisSequence) thisSequence->addSlot(objects::TMP1075_HANDLER_2, length * 0.8, DeviceHandlerIF::GET_READ); thisSequence->addSlot(objects::SYRLINKS_HK_HANDLER, length * 0.8, DeviceHandlerIF::GET_READ); - if (thisSequence->checkSequence() == HasReturnvaluesIF::RETURN_OK) { - return HasReturnvaluesIF::RETURN_OK; - } - else { - sif::error << "PollingSequence::initialize has errors!" << std::endl; - return HasReturnvaluesIF::RETURN_FAILED; - } + if (thisSequence->checkSequence() == HasReturnvaluesIF::RETURN_OK) { + return HasReturnvaluesIF::RETURN_OK; + } + + sif::error << "PollingSequence::initialize has errors!" << std::endl; + return HasReturnvaluesIF::RETURN_FAILED; } ReturnValue_t pst::gomspacePstInit(FixedTimeslotTaskIF *thisSequence){ + uint32_t length = thisSequence->getPeriodMs(); - uint32_t length = thisSequence->getPeriodMs(); + thisSequence->addSlot(objects::PCDU_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::PCDU_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::PCDU_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::PCDU_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::P60DOCK_HANDLER, + length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::PDU1_HANDLER, + length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::PDU2_HANDLER, + length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::ACU_HANDLER, + length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::P60DOCK_HANDLER, - length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::PDU1_HANDLER, - length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::PDU2_HANDLER, - length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::ACU_HANDLER, - length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::P60DOCK_HANDLER, + length * 0.2, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::PDU1_HANDLER, + length * 0.2, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::PDU2_HANDLER, + length * 0.2, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::ACU_HANDLER, + length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::P60DOCK_HANDLER, - length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::PDU1_HANDLER, - length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::PDU2_HANDLER, - length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::ACU_HANDLER, - length * 0.2, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::P60DOCK_HANDLER, + length * 0.4, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::PDU1_HANDLER, + length * 0.4, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::PDU2_HANDLER, + length * 0.4, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::ACU_HANDLER, + length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::P60DOCK_HANDLER, - length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::PDU1_HANDLER, - length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::PDU2_HANDLER, - length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::ACU_HANDLER, - length * 0.4, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::P60DOCK_HANDLER, + length * 0.6, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::PDU1_HANDLER, + length * 0.6, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::PDU2_HANDLER, + length * 0.6, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::ACU_HANDLER, + length * 0.6, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::P60DOCK_HANDLER, - length * 0.6, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::PDU1_HANDLER, - length * 0.6, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::PDU2_HANDLER, - length * 0.6, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::ACU_HANDLER, - length * 0.6, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::P60DOCK_HANDLER, + length * 0.8, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::PDU1_HANDLER, + length * 0.8, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::PDU2_HANDLER, + length * 0.8, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::ACU_HANDLER, + length * 0.8, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::P60DOCK_HANDLER, - length * 0.8, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::PDU1_HANDLER, - length * 0.8, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::PDU2_HANDLER, - length * 0.8, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::ACU_HANDLER, - length * 0.8, DeviceHandlerIF::GET_READ); - - if (thisSequence->checkSequence() == HasReturnvaluesIF::RETURN_OK) { - return HasReturnvaluesIF::RETURN_OK; - } - else { - sif::error << "Initialization of GomSpace PST failed" << std::endl; - return HasReturnvaluesIF::RETURN_FAILED; - } + if (thisSequence->checkSequence() != HasReturnvaluesIF::RETURN_OK) { + sif::error << "Initialization of GomSpace PST failed" << std::endl; + return HasReturnvaluesIF::RETURN_FAILED; + } + return HasReturnvaluesIF::RETURN_OK; } +ReturnValue_t pst::pollingSequenceAcsTest(FixedTimeslotTaskIF *thisSequence) { + uint32_t length = thisSequence->getPeriodMs(); + + thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0.2, + DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0.4, + DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0.6, + DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0.8, + DeviceHandlerIF::GET_READ); + if (thisSequence->checkSequence() != HasReturnvaluesIF::RETURN_OK) { + sif::error << "Initialization of ACS Board PST failed" << std::endl; + return HasReturnvaluesIF::RETURN_FAILED; + } + return HasReturnvaluesIF::RETURN_OK; +} diff --git a/fsfwconfig/returnvalues/classIds.h b/fsfwconfig/returnvalues/classIds.h index c5e4d27a..51412cbf 100644 --- a/fsfwconfig/returnvalues/classIds.h +++ b/fsfwconfig/returnvalues/classIds.h @@ -14,6 +14,7 @@ enum { MGM_LIS3MDL, MGM_RM3100, LINUX_LIBGPIO_IF, + LINUX_SPI_COM_IF, PCDU_HANDLER, HEATER_HANDLER, SA_DEPL_HANDLER, diff --git a/libcsp/CMakeLists.txt b/libcsp/CMakeLists.txt deleted file mode 100644 index 5c9f7677..00000000 --- a/libcsp/CMakeLists.txt +++ /dev/null @@ -1,12 +0,0 @@ -cmake_minimum_required(VERSION 3.13) - -set(LIB_CSP_NAME libcsp) - -add_library(${LIB_CSP_NAME}) - -add_subdirectory(src) -add_subdirectory(include) - -target_include_directories(${LIB_CSP_NAME} PRIVATE - ${CMAKE_CURRENT_SOURCE_DIR} -) \ No newline at end of file diff --git a/libcsp/bindings/python/libcsp/__init__.py b/libcsp/bindings/python/libcsp/__init__.py deleted file mode 100644 index 39de36b5..00000000 --- a/libcsp/bindings/python/libcsp/__init__.py +++ /dev/null @@ -1,6 +0,0 @@ -import sys - -if sys.version_info >= (3, 0): - from libcsp_py3 import * -else: - from libcsp_py2 import * diff --git a/libcsp/doc/example.rst b/libcsp/doc/example.rst deleted file mode 100644 index b82a055e..00000000 --- a/libcsp/doc/example.rst +++ /dev/null @@ -1,123 +0,0 @@ -Client and server example -========================= - -The following examples show the initialization of the protocol stack and examples of client/server code. - -Initialization Sequence ------------------------ - -This code initializes the CSP buffer system, device drivers and router core. The example uses the CAN interface function csp_can_tx but the initialization is similar for other interfaces. The loopback interface does not require any explicit initialization. - -.. code-block:: c - - #include - #include - - /* CAN configuration struct for SocketCAN interface "can0" */ - struct csp_can_config can_conf = {.ifc = "can0"}; - - /* Init buffer system with 10 packets of maximum 320 bytes each */ - csp_buffer_init(10, 320); - - /* Init CSP with address 1 */ - csp_init(1); - - /* Init the CAN interface with hardware filtering */ - csp_can_init(CSP_CAN_MASKED, &can_conf) - - /* Setup default route to CAN interface */ - csp_route_set(CSP_DEFAULT_ROUTE, &csp_can_tx, CSP_HOST_MAC); - - /* Start router task with 500 word stack, OS task priority 1 */ - csp_route_start_task(500, 1); - -Server ------- - -This example shows how to create a server task that listens for incoming connections. CSP should be initialized before starting this task. Note the use of `csp_service_handler()` as the default branch in the port switch case. The service handler will automatically reply to ICMP-like requests, such as pings and buffer status requests. - -.. code-block:: c - - void csp_task(void *parameters) { - /* Create socket without any socket options */ - csp_socket_t *sock = csp_socket(CSP_SO_NONE); - - /* Bind all ports to socket */ - csp_bind(sock, CSP_ANY); - - /* Create 10 connections backlog queue */ - csp_listen(sock, 10); - - /* Pointer to current connection and packet */ - csp_conn_t *conn; - csp_packet_t *packet; - - /* Process incoming connections */ - while (1) { - /* Wait for connection, 10000 ms timeout */ - if ((conn = csp_accept(sock, 10000)) == NULL) - continue; - - /* Read packets. Timout is 1000 ms */ - while ((packet = csp_read(conn, 1000)) != NULL) { - switch (csp_conn_dport(conn)) { - case MY_PORT: - /* Process packet here */ - default: - /* Let the service handler reply pings, buffer use, etc. */ - csp_service_handler(conn, packet); - break; - } - } - - /* Close current connection, and handle next */ - csp_close(conn); - } - } - -Client ------- - -This example shows how to allocate a packet buffer, connect to another host and send the packet. CSP should be initialized before calling this function. RDP, XTEA, HMAC and CRC checksums can be enabled per connection, by setting the connection option to a bitwise OR of any combination of `CSP_O_RDP`, `CSP_O_XTEA`, `CSP_O_HMAC` and `CSP_O_CRC`. - -.. code-block:: c - - int send_packet(void) { - - /* Get packet buffer for data */ - csp_packet_t *packet = csp_buffer_get(data_size); - if (packet == NULL) { - /* Could not get buffer element */ - printf("Failed to get buffer element\\n"); - return -1; - } - - /* Connect to host HOST, port PORT with regular UDP-like protocol and 1000 ms timeout */ - csp_conn_t *conn = csp_connect(CSP_PRIO_NORM, HOST, PORT, 1000, CSP_O_NONE); - if (conn == NULL) { - /* Connect failed */ - printf("Connection failed\\n"); - /* Remember to free packet buffer */ - csp_buffer_free(packet); - return -1; - } - - /* Copy message to packet */ - char *msg = "HELLO"; - strcpy(packet->data, msg); - - /* Set packet length */ - packet->length = strlen(msg); - - /* Send packet */ - if (!csp_send(conn, packet, 1000)) { - /* Send failed */ - printf("Send failed\\n"); - csp_buffer_free(packet); - } - - /* Close connection */ - csp_close(conn); - - return 0 - } diff --git a/libcsp/doc/history.rst b/libcsp/doc/history.rst deleted file mode 100644 index ad064873..00000000 --- a/libcsp/doc/history.rst +++ /dev/null @@ -1,17 +0,0 @@ -History -======= - -The idea was developed by a group of students from Aalborg University in 2008. In 2009 the main developer started working for GomSpace, and CSP became integrated into the GomSpace products. The protocol is based on a 32-bit header containing both transport, network and MAC-layer information. It's implementation is designed for, but not limited to, embedded systems such as the 8-bit AVR microprocessor and the 32-bit ARM and AVR from Atmel. The implementation is written in C and is currently ported to run on FreeRTOS and POSIX and pthreads based operating systems like Linux and BSD. The three letter acronym CSP was originally an abbreviation for CAN Space Protocol because the first MAC-layer driver was written for CAN-bus. Now the physical layer has extended to include spacelink, I2C and RS232, the name was therefore extended to the more general CubeSat Space Protocol without changing the abbreviation. - -Satellites using CSP --------------------- - -This is the known list of satellites or organisations that uses CSP. - - * GomSpace GATOSS GOMX-1 - * AAUSAT-3 - * EgyCubeSat - * EuroLuna - * NUTS - * Hawaiian Space Flight Laboratory - * GomSpace GOMX-3 diff --git a/libcsp/doc/interfaces.rst b/libcsp/doc/interfaces.rst deleted file mode 100644 index 5a80325c..00000000 --- a/libcsp/doc/interfaces.rst +++ /dev/null @@ -1,95 +0,0 @@ -CSP Interfaces -============== - -This is an example of how to implement a new layer-2 interface in CSP. The example is going to show how to create a `csp_if_fifo`, using a set of [named pipes](http://en.wikipedia.org/wiki/Named_pipe). The complete interface example code can be found in `examples/fifo.c`. For an example of a fragmenting interface, see the CAN interface in `src/interfaces/csp_if_can.c`. - -CSP interfaces are declared in a `csp_iface_t` structure, which sets the interface nexthop function and name. A maximum transmission unit can also be set, which forces CSP to drop outgoing packets above a certain size. The fifo interface is defined as: - -.. code-block:: c - - #include - #include - - csp_iface_t csp_if_fifo = { - .name = "fifo", - .nexthop = csp_fifo_tx, - .mtu = BUF_SIZE, - }; - -Outgoing traffic ----------------- - -The nexthop function takes a pointer to a CSP packet and a timeout as parameters. All outgoing packets that are routed to the interface are passed to this function: - -.. code-block:: c - - int csp_fifo_tx(csp_packet_t *packet, uint32_t timeout) { - write(tx_channel, &packet->length, packet->length + sizeof(uint32_t) + sizeof(uint16_t)); - csp_buffer_free(packet); - return 1; - } - -In the fifo interface, we simply transmit the header, length field and data using a write to the fifo. CSP does not dictate the wire format, so other interfaces may decide to e.g. ignore the length field if the physical layer provides start/stop flags. - -_Important notice: If the transmission succeeds, the interface must free the packet and return 1. If transmission fails, the nexthop function should return 0 and not free the packet, to allow retransmissions by the caller._ - -Incoming traffic ----------------- - -The interface also needs to receive incoming packets and pass it to the CSP protocol stack. In the fifo interface, this is handled by a thread that blocks on the incoming fifo and waits for packets: - -.. code-block:: c - - void * fifo_rx(void * parameters) { - csp_packet_t *buf = csp_buffer_get(BUF_SIZE); - /* Wait for packet on fifo */ - while (read(rx_channel, &buf->length, BUF_SIZE) > 0) { - csp_qfifo_write(buf, &csp_if_fifo, NULL); - buf = csp_buffer_get(BUF_SIZE); - } - } - -A new CSP buffer is preallocated with csp_buffer_get(). When data is received, the packet is passed to CSP using `csp_qfifo_write()` and a new buffer is allocated for the next packet. In addition to the received packet, `csp_qfifo_write()` takes two additional arguments: - -.. code-block:: c - - void csp_qfifo_write(csp_packet_t *packet, csp_iface_t *interface, CSP_BASE_TYPE *pxTaskWoken); - -The calling interface must be passed in `interface` to avoid routing loops. Furthermore, `pxTaskWoken` must be set to a non-NULL value if the packet is received in an interrupt service routine. If the packet is received in task context, NULL must be passed. 'pxTaskWoken' only applies to FreeRTOS systems, and POSIX system should always set the value to NULL. - -`csp_qfifo_write` will either accept the packet or free the packet buffer, so the interface must never free the packet after passing it to CSP. - -Initialization --------------- - -In order to initialize the interface, and make it available to the router, use the following function found in `csp/csp_interface.h`: - -.. code-block:: c - - csp_route_add_if(&csp_if_fifo); - -This actually happens automatically if you try to call `csp_route_add()` with an interface that is unknown to the router. This may however be removed in the future, in order to ensure that all interfaces are initialised before configuring the routing table. The reason is, that some products released in the future may ship with an empty routing table, which is then configured by a routing protocol rather than a static configuration. - -In order to setup a manual static route, use the following example where the default route is set to the fifo interface: - -.. code-block:: c - - csp_route_set(CSP_DEFAULT_ROUTE, &csp_if_fifo, CSP_NODE_MAC); - -All outgoing traffic except loopback, is now passed to the fifo interface's nexthop function. - -Building the example --------------------- - -The fifo examples can be compiled with: - -.. code-block:: bash - - % gcc csp_if_fifo.c -o csp_if_fifo -I/include -L/build -lcsp -lpthread -lrt - -The two named pipes are created with: - -.. code-block:: bash - - % mkfifo server_to_client client_to_server - diff --git a/libcsp/doc/libcsp.rst b/libcsp/doc/libcsp.rst deleted file mode 100644 index f866015f..00000000 --- a/libcsp/doc/libcsp.rst +++ /dev/null @@ -1,21 +0,0 @@ -.. CSP Documentation master file. - -.. _libcsp: - -********************** -CubeSat Space Protocol -********************** - -.. toctree:: - :maxdepth: 3 - - ../README - history - structure - interfaces - memory - protocolstack - topology - mtu - example - diff --git a/libcsp/doc/memory.rst b/libcsp/doc/memory.rst deleted file mode 100644 index 4e38d711..00000000 --- a/libcsp/doc/memory.rst +++ /dev/null @@ -1,28 +0,0 @@ -How CSP uses memory -=================== - -CSP has been written for small microprocessor systems. The way memory is handled is therefore a tradeoff between the amount used and the code efficiency. This section tries to give some answers to what the memory is used for and how it it used. The primary memory blocks in use by CSP is: - - * Routing table - * Ports table - * Connection table - * Buffer pool - * Interface list - -Tables ------- -The reason for using tables for the routes, ports and connections is speed. When a new packet arrives the core of CSP needs to do a quick lookup in the connection so see if it can find an existing connection to which the packet matches. If this is not found, it will take a lookup in the ports table to see if there are any applications listening on the incoming port number. Another argument of using tables are pre-allocation. The linker will reserve an area of the memory for which the routes and connections can be stored. This avoid an expensive `malloc()` call during initialization of CSP, and practically costs zero CPU instructions. The downside of using tables are the wasted memory used by unallocated ports and connections. For the routing table the argumentation is the same, pre-allocation is better than calling `malloc()`. - -Buffer Pool ------------ - -The buffer handling system can be compiled for either static allocation or a one-time dynamic allocation of the main memory block. After this, the buffer system is entirely self-contained. All allocated elements are of the same size, so the buffer size must be chosen to be able to handle the maximum possible packet length. The buffer pool uses a queue to store pointers to free buffer elements. First of all, this gives a very quick method to get the next free element since the dequeue is an O(1) operation. Furthermore, since the queue is a protected operating system primitive, it can be accessed from both task-context and interrupt-context. The `csp_buffer_get` version is for task-context and `csp_buffer_get_isr` is for interrupt-context. Using fixed size buffer elements that are preallocated is again a question of speed and safety. - - -A basic concept of the buffer system is called Zero-Copy. This means that from userspace to the kernel-driver, the buffer is never copied from one buffer to another. This is a big deal for a small microprocessor, where a call to `memcpy()` can be very expensive. In practice when data is inserted into a packet, it is shifted a certain number of bytes in order to allow for a packet header to be prepended at the lower layers. This also means that there is a strict contract between the layers, which data can be modified and where. The buffer object is normally casted to a `csp_packet_t`, but when its given to an interface on the MAC layer it's casted to a `csp_i2c_frame_t` for example. - -Interface list --------------- - -The interface list is a simple single-ended linked list of references to the interface specification structures. These structures are static const and allocated by the linker. The pointer to this data is inserted into the list one time during setup of the interface. Each entry in the routing table has a direct pointer to the interface element, thereby avoiding list lookup, but the list is needed in order for the dynamic route configuration to know which interfaces are available. - diff --git a/libcsp/doc/mtu.rst b/libcsp/doc/mtu.rst deleted file mode 100644 index 27753300..00000000 --- a/libcsp/doc/mtu.rst +++ /dev/null @@ -1,19 +0,0 @@ -Maximum Transfer Unit -===================== - -There are two things limiting the MTU of CSP. - - 1. The pre-allocated buffer pool’s allocation size - 2. The link layer protocol. - -So let’s assume that you have made a protocol called KISS with a MTU of 256. The 256 is the total amount of data that you can put into the CSP-packet. However, you need to take the overhead of the link layer into account. Typically this could consist of a length field and/or a start/stop flag. So the actual frame size on the link layer would for example be 256 bytes of data + 2 bytes sync flag + 2 bytes length field. - -This requires a buffer allocation of at lest 256 + 2 + 2. However, the CSP packet itself has some reserved bytes in the beginning of the packet (which you can see in csp.h) - so the recommended buffer allocation size is MAX MTU + 16 bytes. In this case the max MTU would be 256. - -If you try to pass data which is longer than the MTU, the chance is that you will also make a buffer overflow in the CSP buffer pool. However, lets assume that you have two interfaces one with an MTU of 200 bytes and another with an MTU of 100 bytes. In this case you might successfully transfer 150 bytes over the first interface, but the packet will be rejected once it comes to the second interface. - -If you want to increase your MTU of a specific link layer, it is up to the link layer protocol to implement its own fragmentation protocol. A good example is CAN-bus which only allows a frame size of 8 bytes. libcsp have a small protocol for this called the “CAN fragmentation protocol" or CFP for short. This allows data of much larger size to be transferred over the CAN bus. - -Okay, but what if you want to transfer 1000 bytes, and the network maximum MTU is 256? Well, since CSP does not include streaming sockets, only packet’s. Somebody will have to split that data up into chunks. It might be that you application have special knowledge about the datatype you are transmitting, and that it makes sense to split the 1000 byte content into 10 chunks of 100 byte status messages. This, application layer delimitation might be good if you have a situation with packet loss, because your receiver could still make good usage of the partially delivered chunks. - -But, what if you just want 1000 bytes transmitted, and you don’t care about the fragmentation unit, and also don’t want the hassle of writing the fragmentation code yourself? - In this case, libcsp now features a new (still experimental) feature called SFP (small fragmentation protocol) designed to work on the application layer. For this purpose you will not use csp_send and csp_recv, but csp_sfp_send and csp_sfp_recv. This will split your data into chunks of a certain size, enumerate them and transfer over a given connection. If a chunk is missing the SFP client will abort the reception, because SFP does not provide retransmission. If you wish to also have retransmission and orderly delivery you will have to open an RDP connection and send your SFP message to that connection. diff --git a/libcsp/doc/protocolstack.rst b/libcsp/doc/protocolstack.rst deleted file mode 100644 index 365aabbe..00000000 --- a/libcsp/doc/protocolstack.rst +++ /dev/null @@ -1,54 +0,0 @@ -The Protocol Stack -================== - -The CSP protocol stack includes functionality on all layers of the TCP/IP model: - -Layer 1: Drivers ----------------- - -Lib CSP is not designed for any specific processor or hardware peripheral, but yet these drivers are required in order to work. The intention of LibCSP is not to provide CAN, I2C or UART drivers for all platforms, however some drivers has been included for some platforms. If you do not find your platform supported, it is quite simple to add a driver that conforms to the CSP interfaces. For example the I2C driver just requires three functions: `init`, `send` and `recv`. For good stability and performance interrupt driven drivers are preferred in favor of polled drivers. Where applicable also DMA usage is recommended. - -Layer 2: MAC interfaces ------------------------ - -CSP has interfaces for I2C, CAN, RS232 (KISS) and Loopback. The layer 2 protocol software defines a frame-format that is suitable for the media. CSP can be easily extended with implementations for even more links. For example a radio-link and IP-networks. The file `csp_interface.h` declares the rx and tx functions needed in order to define a network interface in CSP. During initialisation of CSP each interface will be inserted into a linked list of interfaces that is available to the router. In cases where link-layer addresses are required, such as I2C, the routing table supports specifying next-hop link-layer address directly. This avoids the need to implement an address resolution protocol to translate CSP addresses to I2C addresses. - -Layer 3: Network Router ------------------------ - -The router core is the backbone of the CSP implementation. The router works by looking at a 32-bit CSP header which contains the delivery and source address together with port numbers for the connection. Each router supports both local delivery and forwarding of frames to another destination. Frames will never exit the router on the same interface that they arrives at, this concept is called split horizon, and helps prevent routing loops. - -The main purpose of the router is to accept incoming packets and deliver them to the right message queue. Therefore, in order to listen on a port-number on the network, a task must create a socket and call the accept() call. This will make the task block and wait for incoming traffic, just like a web-server or similar. When an incoming connection is opened, the task is woken. Depending on the task-priority, the task can even preempt another task and start execution immediately. - -There is no routing protocol for automatic route discovery, all routing tables are pre-programmed into the subsystems. The table itself contains a separate route to each of the possible 32 nodes in the network and the additional default route. This means that the overall topology must be decided before putting sub-systems together, as explained in the `topology.md` file. However CSP has an extension on port zero CMP (CSP management protocol), which allows for over-the-network routing table configuration. This has the advantage that default routes could be changed if for example the primary radio fails, and the secondary should be used instead. - -Layer 4: Transport Layer ------------------------- - -LibCSP implements two different Transport Layer protocols, they are called UDP (unreliable datagram protocol) and RDP (reliable datagram protocol). The name UDP has not been chosen to be an exact replica of the UDP (user datagram protocol) known from the TCP/IP model, but they have certain similarities. - -The most important thing to notice is that CSP is entirely a datagram service. There is no stream based service like TCP. A datagram is defined a block of data with a specified size and structure. This block enters the transport layer as a single datagram and exits the transport layer in the other end as a single datagram. CSP preserves this structure all the way to the physical layer for I2C, KISS and Loopback interfaces are used. The CAN-bus interface has to fragment the datagram into CAN-frames of 8 bytes, however only a fully completed datagram will arrive at the receiver. - -UDP -^^^ - -UDP uses a simple transmission model without implicit hand-shaking dialogues for guaranteeing reliability, ordering, or data integrity. Thus, UDP provides an unreliable service and datagrams may arrive out of order, appear duplicated, or go missing without notice. UDP assumes that error checking and correction is either not necessary or performed in the application, avoiding the overhead of such processing at the network interface level. Time-sensitive applications often use UDP because dropping packets is preferable to waiting for delayed packets, which may not be an option in a real-time system. - -UDP is very practical to implement request/reply based communication where a single packet forms the request and a single packet forms the reply. In this case a typical request and wait protocol is used between the client and server, which will simply return an error if a reply is not received within a specified time limit. An error would normally lead to a retransmission of the request from the user or operator which sent the request. - -While UDP is very simple, it also has some limitations. Normally a human in the loop is a good thing when operating the satellite over UDP. But when it comes to larger file transfers, the human becomes the bottleneck. When a high-speed file transfer is initiated data acknowledgment should be done automatically in order to speed up the transfer. This is where the RDP protocol can help. - -RDP -^^^ -CSP provides a transport layer extension called RDP (reliable datagram protocol) which is an implementation of RFC908 and RFC1151. RDP provides a few additional features: - - * Three-way handshake - * Flow Control - * Data-buffering - * Packet re-ordering - * Retransmission - * Windowing - * Extended Acknowledgment - -For more information on this, please refer to RFC908. - diff --git a/libcsp/doc/structure.rst b/libcsp/doc/structure.rst deleted file mode 100644 index 4c9b515c..00000000 --- a/libcsp/doc/structure.rst +++ /dev/null @@ -1,27 +0,0 @@ -Structure -========= -The Cubesat Space Protocol library is structured as shown in the following table: - -============================= ========================================================================= -**Folder** **Description** -============================= ========================================================================= -libcsp/include/csp Main include files -libcsp/include/csp/arch Architecture include files -libcsp/include/csp/interfaces Interface include files -libcsp/include/csp/drivers Drivers include files -libcsp/src Main modules for CSP: io, router, connections, services -libcsp/src/interfaces Interface modules for CAN, I2C, KISS, LOOP and ZMQHUB -libcsp/src/drivers/can Driver for CAN -libcsp/src/drivers/usart Driver for USART -libcsp/src/arch/freertos FreeRTOS architecture module -libcsp/src/arch/macosx Mac OS X architecture module -libcsp/src/arch/posix Posix architecture module -libcsp/src/arch/windows Windows architecture module -libcsp/src/rtable Routing table module -libcsp/transport Transport module, UDP and RDP -libcsp/crypto Crypto module -libcsp/utils Utilities -libcsp/bindings/python Python wrapper for libcsp -libcsp/examples CSP examples (source code) -libasf/doc The doc folder contains the source code for this documentation -============================= ========================================================================= diff --git a/libcsp/doc/topology.rst b/libcsp/doc/topology.rst deleted file mode 100644 index e629c29e..00000000 --- a/libcsp/doc/topology.rst +++ /dev/null @@ -1,26 +0,0 @@ -Network Topology -================ - -CSP uses a network oriented terminology similar to what is known from the Internet and the TCP/IP model. A CSP network can be configured for several different topologies. The most common topology is to create two segments, one for the Satellite and one for the Ground-Station. - -.. code-block:: none - - I2C BUS - _______________________________ - / | | | \ - +---+ +---+ +---+ +---+ +---+ - |OBC| |COM| |EPS| |PL1| |PL2| Nodes 0 - 7 (Space segment) - +---+ +---+ +---+ +---+ +---+ - ^ - | Radio - v - +---+ +----+ - |TNC| ------- | PC | Nodes 8 - 15 (Ground segment) - +---+ USB +----+ - - Node 9 Node 10 - -The address range, from 0 to 15, has been segmented into two equal size segments. This allows for easy routing in the network. All addresses starting with binary 1 is on the ground-segment, and all addresses starting with 0 is on the space segment. From CSP v1.0 the address space has been increased to 32 addresses, 0 to 31. But for legacy purposes, the old 0 to 15 is still used in most products. - -The network is configured using static routes initialised at boot-up of each sub-system. This means that the basic routing table must be assigned compile-time of each subsystem. However each node supports assigning an individual route to every single node in the network and can be changed run-time. This means that the network topology can be easily reconfigured after startup. - diff --git a/libcsp/examples/csp_if_fifo.c b/libcsp/examples/csp_if_fifo.c deleted file mode 100644 index 136fc3aa..00000000 --- a/libcsp/examples/csp_if_fifo.c +++ /dev/null @@ -1,165 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include -#include -#include -#include -#include -#include - -#include -#include - -#define TYPE_SERVER 1 -#define TYPE_CLIENT 2 -#define PORT 10 -#define BUF_SIZE 250 - -pthread_t rx_thread; -int rx_channel, tx_channel; - -int csp_fifo_tx(csp_iface_t *ifc, csp_packet_t *packet, uint32_t timeout); - -csp_iface_t csp_if_fifo = { - .name = "fifo", - .nexthop = csp_fifo_tx, - .mtu = BUF_SIZE, -}; - -int csp_fifo_tx(csp_iface_t *ifc, csp_packet_t *packet, uint32_t timeout) { - /* Write packet to fifo */ - if (write(tx_channel, &packet->length, packet->length + sizeof(uint32_t) + sizeof(uint16_t)) < 0) - printf("Failed to write frame\r\n"); - csp_buffer_free(packet); - return CSP_ERR_NONE; -} - -void * fifo_rx(void * parameters) { - csp_packet_t *buf = csp_buffer_get(BUF_SIZE); - /* Wait for packet on fifo */ - while (read(rx_channel, &buf->length, BUF_SIZE) > 0) { - csp_qfifo_write(buf, &csp_if_fifo, NULL); - buf = csp_buffer_get(BUF_SIZE); - } - - return NULL; -} - -int main(int argc, char **argv) { - - int me, other, type; - const char *message = "Testing CSP"; - const char *rx_channel_name; - const char *tx_channel_name; - csp_socket_t *sock; - csp_conn_t *conn; - csp_packet_t *packet; - - /* Run as either server or client */ - if (argc != 2) { - printf("usage: %s \r\n", argv[0]); - return -1; - } - - /* Set type */ - if (strcmp(argv[1], "server") == 0) { - me = 1; - other = 2; - tx_channel_name = "server_to_client"; - rx_channel_name = "client_to_server"; - type = TYPE_SERVER; - } else if (strcmp(argv[1], "client") == 0) { - me = 2; - other = 1; - tx_channel_name = "client_to_server"; - rx_channel_name = "server_to_client"; - type = TYPE_CLIENT; - } else { - printf("Invalid type. Must be either 'server' or 'client'\r\n"); - return -1; - } - - /* Init CSP and CSP buffer system */ - if (csp_init(me) != CSP_ERR_NONE || csp_buffer_init(10, 300) != CSP_ERR_NONE) { - printf("Failed to init CSP\r\n"); - return -1; - } - - tx_channel = open(tx_channel_name, O_RDWR); - if (tx_channel < 0) { - printf("Failed to open TX channel\r\n"); - return -1; - } - - rx_channel = open(rx_channel_name, O_RDWR); - if (rx_channel < 0) { - printf("Failed to open RX channel\r\n"); - return -1; - } - - /* Start fifo RX task */ - pthread_create(&rx_thread, NULL, fifo_rx, NULL); - - /* Set default route and start router */ - csp_route_set(CSP_DEFAULT_ROUTE, &csp_if_fifo, CSP_NODE_MAC); - csp_route_start_task(0, 0); - - /* Create socket and listen for incoming connections */ - if (type == TYPE_SERVER) { - sock = csp_socket(CSP_SO_NONE); - csp_bind(sock, PORT); - csp_listen(sock, 5); - } - - /* Super loop */ - while (1) { - if (type == TYPE_SERVER) { - /* Process incoming packet */ - conn = csp_accept(sock, 1000); - if (conn) { - packet = csp_read(conn, 0); - if (packet) - printf("Received: %s\r\n", packet->data); - csp_buffer_free(packet); - csp_close(conn); - } - } else { - /* Send a new packet */ - packet = csp_buffer_get(strlen(message)); - if (packet) { - strcpy((char *) packet->data, message); - packet->length = strlen(message); - - conn = csp_connect(CSP_PRIO_NORM, other, PORT, 1000, CSP_O_NONE); - printf("Sending: %s\r\n", message); - if (!conn || !csp_send(conn, packet, 1000)) - return -1; - csp_close(conn); - } - sleep(1); - } - } - - close(rx_channel); - close(tx_channel); - - return 0; -} diff --git a/libcsp/examples/csp_if_fifo_windows.c b/libcsp/examples/csp_if_fifo_windows.c deleted file mode 100644 index 5b360709..00000000 --- a/libcsp/examples/csp_if_fifo_windows.c +++ /dev/null @@ -1,225 +0,0 @@ -#include -#include -#include -#include -#include -#undef interface - -#include -#include - -#define PIPE_BUFSIZE 1024 - -#define TYPE_SERVER 1 -#define TYPE_CLIENT 2 -#define PORT 10 -#define BUF_SIZE 250 - - -static LPCTSTR pipeName = TEXT("\\\\.\\pipe\\CSP_Pipe"); - -static HANDLE pipe = INVALID_HANDLE_VALUE; - -unsigned WINAPI fifo_rx(void *); -unsigned WINAPI pipe_listener(void *); - -void printError(void); - -int csp_fifo_tx(csp_packet_t *packet, uint32_t timeout); - -csp_iface_t csp_if_fifo = { - .name = "fifo", - .nexthop = csp_fifo_tx, - .mtu = BUF_SIZE, -}; - -int csp_fifo_tx(csp_packet_t *packet, uint32_t timeout) { - printf("csp_fifo_tx tid: %lu\n", GetCurrentThreadId()); - DWORD expectedSent = packet->length + sizeof(uint32_t) + sizeof(uint16_t); - DWORD actualSent; - /* Write packet to fifo */ - if( !WriteFile(pipe, &packet->length, expectedSent, &actualSent, NULL) - || actualSent != expectedSent ) { - printError(); - } - - csp_buffer_free(packet); - return CSP_ERR_NONE; -} - - -int main(int argc, char *argv[]) { - int me, other, type; - char *message = "Testing CSP"; - csp_socket_t *sock = NULL; - csp_conn_t *conn = NULL; - csp_packet_t *packet = NULL; - - /* Run as either server or client */ - if (argc != 2) { - printf("usage: server \r\n"); - return -1; - } - - /* Set type */ - if (strcmp(argv[1], "server") == 0) { - me = 1; - other = 2; - type = TYPE_SERVER; - } else if (strcmp(argv[1], "client") == 0) { - me = 2; - other = 1; - type = TYPE_CLIENT; - } else { - printf("Invalid type. Must be either 'server' or 'client'\r\n"); - return -1; - } - - /* Init CSP and CSP buffer system */ - if (csp_init(me) != CSP_ERR_NONE || csp_buffer_init(10, 300) != CSP_ERR_NONE) { - printf("Failed to init CSP\r\n"); - return -1; - } - - if( type == TYPE_SERVER ) { - _beginthreadex(NULL, 0, pipe_listener, NULL, 0, 0); - } else { - pipe = CreateFile( - pipeName, - GENERIC_READ | GENERIC_WRITE, - 0, - NULL, - OPEN_EXISTING, - 0, - NULL); - if( pipe == INVALID_HANDLE_VALUE ) { - printError(); - return -1; - } - } - - /* Set default route and start router */ - csp_route_set(CSP_DEFAULT_ROUTE, &csp_if_fifo, CSP_NODE_MAC); - csp_route_start_task(0, 0); - - /* Create socket and listen for incoming connections */ - if (type == TYPE_SERVER) { - sock = csp_socket(CSP_SO_NONE); - csp_bind(sock, PORT); - csp_listen(sock, 5); - } - - /* Super loop */ - while (1) { - if (type == TYPE_SERVER) { - /* Process incoming packet */ - conn = csp_accept(sock, 1000); - if (conn) { - packet = csp_read(conn, 0); - if (packet) - printf("Received: %s\r\n", packet->data); - csp_buffer_free(packet); - csp_close(conn); - } - } else { - /* Send a new packet */ - packet = csp_buffer_get(strlen(message)); - if (packet) { - strcpy((char *) packet->data, message); - packet->length = strlen(message); - - conn = csp_connect(CSP_PRIO_NORM, other, PORT, 1000, CSP_O_NONE); - printf("Sending: %s\r\n", message); - if (!conn || !csp_send(conn, packet, 1000)) - return -1; - csp_close(conn); - Sleep(1000); - } - } - } - - return 0; -} - -void printError(void) { - LPTSTR messageBuffer = NULL; - DWORD errorCode = GetLastError(); - DWORD formatMessageRet; - formatMessageRet = FormatMessage( - FORMAT_MESSAGE_ALLOCATE_BUFFER | - FORMAT_MESSAGE_FROM_SYSTEM | - FORMAT_MESSAGE_IGNORE_INSERTS, - NULL, - errorCode, - MAKELANGID(LANG_NEUTRAL, SUBLANG_DEFAULT), - (LPTSTR)&messageBuffer, - 0, - NULL); - - if( !formatMessageRet ) { - wprintf(L"FormatMessage error, code: %lu\n", GetLastError()); - return; - } - - printf("%s\n", messageBuffer); - LocalFree(messageBuffer); -} - -unsigned WINAPI pipe_listener(void *parameters) { - while(1) { - HANDLE pipe = CreateNamedPipe( - pipeName, - PIPE_ACCESS_DUPLEX, - PIPE_TYPE_MESSAGE | PIPE_READMODE_MESSAGE | PIPE_WAIT, - PIPE_UNLIMITED_INSTANCES, - PIPE_BUFSIZE, - PIPE_BUFSIZE, - 0, - NULL); - BOOL clientConnected; - if( pipe == INVALID_HANDLE_VALUE ) { - printf("Error creating named pipe. Code %lu\n", GetLastError()); - return -1; - } - - // True if client connects *after* server called ConnectNamedPipe - // or *between* CreateNamedPipe and ConnectNamedPipe - clientConnected = - ConnectNamedPipe(pipe, NULL) ? TRUE : GetLastError()==ERROR_PIPE_CONNECTED; - printf("Client connected!\n"); - - if( !clientConnected ) { - printf("Failure while listening for clients. Code %lu\n", GetLastError()); - CloseHandle(pipe); - return -1; - } - printf("Create client thread\n"); - _beginthreadex(NULL, 0, fifo_rx, (PVOID)pipe, 0, 0); - } - - return 0; -} - -unsigned WINAPI fifo_rx(void *handle) { - printf("fifo_rx tid: %lu\n", GetCurrentThreadId()); - HANDLE pipe = (HANDLE) handle; - csp_packet_t *buf = csp_buffer_get(BUF_SIZE); - DWORD bytesRead; - BOOL readSuccess; - - while(1) { - readSuccess = - ReadFile(pipe, &buf->length, BUF_SIZE, &bytesRead, NULL); - if( !readSuccess || bytesRead == 0 ) { - csp_buffer_free(buf); - printError(); - break; - } - csp_qfifo_write(buf, &csp_if_fifo, NULL); - buf = csp_buffer_get(BUF_SIZE); - } - printf("Closing pipe to client\n"); - CloseHandle(pipe); - - return 0; -} diff --git a/libcsp/examples/kiss.c b/libcsp/examples/kiss.c deleted file mode 100644 index c95eb2aa..00000000 --- a/libcsp/examples/kiss.c +++ /dev/null @@ -1,151 +0,0 @@ -/** - * Build this example on linux with: - * ./waf configure --enable-examples --enable-if-kiss --with-driver-usart=linux --enable-crc32 clean build - */ - -#include -#include -#include - -#include -#include - -#define PORT 10 -#define MY_ADDRESS 1 - -#define SERVER_TIDX 0 -#define CLIENT_TIDX 1 -#define USART_HANDLE 0 - -CSP_DEFINE_TASK(task_server) { - int running = 1; - csp_socket_t *socket = csp_socket(CSP_SO_NONE); - csp_conn_t *conn; - csp_packet_t *packet; - csp_packet_t *response; - - response = csp_buffer_get(sizeof(csp_packet_t) + 2); - if( response == NULL ) { - fprintf(stderr, "Could not allocate memory for response packet!\n"); - return CSP_TASK_RETURN; - } - response->data[0] = 'O'; - response->data[1] = 'K'; - response->length = 2; - - csp_bind(socket, CSP_ANY); - csp_listen(socket, 5); - - printf("Server task started\r\n"); - - while(running) { - if( (conn = csp_accept(socket, 10000)) == NULL ) { - continue; - } - - while( (packet = csp_read(conn, 100)) != NULL ) { - switch( csp_conn_dport(conn) ) { - case PORT: - if( packet->data[0] == 'q' ) - running = 0; - csp_buffer_free(packet); - csp_send(conn, response, 1000); - break; - default: - csp_service_handler(conn, packet); - break; - } - } - - csp_close(conn); - } - - csp_buffer_free(response); - - return CSP_TASK_RETURN; -} - -CSP_DEFINE_TASK(task_client) { - - char outbuf = 'q'; - char inbuf[3] = {0}; - int pingResult; - - for(int i = 50; i <= 200; i+= 50) { - pingResult = csp_ping(MY_ADDRESS, 1000, 100, CSP_O_NONE); - printf("Ping with payload of %d bytes, took %d ms\n", i, pingResult); - csp_sleep_ms(1000); - } - csp_ps(MY_ADDRESS, 1000); - csp_sleep_ms(1000); - csp_memfree(MY_ADDRESS, 1000); - csp_sleep_ms(1000); - csp_buf_free(MY_ADDRESS, 1000); - csp_sleep_ms(1000); - csp_uptime(MY_ADDRESS, 1000); - csp_sleep_ms(1000); - - csp_transaction(0, MY_ADDRESS, PORT, 1000, &outbuf, 1, inbuf, 2); - printf("Quit response from server: %s\n", inbuf); - - return CSP_TASK_RETURN; -} - -int main(int argc, char **argv) { - csp_debug_toggle_level(CSP_PACKET); - csp_debug_toggle_level(CSP_INFO); - - csp_buffer_init(10, 300); - csp_init(MY_ADDRESS); - - struct usart_conf conf; - -#if defined(CSP_WINDOWS) - conf.device = argc != 2 ? "COM4" : argv[1]; - conf.baudrate = CBR_9600; - conf.databits = 8; - conf.paritysetting = NOPARITY; - conf.stopbits = ONESTOPBIT; - conf.checkparity = FALSE; -#elif defined(CSP_POSIX) - conf.device = argc != 2 ? "/dev/ttyUSB0" : argv[1]; - conf.baudrate = 500000; -#elif defined(CSP_MACOSX) - conf.device = argc != 2 ? "/dev/tty.usbserial-FTSM9EGE" : argv[1]; - conf.baudrate = 115200; -#endif - - /* Run USART init */ - usart_init(&conf); - - /* Setup CSP interface */ - static csp_iface_t csp_if_kiss; - static csp_kiss_handle_t csp_kiss_driver; - csp_kiss_init(&csp_if_kiss, &csp_kiss_driver, usart_putc, usart_insert, "KISS"); - - /* Setup callback from USART RX to KISS RS */ - void my_usart_rx(uint8_t * buf, int len, void * pxTaskWoken) { - csp_kiss_rx(&csp_if_kiss, buf, len, pxTaskWoken); - } - usart_set_callback(my_usart_rx); - - csp_route_set(MY_ADDRESS, &csp_if_kiss, CSP_NODE_MAC); - csp_route_start_task(0, 0); - - csp_conn_print_table(); - csp_route_print_table(); - csp_route_print_interfaces(); - - csp_thread_handle_t handle_server; - csp_thread_create(task_server, "SERVER", 1000, NULL, 0, &handle_server); - csp_thread_handle_t handle_client; - csp_thread_create(task_client, "CLIENT", 1000, NULL, 0, &handle_client); - - /* Wait for program to terminate (ctrl + c) */ - while(1) { - csp_sleep_ms(1000000); - } - - return 0; - -} diff --git a/libcsp/examples/python_bindings_example_client.py b/libcsp/examples/python_bindings_example_client.py deleted file mode 100644 index 123ce36e..00000000 --- a/libcsp/examples/python_bindings_example_client.py +++ /dev/null @@ -1,42 +0,0 @@ -#!/usr/bin/python - -# libcsp must be build with at least these options to run this example client: -# ./waf distclean configure build --enable-bindings --enable-crc32 --enable-rdp --enable-if-zmq --with-driver-usart=linux --enable-if-kiss --enable-xtea --enable-if-can --enable-can-socketcan --enable-hmac --enable-examples - -# Can be run from root of libcsp like this: -# LD_LIBRARY_PATH=build PYTHONPATH=bindings/python:build python examples/python_bindings_example_client.py -# - -import os -import time -import libcsp as csp - - -if __name__ == "__main__": - - csp.buffer_init(10, 300) - csp.init(28) - csp.zmqhub_init(28, "localhost") - csp.rtable_set(27, 5, "ZMQHUB") - csp.route_start_task() - - ## allow router task startup - time.sleep(1) - - ## cmp_ident - (rc, host, model, rev, date, time) = csp.cmp_ident(27) - if rc == csp.CSP_ERR_NONE: - print (host, model, rev, date, time) - else: - print ("error in cmp_ident, rc=%i" % (rc)) - - ## transaction - outbuf = bytearray().fromhex('01') - inbuf = bytearray(1) - print ("using csp_transaction to send a single byte") - if csp.transaction(0, 27, 10, 1000, outbuf, inbuf) < 1: - print ("csp_transaction failed") - else: - print ("got reply, data=" + ''.join('{:02x}'.format(x) for x in inbuf)) - - diff --git a/libcsp/examples/python_bindings_example_client_can.py b/libcsp/examples/python_bindings_example_client_can.py deleted file mode 100644 index ec796572..00000000 --- a/libcsp/examples/python_bindings_example_client_can.py +++ /dev/null @@ -1,30 +0,0 @@ -#!/usr/bin/python - -# libcsp must be build with at least these options to run this example client: -# ./waf distclean configure build --enable-bindings --enable-crc32 --enable-rdp --enable-if-zmq --with-driver-usart=linux --enable-if-kiss --enable-xtea --enable-if-can --enable-can-socketcan --enable-hmac --enable-examples - -# Can be run from root of libcsp like this: -# LD_LIBRARY_PATH=build PYTHONPATH=bindings/python:build python examples/python_bindings_example_client.py -# - -import os -import time -import libcsp as csp - - -if __name__ == "__main__": - - csp.buffer_init(10, 300) - csp.init(28) - csp.can_socketcan_init("can0") - csp.rtable_set(4, 5, "CAN") - csp.route_start_task() - - ## allow router task startup - time.sleep(1) - - - node = 4 - if csp.ping(node) < 0: - print ("Unable to ping node %d"%(node)) - diff --git a/libcsp/examples/python_bindings_example_server.py b/libcsp/examples/python_bindings_example_server.py deleted file mode 100644 index 3cf3f5da..00000000 --- a/libcsp/examples/python_bindings_example_server.py +++ /dev/null @@ -1,72 +0,0 @@ -#!/usr/bin/python - -# libcsp must be build with at least these options to run this example server: -# ./waf distclean configure build --enable-bindings --enable-crc32 --enable-rdp --enable-if-zmq --with-driver-usart=linux --enable-if-kiss --enable-xtea --enable-if-can --enable-can-socketcan --enable-hmac --enable-examples - -# Can be run from root of libcsp like this: -# LD_LIBRARY_PATH=build PYTHONPATH=bindings/python:build python examples/python_bindings_example_server.py -# - -import os -import time -import sys -import libcsp as csp -import subprocess - -if __name__ == "__main__": - - # start a zmqproxy to transport messages to and from the client - zmqp = subprocess.Popen('build/zmqproxy') - - # init csp - csp.buffer_init(10, 300) - csp.init(27) - csp.zmqhub_init(27, "localhost") - csp.rtable_set(28, 5, "ZMQHUB") - csp.route_start_task() - - # set identity - csp.set_hostname("test_service") - csp.set_model("bindings") - csp.set_revision("1.2.3") - - # and read it back - print (csp.get_hostname()) - print (csp.get_model()) - print (csp.get_revision()) - - # start listening for packets... - sock = csp.socket() - csp.bind(sock, csp.CSP_ANY) - csp.listen(sock) - while True: - conn = csp.accept(sock) - if not conn: - continue - - print ("connection: source=%i:%i, dest=%i:%i" % (csp.conn_src(conn), - csp.conn_sport(conn), - csp.conn_dst(conn), - csp.conn_dport(conn))) - - while True: - packet = csp.read(conn) - if not packet: - break - - if csp.conn_dport(conn) == 10: - data = bytearray(csp.packet_get_data(packet)) - length = csp.packet_get_length(packet) - print ("got packet, len=" + str(length) + ", data=" + ''.join('{:02x}'.format(x) for x in data)) - - data[0] = data[0] + 1 - reply_packet = csp.buffer_get(1) - if reply_packet: - csp.packet_set_data(reply_packet, data) - csp.sendto_reply(packet, reply_packet, csp.CSP_O_NONE) - - csp.buffer_free(packet) - else: - csp.service_handler(conn, packet) - csp.close(conn) - diff --git a/libcsp/examples/simple.c b/libcsp/examples/simple.c deleted file mode 100644 index b996f8c1..00000000 --- a/libcsp/examples/simple.c +++ /dev/null @@ -1,200 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include -#include -#include - -#include - -/* Using un-exported header file. - * This is allowed since we are still in libcsp */ -#include - -/** Example defines */ -#define MY_ADDRESS 1 // Address of local CSP node -#define MY_PORT 10 // Port to send test traffic to - -CSP_DEFINE_TASK(task_server) { - - /* Create socket without any socket options */ - csp_socket_t *sock = csp_socket(CSP_SO_NONE); - - /* Bind all ports to socket */ - csp_bind(sock, CSP_ANY); - - /* Create 10 connections backlog queue */ - csp_listen(sock, 10); - - /* Pointer to current connection and packet */ - csp_conn_t *conn; - csp_packet_t *packet; - - /* Process incoming connections */ - while (1) { - - /* Wait for connection, 10000 ms timeout */ - if ((conn = csp_accept(sock, 10000)) == NULL) - continue; - - /* Read packets. Timout is 100 ms */ - while ((packet = csp_read(conn, 100)) != NULL) { - switch (csp_conn_dport(conn)) { - case MY_PORT: - /* Process packet here */ - printf("Packet received on MY_PORT: %s\r\n", (char *) packet->data); - csp_buffer_free(packet); - break; - - default: - /* Let the service handler reply pings, buffer use, etc. */ - csp_service_handler(conn, packet); - break; - } - } - - /* Close current connection, and handle next */ - csp_close(conn); - - } - - return CSP_TASK_RETURN; - -} - -CSP_DEFINE_TASK(task_client) { - - csp_packet_t * packet; - csp_conn_t * conn; - - while (1) { - - /** - * Try ping - */ - - csp_sleep_ms(1000); - - int result = csp_ping(MY_ADDRESS, 100, 100, CSP_O_NONE); - printf("Ping result %d [ms]\r\n", result); - - csp_sleep_ms(1000); - - /** - * Try data packet to server - */ - - /* Get packet buffer for data */ - packet = csp_buffer_get(100); - if (packet == NULL) { - /* Could not get buffer element */ - printf("Failed to get buffer element\n"); - return CSP_TASK_RETURN; - } - - /* Connect to host HOST, port PORT with regular UDP-like protocol and 1000 ms timeout */ - conn = csp_connect(CSP_PRIO_NORM, MY_ADDRESS, MY_PORT, 1000, CSP_O_NONE); - if (conn == NULL) { - /* Connect failed */ - printf("Connection failed\n"); - /* Remember to free packet buffer */ - csp_buffer_free(packet); - return CSP_TASK_RETURN; - } - - /* Copy dummy data to packet */ - const char *msg = "Hello World"; - strcpy((char *) packet->data, msg); - - /* Set packet length */ - packet->length = strlen(msg); - - /* Send packet */ - if (!csp_send(conn, packet, 1000)) { - /* Send failed */ - printf("Send failed\n"); - csp_buffer_free(packet); - } - - /* Close connection */ - csp_close(conn); - - } - - return CSP_TASK_RETURN; -} - -int main(int argc, char * argv[]) { - - /** - * Initialise CSP, - * No physical interfaces are initialised in this example, - * so only the loopback interface is registered. - */ - - /* Init buffer system with 10 packets of maximum 300 bytes each */ - printf("Initialising CSP\r\n"); - csp_buffer_init(5, 300); - - /* Init CSP with address MY_ADDRESS */ - csp_init(MY_ADDRESS); - - /* Start router task with 500 word stack, OS task priority 1 */ - csp_route_start_task(500, 1); - - /* Enable debug output from CSP */ - if ((argc > 1) && (strcmp(argv[1], "-v") == 0)) { - printf("Debug enabed\r\n"); - csp_debug_toggle_level(3); - csp_debug_toggle_level(4); - - printf("Conn table\r\n"); - csp_conn_print_table(); - - printf("Route table\r\n"); - csp_route_print_table(); - - printf("Interfaces\r\n"); - csp_route_print_interfaces(); - - } - - /** - * Initialise example threads, using pthreads. - */ - - /* Server */ - printf("Starting Server task\r\n"); - csp_thread_handle_t handle_server; - csp_thread_create(task_server, "SERVER", 1000, NULL, 0, &handle_server); - - /* Client */ - printf("Starting Client task\r\n"); - csp_thread_handle_t handle_client; - csp_thread_create(task_client, "SERVER", 1000, NULL, 0, &handle_client); - - /* Wait for execution to end (ctrl+c) */ - while(1) { - csp_sleep_ms(100000); - } - - return 0; - -} diff --git a/libcsp/examples/zmqproxy.c b/libcsp/examples/zmqproxy.c deleted file mode 100644 index 5e259579..00000000 --- a/libcsp/examples/zmqproxy.c +++ /dev/null @@ -1,82 +0,0 @@ -#include -#include -#include -#include -#include -#include -#include - -static void * task_capture(void *ctx) { - - /* Subscriber (RX) */ - void *subscriber = zmq_socket(ctx, ZMQ_SUB); - assert(zmq_connect(subscriber, "tcp://localhost:7000") == 0); - assert(zmq_setsockopt(subscriber, ZMQ_SUBSCRIBE, "", 0) == 0); - - while (1) { - zmq_msg_t msg; - zmq_msg_init_size(&msg, 1024); - - /* Receive data */ - if (zmq_msg_recv(&msg, subscriber, 0) < 0) { - zmq_msg_close(&msg); - csp_log_error("ZMQ: %s\r\n", zmq_strerror(zmq_errno())); - continue; - } - - int datalen = zmq_msg_size(&msg); - if (datalen < 5) { - csp_log_warn("ZMQ: Too short datalen: %u\r\n", datalen); - while(zmq_msg_recv(&msg, subscriber, ZMQ_NOBLOCK) > 0) - zmq_msg_close(&msg); - continue; - } - - /* Create new csp packet */ - csp_packet_t * packet = malloc(1024); - if (packet == NULL) { - zmq_msg_close(&msg); - continue; - } - - /* Copy the data from zmq to csp */ - char * satidptr = ((char *) &packet->id) - 1; - memcpy(satidptr, zmq_msg_data(&msg), datalen); - packet->length = datalen - 4 - 1; - - printf("Input: Src %u, Dst %u, Dport %u, Sport %u, Pri %u, Flags 0x%02X, Size %"PRIu16"\r\n", - packet->id.src, packet->id.dst, packet->id.dport, - packet->id.sport, packet->id.pri, packet->id.flags, packet->length); - - free(packet); - zmq_msg_close(&msg); - } -} - -int main(int argc, char ** argv) { - - /** - * ZMQ PROXY - */ - void * ctx = zmq_ctx_new(); - assert(ctx); - - void *frontend = zmq_socket(ctx, ZMQ_XSUB); - assert(frontend); - assert(zmq_bind (frontend, "tcp://*:6000") == 0); - - void *backend = zmq_socket(ctx, ZMQ_XPUB); - assert(backend); - assert(zmq_bind(backend, "tcp://*:7000") == 0); - - pthread_t capworker; - pthread_create(&capworker, NULL, task_capture, ctx); - - printf("Starting ZMQproxy\r\n"); - zmq_proxy(frontend, backend, NULL); - - printf("Closing ZMQproxy\r\n"); - zmq_ctx_destroy(ctx); - return 0; - -} diff --git a/libcsp/include/CMakeLists.txt b/libcsp/include/CMakeLists.txt deleted file mode 100644 index 196e26f3..00000000 --- a/libcsp/include/CMakeLists.txt +++ /dev/null @@ -1,9 +0,0 @@ -target_include_directories(${LIB_CSP_NAME} PRIVATE - ${CMAKE_CURRENT_SOURCE_DIR} -) - -target_include_directories(${LIB_CSP_NAME} INTERFACE - ${CMAKE_CURRENT_SOURCE_DIR} -) - - diff --git a/libcsp/include/csp/arch/csp_clock.h b/libcsp/include/csp/arch/csp_clock.h deleted file mode 100644 index 3c19c887..00000000 --- a/libcsp/include/csp/arch/csp_clock.h +++ /dev/null @@ -1,60 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#ifndef _CSP_CLOCK_H_ -#define _CSP_CLOCK_H_ - -/** - @file - - Clock API. -*/ - -#ifdef __cplusplus -extern "C" { -#endif - -#include - -/** - Cross-platform timestamp. -*/ -typedef struct { - //! Seconds - uint32_t tv_sec; - //! Nano-seconds. - uint32_t tv_nsec; -} csp_timestamp_t; - -/** - Get time - must be implemented by the user. -*/ -__attribute__((weak)) extern void clock_get_time(csp_timestamp_t * time); - -/** - Set time - must be implemented by the user. -*/ -__attribute__((weak)) extern void clock_set_time(csp_timestamp_t * time); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // _CSP_CLOCK_H_ diff --git a/libcsp/include/csp/arch/csp_malloc.h b/libcsp/include/csp/arch/csp_malloc.h deleted file mode 100644 index 12602d1b..00000000 --- a/libcsp/include/csp/arch/csp_malloc.h +++ /dev/null @@ -1,39 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#ifndef _CSP_MALLOC_H_ -#define _CSP_MALLOC_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include -#include -#include - -void * csp_malloc(size_t size); -void csp_free(void * ptr); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // _CSP_MALLOC_H_ diff --git a/libcsp/include/csp/arch/csp_queue.h b/libcsp/include/csp/arch/csp_queue.h deleted file mode 100644 index 3156c05e..00000000 --- a/libcsp/include/csp/arch/csp_queue.h +++ /dev/null @@ -1,49 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#ifndef _CSP_QUEUE_H_ -#define _CSP_QUEUE_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#define CSP_QUEUE_FULL 0 -#define CSP_QUEUE_ERROR 0 -#define CSP_QUEUE_OK 1 -typedef void * csp_queue_handle_t; - -#include -#include - -csp_queue_handle_t csp_queue_create(int length, size_t item_size); -void csp_queue_remove(csp_queue_handle_t queue); -int csp_queue_enqueue(csp_queue_handle_t handle, void *value, uint32_t timeout); -int csp_queue_enqueue_isr(csp_queue_handle_t handle, void * value, CSP_BASE_TYPE * task_woken); -int csp_queue_dequeue(csp_queue_handle_t handle, void *buf, uint32_t timeout); -int csp_queue_dequeue_isr(csp_queue_handle_t handle, void * buf, CSP_BASE_TYPE * task_woken); -int csp_queue_size(csp_queue_handle_t handle); -int csp_queue_size_isr(csp_queue_handle_t handle); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // _CSP_QUEUE_H_ diff --git a/libcsp/include/csp/arch/csp_semaphore.h b/libcsp/include/csp/arch/csp_semaphore.h deleted file mode 100644 index c8068da2..00000000 --- a/libcsp/include/csp/arch/csp_semaphore.h +++ /dev/null @@ -1,109 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#ifndef _CSP_SEMAPHORE_H_ -#define _CSP_SEMAPHORE_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include - -#include - -/* POSIX interface */ -#if defined(CSP_POSIX) - -#include -#include - -#define CSP_SEMAPHORE_OK 1 -#define CSP_SEMAPHORE_ERROR 2 -#define CSP_MUTEX_OK CSP_SEMAPHORE_OK -#define CSP_MUTEX_ERROR CSP_SEMAPHORE_ERROR - -typedef sem_t csp_bin_sem_handle_t; -typedef pthread_mutex_t csp_mutex_t; - -#endif // CSP_POSIX - -/* MAC OS X interface */ -#if defined(CSP_MACOSX) - -#include -#include "posix/pthread_queue.h" - -#define CSP_SEMAPHORE_OK PTHREAD_QUEUE_OK -#define CSP_SEMAPHORE_ERROR PTHREAD_QUEUE_EMPTY -#define CSP_MUTEX_OK CSP_SEMAPHORE_OK -#define CSP_MUTEX_ERROR CSP_SEMAPHORE_ERROR - -typedef pthread_queue_t * csp_bin_sem_handle_t; -typedef pthread_queue_t * csp_mutex_t; - -#endif // CSP_MACOSX - -#if defined(CSP_WINDOWS) - -#include -#undef interface - -#define CSP_SEMAPHORE_OK 1 -#define CSP_SEMAPHORE_ERROR 2 -#define CSP_MUTEX_OK CSP_SEMAPHORE_OK -#define CSP_MUTEX_ERROR CSP_SEMAPHORE_ERROR - -typedef HANDLE csp_bin_sem_handle_t; -typedef HANDLE csp_mutex_t; - -#endif - -/* FreeRTOS interface */ -#if defined(CSP_FREERTOS) - -#include -#include - -#define CSP_SEMAPHORE_OK pdPASS -#define CSP_SEMAPHORE_ERROR pdFAIL -#define CSP_MUTEX_OK CSP_SEMAPHORE_OK -#define CSP_MUTEX_ERROR CSP_SEMAPHORE_ERROR - -typedef xSemaphoreHandle csp_bin_sem_handle_t; -typedef xSemaphoreHandle csp_mutex_t; - -#endif // CSP_FREERTOS - -int csp_mutex_create(csp_mutex_t * mutex); -int csp_mutex_remove(csp_mutex_t * mutex); -int csp_mutex_lock(csp_mutex_t * mutex, uint32_t timeout); -int csp_mutex_unlock(csp_mutex_t * mutex); -int csp_bin_sem_create(csp_bin_sem_handle_t * sem); -int csp_bin_sem_remove(csp_bin_sem_handle_t * sem); -int csp_bin_sem_wait(csp_bin_sem_handle_t * sem, uint32_t timeout); -int csp_bin_sem_post(csp_bin_sem_handle_t * sem); -int csp_bin_sem_post_isr(csp_bin_sem_handle_t * sem, CSP_BASE_TYPE * task_woken); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // _CSP_SEMAPHORE_H_ diff --git a/libcsp/include/csp/arch/csp_system.h b/libcsp/include/csp/arch/csp_system.h deleted file mode 100644 index c6c0e5af..00000000 --- a/libcsp/include/csp/arch/csp_system.h +++ /dev/null @@ -1,74 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#ifndef _CSP_SYSTEM_H_ -#define _CSP_SYSTEM_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include - -#define COLOR_MASK_COLOR 0x0F -#define COLOR_MASK_MODIFIER 0xF0 - -typedef enum { - /* Colors */ - COLOR_RESET = 0xF0, - COLOR_BLACK = 0x01, - COLOR_RED = 0x02, - COLOR_GREEN = 0x03, - COLOR_YELLOW = 0x04, - COLOR_BLUE = 0x05, - COLOR_MAGENTA = 0x06, - COLOR_CYAN = 0x07, - COLOR_WHITE = 0x08, - /* Modifiers */ - COLOR_NORMAL = 0x0F, - COLOR_BOLD = 0x10, - COLOR_UNDERLINE = 0x20, - COLOR_BLINK = 0x30, - COLOR_HIDE = 0x40, -} csp_color_t; - -/** - * Writes out a task list into a pre-allocate buffer, - * use csp_sys_tasklist_size to get sizeof buffer to allocate - * @param out pointer to output buffer - * @return - */ -int csp_sys_tasklist(char * out); - -/** - * @return Size of tasklist buffer to allocate for the csp_sys_tasklist call - */ -int csp_sys_tasklist_size(void); - -uint32_t csp_sys_memfree(void); -int csp_sys_reboot(void); -int csp_sys_shutdown(void); -void csp_sys_set_color(csp_color_t color); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // _CSP_SYSTEM_H_ diff --git a/libcsp/include/csp/arch/csp_thread.h b/libcsp/include/csp/arch/csp_thread.h deleted file mode 100644 index 3c6ea171..00000000 --- a/libcsp/include/csp/arch/csp_thread.h +++ /dev/null @@ -1,100 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#ifndef _CSP_THREAD_H_ -#define _CSP_THREAD_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include -#include - -/* POSIX interface */ -#if defined(CSP_POSIX) || defined(CSP_MACOSX) - -#include -#include - -#define csp_thread_exit() pthread_exit(NULL) - -typedef pthread_t csp_thread_handle_t; -typedef void * csp_thread_return_t; - -#define CSP_DEFINE_TASK(task_name) csp_thread_return_t task_name(void * param) -#define CSP_TASK_RETURN NULL - -#define csp_sleep_ms(time_ms) usleep(time_ms * 1000); - -#endif // CSP_POSIX - -/* Windows interface */ -#if defined(CSP_WINDOWS) - -#include -#undef interface -#include - -#define csp_thread_exit() _endthreadex(0) - -typedef HANDLE csp_thread_handle_t; -typedef unsigned int csp_thread_return_t; - -#define CSP_DEFINE_TASK(task_name) csp_thread_return_t __attribute__((stdcall)) task_name(void * param) -#define CSP_TASK_RETURN 0 - -#define csp_sleep_ms(time_ms) Sleep(time_ms); - -#endif // CSP_WINDOWS - -/* FreeRTOS interface */ -#if defined(CSP_FREERTOS) - -#include -#include - -#if INCLUDE_vTaskDelete -#define csp_thread_exit() vTaskDelete(NULL) -#else -#define csp_thread_exit() -#endif - -typedef xTaskHandle csp_thread_handle_t; -typedef void csp_thread_return_t; - -#define CSP_DEFINE_TASK(task_name) csp_thread_return_t task_name(void * param) -#define CSP_TASK_RETURN - -#define csp_sleep_ms(time_ms) vTaskDelay(time_ms / portTICK_RATE_MS); - -#endif // CSP_FREERTOS - -#ifndef CSP_WINDOWS -int csp_thread_create(csp_thread_return_t (* routine)(void *), const char * const thread_name, unsigned short stack_depth, void * parameters, unsigned int priority, csp_thread_handle_t * handle); -#else -int csp_thread_create(csp_thread_return_t (* routine)(void *)__attribute__((stdcall)), const char * const thread_name, unsigned short stack_depth, void * parameters, unsigned int priority, csp_thread_handle_t * handle); -#endif - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // _CSP_THREAD_H_ diff --git a/libcsp/include/csp/arch/csp_time.h b/libcsp/include/csp/arch/csp_time.h deleted file mode 100644 index aa72ab8f..00000000 --- a/libcsp/include/csp/arch/csp_time.h +++ /dev/null @@ -1,57 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#ifndef _CSP_TIME_H_ -#define _CSP_TIME_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include -#include - -/* Blackfin/x86 on Linux */ -#if defined(CSP_POSIX) - -#include -#include -#include - -#endif // CSP_POSIX - -/* AVR/ARM on FreeRTOS */ -#if defined(CSP_FREERTOS) - -#include -#include - -#endif // CSP_FREERTOS - -uint32_t csp_get_ms(void); -uint32_t csp_get_ms_isr(void); -uint32_t csp_get_s(void); -uint32_t csp_get_s_isr(void); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // _CSP_TIME_H_ diff --git a/libcsp/include/csp/arch/posix/pthread_queue.h b/libcsp/include/csp/arch/posix/pthread_queue.h deleted file mode 100644 index 44ef596e..00000000 --- a/libcsp/include/csp/arch/posix/pthread_queue.h +++ /dev/null @@ -1,118 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#ifndef _PTHREAD_QUEUE_H_ -#define _PTHREAD_QUEUE_H_ - -/** - @file - - Queue implemented using pthread locks and conds. - - Inspired by c-pthread-queue by Matthew Dickinson: http://code.google.com/p/c-pthread-queue/ -*/ - -#ifdef __cplusplus -extern "C" { -#endif - -#include -#include -#include - -#include - -/** - Queue error codes. - @{ -*/ -/** - General error code - something went wrong. -*/ -#define PTHREAD_QUEUE_ERROR CSP_QUEUE_ERROR -/** - Queue is empty - cannot extract element. -*/ -#define PTHREAD_QUEUE_EMPTY CSP_QUEUE_ERROR -/** - Queue is full - cannot insert element. -*/ -#define PTHREAD_QUEUE_FULL CSP_QUEUE_ERROR -/** - Ok - no error. -*/ -#define PTHREAD_QUEUE_OK CSP_QUEUE_OK -/** @{ */ - -/** - Queue handle. -*/ -typedef struct pthread_queue_s { - //! Memory area. - void * buffer; - //! Memory size. - int size; - //! Item/element size. - int item_size; - //! Items/elements in queue. - int items; - //! Insert point. - int in; - //! Extract point. - int out; - //! Lock. - pthread_mutex_t mutex; - //! Wait because queue is full (insert). - pthread_cond_t cond_full; - //! Wait because queue is empty (extract). - pthread_cond_t cond_empty; -} pthread_queue_t; - -/** - Create queue. -*/ -pthread_queue_t * pthread_queue_create(int length, size_t item_size); - -/** - Delete queue. -*/ -void pthread_queue_delete(pthread_queue_t * q); - -/** - Enqueue/insert element. -*/ -int pthread_queue_enqueue(pthread_queue_t * queue, void * value, uint32_t timeout); - -/** - Dequeue/extract element. -*/ -int pthread_queue_dequeue(pthread_queue_t * queue, void * buf, uint32_t timeout); - -/** - Return number of elements in the queue. -*/ -int pthread_queue_items(pthread_queue_t * queue); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // _PTHREAD_QUEUE_H_ - diff --git a/libcsp/include/csp/crypto/csp_hmac.h b/libcsp/include/csp/crypto/csp_hmac.h deleted file mode 100644 index 8c3f5d6a..00000000 --- a/libcsp/include/csp/crypto/csp_hmac.h +++ /dev/null @@ -1,73 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#ifndef _CSP_HMAC_H_ -#define _CSP_HMAC_H_ - -#include - -#ifdef __cplusplus -extern "C" { -#endif - -#define CSP_HMAC_LENGTH 4 - -/** - * Append HMAC to packet - * @param packet Pointer to packet - * @param include_header use header in hmac calculation (this will not modify the flags field) - * @return 0 on success, negative on failure - */ -int csp_hmac_append(csp_packet_t * packet, bool include_header); - -/** - * Verify HMAC of packet - * @param packet Pointer to packet - * @param include_header use header in hmac calculation (this will not modify the flags field) - * @return 0 on success, negative on failure - */ -int csp_hmac_verify(csp_packet_t * packet, bool include_header); - -/** - * Calculate HMAC on buffer - * - * This function is used by append/verify but cal also be called separately. - * @param key HMAC key - * @param keylen HMAC key length - * @param data pointer to data - * @param datalen lehgth of data - * @param hmac output HMAC calculation (CSP_HMAC_LENGTH) - * @return 0 on success, negative on failure - */ -int csp_hmac_memory(const uint8_t * key, uint32_t keylen, const uint8_t * data, uint32_t datalen, uint8_t * hmac); - -/** - * Save a copy of the key string for use by the append/verify functions - * @param key HMAC key - * @param keylen HMAC key length - * @return Always returns 0 - */ -int csp_hmac_set_key(char * key, uint32_t keylen); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // _CSP_HMAC_H_ diff --git a/libcsp/include/csp/crypto/csp_sha1.h b/libcsp/include/csp/crypto/csp_sha1.h deleted file mode 100644 index aa7e7a0d..00000000 --- a/libcsp/include/csp/crypto/csp_sha1.h +++ /dev/null @@ -1,81 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#ifndef _CSP_SHA1_H_ -#define _CSP_SHA1_H_ - -#include - -#ifdef __cplusplus -extern "C" { -#endif - -/* The SHA1 block and message digest size in bytes */ -#define SHA1_BLOCKSIZE 64 -#define SHA1_DIGESTSIZE 20 - -/** - SHA1 state structure -*/ -typedef struct { - //! Internal SHA1 state. - uint64_t length; - //! Internal SHA1 state. - uint32_t state[5]; - //! Internal SHA1 state. - uint32_t curlen; - //! Internal SHA1 state. - uint8_t buf[SHA1_BLOCKSIZE]; -} csp_sha1_state; - -/** - * Initialize the hash state - * @param sha1 The hash state you wish to initialize - */ -void csp_sha1_init(csp_sha1_state * sha1); - -/** - * Process a block of memory though the hash - * @param sha1 The hash state - * @param in The data to hash - * @param inlen The length of the data (octets) - */ -void csp_sha1_process(csp_sha1_state * sha1, const uint8_t * in, uint32_t inlen); - -/** - * Terminate the hash to get the digest - * @param sha1 The hash state - * @param out [out] The destination of the hash (20 bytes) - */ -void csp_sha1_done(csp_sha1_state * sha1, uint8_t * out); - -/** - * Calculate SHA1 hash of block of memory. - * @param msg Pointer to message buffer - * @param len Length of message - * @param sha1 Pointer to SHA1 output buffer. Must be 20 bytes or more! - */ -void csp_sha1_memory(const uint8_t * msg, uint32_t len, uint8_t * hash); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // _CSP_SHA1_H_ diff --git a/libcsp/include/csp/crypto/csp_xtea.h b/libcsp/include/csp/crypto/csp_xtea.h deleted file mode 100644 index f740b8d5..00000000 --- a/libcsp/include/csp/crypto/csp_xtea.h +++ /dev/null @@ -1,52 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#ifndef _CSP_XTEA_H_ -#define _CSP_XTEA_H_ - -#include - -#ifdef __cplusplus -extern "C" { -#endif - -#define CSP_XTEA_IV_LENGTH 8 - -/** - * XTEA encrypt byte array - * @param plain Pointer to plain text - * @param len Length of plain text - * @param iv Initialization vector - */ -int csp_xtea_encrypt(uint8_t * plain, const uint32_t len, uint32_t iv[2]); - -/** - * Decrypt XTEA encrypted byte array - * @param cipher Pointer to cipher text - * @param len Length of plain text - * @param iv Initialization vector - */ -int csp_xtea_decrypt(uint8_t * cipher, const uint32_t len, uint32_t iv[2]); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // _CSP_XTEA_H_ diff --git a/libcsp/include/csp/csp.h b/libcsp/include/csp/csp.h deleted file mode 100644 index 6962195b..00000000 --- a/libcsp/include/csp/csp.h +++ /dev/null @@ -1,545 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#ifndef _CSP_H_ -#define _CSP_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes */ -#include - -#include - -/* CSP includes */ -#include "csp_types.h" -#include "csp_platform.h" -#include "csp_error.h" -#include "csp_debug.h" -#include "csp_buffer.h" -#include "csp_rtable.h" -#include "csp_iflist.h" - -/** csp_init - * Start up the can-space protocol - * @param my_node_address The CSP node address - */ -int csp_init(uint8_t my_node_address); - -/** csp_set_address - * Set the systems own address - * @param addr The new address of the system - */ -void csp_set_address(uint8_t addr); - -/** csp_get_address - * Get the systems own address - * @return The current address of the system - */ -uint8_t csp_get_address(void); - -/** csp_set_hostname - * Set subsystem hostname. - * This function takes a pointer to a string, which should remain static - * @param hostname Hostname to set - */ -void csp_set_hostname(const char *hostname); - -/** csp_get_hostname - * Get current subsystem hostname. - * @return Pointer to char array with current hostname. - */ -const char *csp_get_hostname(void); - -/** csp_set_model - * Set subsystem model name. - * This function takes a pointer to a string, which should remain static - * @param model Model name to set - */ -void csp_set_model(const char *model); - -/** csp_get_model - * Get current model name. - * @return Pointer to char array with current model name. - */ -const char *csp_get_model(void); - -/** csp_set_revision - * Set subsystem revision. This can be used to override the CMP revision field. - * This function takes a pointer to a string, which should remain static - * @param revision Revision name to set - */ -void csp_set_revision(const char *revision); - -/** csp_get_revision - * Get subsystem revision. - * @return Pointer to char array with software revision. - */ -const char *csp_get_revision(void); - -/** csp_socket - * Create CSP socket endpoint - * @param opts Socket options - * @return Pointer to socket on success, NULL on failure - */ -csp_socket_t *csp_socket(uint32_t opts); - -/** - * Wait for a new connection on a socket created by csp_socket - * @param socket Socket to accept connections on - * @param timeout use CSP_MAX_DELAY for infinite timeout - * @return Return pointer to csp_conn_t or NULL if timeout was reached - */ -csp_conn_t *csp_accept(csp_socket_t *socket, uint32_t timeout); - -/** - * Read data from a connection - * This fuction uses the RX queue of a connection to receive a packet - * If no packet is available and a timeout has been specified - * The call will block. - * Do NOT call this from ISR - * @param conn pointer to connection - * @param timeout timeout in ms, use CSP_MAX_DELAY for infinite blocking time - * @return Returns pointer to csp_packet_t, which you MUST free yourself, either by calling csp_buffer_free() or reusing the buffer for a new csp_send. - */ -csp_packet_t *csp_read(csp_conn_t *conn, uint32_t timeout); - -/** - * Send a packet on an already established connection - * @param conn pointer to connection - * @param packet pointer to packet, - * @param timeout a timeout to wait for TX to complete. NOTE: not all underlying drivers supports flow-control. - * @return returns 1 if successful and 0 otherwise. you MUST free the frame yourself if the transmission was not successful. - */ -int csp_send(csp_conn_t *conn, csp_packet_t *packet, uint32_t timeout); - -/** - * Send a packet on an already established connection, and change the default priority of the connection - * - * @note When using this function, the priority of the connection will change. If you need to change it back - * use another call to csp_send_prio, or ensure that all packets sent on a given connection is using send_prio call. - * - * @param prio csp priority - * @param conn pointer to connection - * @param packet pointer to packet, - * @param timeout a timeout to wait for TX to complete. NOTE: not all underlying drivers supports flow-control. - * @return returns 1 if successful and 0 otherwise. you MUST free the frame yourself if the transmission was not successful. - */ -int csp_send_prio(uint8_t prio, csp_conn_t *conn, csp_packet_t *packet, uint32_t timeout); - -/** - * Perform an entire request/reply transaction - * Copies both input buffer and reply to output buffeer. - * Also makes the connection and closes it again - * @param prio CSP Prio - * @param dest CSP Dest - * @param port CSP Port - * @param timeout timeout in ms - * @param outbuf pointer to outgoing data buffer - * @param outlen length of request to send - * @param inbuf pointer to incoming data buffer - * @param inlen length of expected reply, -1 for unknown size (note inbuf MUST be large enough) - * @return Return 1 or reply size if successful, 0 if error or incoming length does not match or -1 if timeout was reached - */ -int csp_transaction(uint8_t prio, uint8_t dest, uint8_t port, uint32_t timeout, void *outbuf, int outlen, void *inbuf, int inlen); - -/** - * Perform an entire request/reply transaction - * Copies both input buffer and reply to output buffeer. - * Also makes the connection and closes it again - * @param prio CSP Prio - * @param dest CSP Dest - * @param port CSP Port - * @param timeout timeout in ms - * @param outbuf pointer to outgoing data buffer - * @param outlen length of request to send - * @param inbuf pointer to incoming data buffer - * @param inlen length of expected reply, -1 for unknown size (note inbuf MUST be large enough) - * @param opts Connection options. - * @return Return 1 or reply size if successful, 0 if error or incoming length does not match or -1 if timeout was reached - */ -int csp_transaction2(uint8_t prio, uint8_t dest, uint8_t port, uint32_t timeout, void *outbuf, int outlen, void *inbuf, int inlen, uint32_t opts); - -/** - * Use an existing connection to perform a transaction, - * This is only possible if the next packet is on the same port and destination! - * @param conn pointer to connection structure - * @param timeout timeout in ms - * @param outbuf pointer to outgoing data buffer - * @param outlen length of request to send - * @param inbuf pointer to incoming data buffer - * @param inlen length of expected reply, -1 for unknown size (note inbuf MUST be large enough) - * @return - */ -int csp_transaction_persistent(csp_conn_t *conn, uint32_t timeout, void *outbuf, int outlen, void *inbuf, int inlen); - -/** - * Read data from a connection-less server socket - * This fuction uses the socket directly to receive a frame - * If no packet is available and a timeout has been specified the call will block. - * Do NOT call this from ISR - * @return Returns pointer to csp_packet_t, which you MUST free yourself, either by calling csp_buffer_free() or reusing the buffer for a new csp_send. - */ -csp_packet_t *csp_recvfrom(csp_socket_t *socket, uint32_t timeout); - -/** - * Send a packet without previously opening a connection - * @param prio CSP_PRIO_x - * @param dest destination node - * @param dport destination port - * @param src_port source port - * @param opts CSP_O_x - * @param packet pointer to packet - * @param timeout timeout used by interfaces with blocking send - * @return -1 if error (you must free packet), 0 if OK (you must discard pointer) - */ -int csp_sendto(uint8_t prio, uint8_t dest, uint8_t dport, uint8_t src_port, uint32_t opts, csp_packet_t *packet, uint32_t timeout); - -/** - * Send a packet as a direct reply to the source of an incoming packet, - * but still without holding an entire connection - * @param request_packet pointer to packet to reply to - * @param reply_packet actual reply data - * @param opts CSP_O_x - * @param timeout timeout used by interfaces with blocking send - * @return -1 if error (you must free packet), 0 if OK (you must discard pointer) - */ -int csp_sendto_reply(csp_packet_t * request_packet, csp_packet_t * reply_packet, uint32_t opts, uint32_t timeout); - -/** csp_connect - * Used to establish outgoing connections - * This function searches the port table for free slots and finds an unused - * connection from the connection pool - * There is no handshake in the CSP protocol - * @param prio Connection priority. - * @param dest Destination address. - * @param dport Destination port. - * @param timeout Timeout in ms. - * @param opts Connection options. - * @return a pointer to a new connection or NULL - */ -csp_conn_t *csp_connect(uint8_t prio, uint8_t dest, uint8_t dport, uint32_t timeout, uint32_t opts); - -/** csp_close - * Closes a given connection and frees buffers used. - * @param conn pointer to connection structure - * @return CSP_ERR_NONE if connection was closed. Otherwise, an err code is returned. - */ -int csp_close(csp_conn_t *conn); - -/** - * @param conn pointer to connection structure - * @return destination port of an incoming connection - */ -int csp_conn_dport(csp_conn_t *conn); - -/** - * @param conn pointer to connection structure - * @return source port of an incoming connection - */ -int csp_conn_sport(csp_conn_t *conn); - -/** - * @param conn pointer to connection structure - * @return destination address of an incoming connection - */ -int csp_conn_dst(csp_conn_t *conn); - -/** - * @param conn pointer to connection structure - * @return source address of an incoming connection - */ -int csp_conn_src(csp_conn_t *conn); - -/** - * @param conn pointer to connection structure - * @return flags field of an incoming connection - */ -int csp_conn_flags(csp_conn_t *conn); - -/** - * Set socket to listen for incoming connections - * @param socket Socket to enable listening on - * @param conn_queue_length Lenght of backlog connection queue - * @return 0 on success, -1 on error. - */ -int csp_listen(csp_socket_t *socket, size_t conn_queue_length); - -/** - * Bind port to socket - * @param socket Socket to bind port to - * @param port Port number to bind - * @return 0 on success, -1 on error. - */ -int csp_bind(csp_socket_t *socket, uint8_t port); - -/** - * Start the router task. - * @param task_stack_size The number of portStackType to allocate. This only affects FreeRTOS systems. - * @param priority The OS task priority of the router - */ -int csp_route_start_task(unsigned int task_stack_size, unsigned int priority); - -/** - * Call the router worker function manually (without the router task) - * This must be run inside a loop or called periodically for the csp router to work. - * Use this function instead of calling and starting the router task. - * @param timeout max blocking time - * @return -1 if no packet was processed, 0 otherwise - */ -int csp_route_work(uint32_t timeout); - -/** - * Start the bridge task. - * @param task_stack_size The number of portStackType to allocate. This only affects FreeRTOS systems. - * @param priority The OS task priority of the router - * @param _if_a pointer to first side - * @param _if_b pointer to second side - * @return CSP_ERR type - */ -int csp_bridge_start(unsigned int task_stack_size, unsigned int task_priority, csp_iface_t * _if_a, csp_iface_t * _if_b); - -/** - * Enable promiscuous mode packet queue - * This function is used to enable promiscuous mode for the router. - * If enabled, a copy of all incoming packets are placed in a queue - * that can be read with csp_promisc_get(). Not all interface drivers - * support promiscuous mode. - * - * @param buf_size Size of buffer for incoming packets - */ -int csp_promisc_enable(unsigned int buf_size); - -/** - * Disable promiscuous mode. - * If the queue was initialised prior to this, it can be re-enabled - * by calling promisc_enable(0) - */ -void csp_promisc_disable(void); - -/** - * Get packet from promiscuous mode packet queue - * Returns the first packet from the promiscuous mode packet queue. - * The queue is FIFO, so the returned packet is the oldest one - * in the queue. - * - * @param timeout Timeout in ms to wait for a new packet - */ -csp_packet_t *csp_promisc_read(uint32_t timeout); - -/** - * Send multiple packets using the simple fragmentation protocol - * CSP will add total size and offset to all packets - * This can be read by the client using the csp_sfp_recv, if the CSP_FFRAG flag is set - * @param conn pointer to connection - * @param data pointer to data to send - * @param totalsize size of data to send - * @param mtu maximum transfer unit - * @param timeout timeout in ms to wait for csp_send() - * @return 0 if OK, -1 if ERR - */ -int csp_sfp_send(csp_conn_t * conn, const void * data, int totalsize, int mtu, uint32_t timeout); - -/** - * Same as csp_sfp_send but with option to supply your own memcpy function. - * This is usefull if you wish to send data stored in flash memory or another location - * @param conn pointer to connection - * @param data pointer to data to send - * @param totalsize size of data to send - * @param mtu maximum transfer unit - * @param timeout timeout in ms to wait for csp_send() - * @param memcpyfcn, pointer to memcpy function - * @return 0 if OK, -1 if ERR - */ -int csp_sfp_send_own_memcpy(csp_conn_t * conn, const void * data, int totalsize, int mtu, uint32_t timeout, void * (*memcpyfcn)(void *, const void *, size_t)); - -/** - * This is the counterpart to the csp_sfp_send function - * @param conn pointer to active conn, on which you expect to receive sfp packed data - * @param dataout pointer to NULL pointer, whill be overwritten with malloc pointer - * @param datasize actual size of received data - * @param timeout timeout in ms to wait for csp_recv() - * @return 0 if OK, -1 if ERR - */ -int csp_sfp_recv(csp_conn_t * conn, void ** dataout, int * datasize, uint32_t timeout); - -/** - * This is the counterpart to the csp_sfp_send function - * @param conn pointer to active conn, on which you expect to receive sfp packed data - * @param dataout pointer to NULL pointer, whill be overwritten with malloc pointer - * @param datasize actual size of received data - * @param timeout timeout in ms to wait for csp_recv() - * @param first_packet This is a pointer to the first SFP packet (previously received with csp_read) - * @return 0 if OK, -1 if ERR - */ -int csp_sfp_recv_fp(csp_conn_t * conn, void ** dataout, int * datasize, uint32_t timeout, csp_packet_t * first_packet); - -/** - * If the given packet is a service-request (that is uses one of the csp service ports) - * it will be handled according to the CSP service handler. - * This function will either use the packet buffer or delete it, - * so this function is typically called in the last "default" clause of - * a switch/case statement in a csp_listener task. - * In order to listen to csp service ports, bind your listener to the CSP_ANY port. - * This function may only be called from task context. - * @param conn Pointer to the new connection - * @param packet Pointer to the first packet, obtained by using csp_read() - */ -void csp_service_handler(csp_conn_t *conn, csp_packet_t *packet); - -/** - * Send a single ping/echo packet - * @param node node id - * @param timeout timeout in ms - * @param size size of packet to transmit - * @param conn_options csp connection options - * @return >0 = Echo time in ms, -1 = ERR - */ -int csp_ping(uint8_t node, uint32_t timeout, unsigned int size, uint8_t conn_options); - -/** - * Send a single ping/echo packet without waiting for reply - * @param node node id - */ -void csp_ping_noreply(uint8_t node); - -/** - * Request process list. - * @note This is only available for FreeRTOS systems - * @param node node id - * @param timeout timeout in ms - */ -void csp_ps(uint8_t node, uint32_t timeout); - -/** - * Request amount of free memory - * @param node node id - * @param timeout timeout in ms - */ -void csp_memfree(uint8_t node, uint32_t timeout); - -/** - * Request number of free buffer elements - * @param node node id - * @param timeout timeout in ms - */ -void csp_buf_free(uint8_t node, uint32_t timeout); - -/** - * Reboot subsystem - * @param node node id - */ -void csp_reboot(uint8_t node); - -/** - * Shutdown subsystem - * @param node node id - */ -void csp_shutdown(uint8_t node); - -/** - * Request subsystem uptime - * @param node node id - * @param timeout timeout in ms - */ -void csp_uptime(uint8_t node, uint32_t timeout); - -/** - * Set RDP options - * @param window_size Window size - * @param conn_timeout_ms Connection timeout in ms - * @param packet_timeout_ms Packet timeout in ms - * @param delayed_acks Enable/disable delayed acknowledgements - * @param ack_timeout Acknowledgement timeout when delayed ACKs is enabled - * @param ack_delay_count Send acknowledgement for every ack_delay_count packets - */ -void csp_rdp_set_opt(unsigned int window_size, unsigned int conn_timeout_ms, - unsigned int packet_timeout_ms, unsigned int delayed_acks, - unsigned int ack_timeout, unsigned int ack_delay_count); - -/** - * Get RDP options - * @param window_size Window size - * @param conn_timeout_ms Connection timeout in ms - * @param packet_timeout_ms Packet timeout in ms - * @param delayed_acks Enable/disable delayed acknowledgements - * @param ack_timeout Acknowledgement timeout when delayed ACKs is enabled - * @param ack_delay_count Send acknowledgement for every ack_delay_count packets - */ -void csp_rdp_get_opt(unsigned int *window_size, unsigned int *conn_timeout_ms, - unsigned int *packet_timeout_ms, unsigned int *delayed_acks, - unsigned int *ack_timeout, unsigned int *ack_delay_count); - -/** - * Set XTEA key - * @param key Pointer to key array - * @param keylen Length of key - * @return 0 if key was successfully set, -1 otherwise - */ -int csp_xtea_set_key(char *key, uint32_t keylen); - -/** - * Set HMAC key - * @param key Pointer to key array - * @param keylen Length of key - * @return 0 if key was successfully set, -1 otherwise - */ -int csp_hmac_set_key(char *key, uint32_t keylen); - -/** - * Print connection table - */ -void csp_conn_print_table(void); -int csp_conn_print_table_str(char * str_buf, int str_size); - -/** - * Print buffer usage table - */ -void csp_buffer_print_table(void); - -/** - * Hex dump to stdout - */ -void csp_hex_dump(const char *desc, void *addr, int len); - -#ifdef __AVR__ -typedef uint32_t csp_memptr_t; -#else -typedef void * csp_memptr_t; -#endif - -typedef csp_memptr_t (*csp_memcpy_fnc_t)(csp_memptr_t, const csp_memptr_t, size_t); -void csp_cmp_set_memcpy(csp_memcpy_fnc_t fnc); - -/** - * Set csp_debug hook function - * @param f Hook function - */ -#include -typedef void (*csp_debug_hook_func_t)(csp_debug_level_t level, const char *format, va_list args); -void csp_debug_hook_set(csp_debug_hook_func_t f); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // _CSP_H_ diff --git a/libcsp/include/csp/csp_autoconfig.h b/libcsp/include/csp/csp_autoconfig.h deleted file mode 100644 index 703f3754..00000000 --- a/libcsp/include/csp/csp_autoconfig.h +++ /dev/null @@ -1,48 +0,0 @@ -/* - * csp_autoconfig.h - * - * Created on: 20.11.2020 - * Author: jakob - */ - -#ifndef GOMSPACE_LIBCSP_INCLUDE_CSP_CSP_AUTOCONFIG_H_ -#define GOMSPACE_LIBCSP_INCLUDE_CSP_CSP_AUTOCONFIG_H_ - -#define ENABLE_NANOPOWER2_CLIENT 1 -#define GIT_REV "unknown" -/* #undef CSP_FREERTOS */ -#define CSP_POSIX 1 -/* #undef CSP_WINDOWS */ -/* #undef CSP_MACOSX */ -#define HAVE_LIBZMQ 1 -#define CSP_DEBUG 1 -#define CSP_USE_RDP 1 -#define CSP_USE_CRC32 1 -#define CSP_USE_HMAC 1 -#define CSP_USE_XTEA 1 -#define CSP_USE_PROMISC 1 -#define CSP_USE_QOS 1 -/* #undef CSP_USE_DEDUP */ -/* #undef CSP_USE_INIT_SHUTDOWN */ -#define CSP_USE_CAN 1 -/* #define CSP_USE_I2C 1 */ -/* #define CSP_USE_KISS 1 */ -/* #define CSP_USE_ZMQHUB 1 */ -#define CSP_CONN_MAX 10 -#define CSP_CONN_QUEUE_LENGTH 100 -#define CSP_FIFO_INPUT 100 -#define CSP_MAX_BIND_PORT 31 -#define CSP_RDP_MAX_WINDOW 20 -#define CSP_PADDING_BYTES 8 -#define CSP_CONNECTION_SO 64 -#define CSP_LOG_LEVEL_DEBUG 1 -#define CSP_LOG_LEVEL_INFO 1 -#define CSP_LOG_LEVEL_WARN 1 -#define CSP_LOG_LEVEL_ERROR 1 -#define CSP_LITTLE_ENDIAN 1 -/* #undef CSP_BIG_ENDIAN */ -#define CSP_HAVE_STDBOOL_H 1 -/* #define CSP_HAVE_LIBSOCKETCAN 1 */ -#define LIBCSP_VERSION "1.5" - -#endif /* GOMSPACE_LIBCSP_INCLUDE_CSP_CSP_AUTOCONFIG_H_ */ diff --git a/libcsp/include/csp/csp_buffer.h b/libcsp/include/csp/csp_buffer.h deleted file mode 100644 index 9ed6df77..00000000 --- a/libcsp/include/csp/csp_buffer.h +++ /dev/null @@ -1,92 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#ifndef _CSP_BUFFER_H_ -#define _CSP_BUFFER_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -/** - * Start the buffer handling system - * You must specify the number for buffers and the size. All buffers are fixed - * size so you must specify the size of your largest buffer. - * - * @param count Number of buffers to allocate - * @param size Buffer size in bytes. - * - * @return CSP_ERR_NONE if malloc() succeeded, CSP_ERR message otherwise. - */ -int csp_buffer_init(int count, int size); - -/** - * Get a reference to a free buffer. This function can only be called - * from task context. - * - * @param size Specify what data-size you will put in the buffer - * @return pointer to a free csp_packet_t or NULL if out of memory - */ -void * csp_buffer_get(size_t size); - -/** - * Get a reference to a free buffer. This function can only be called - * from interrupt context. - * - * @param buf_size Specify what data-size you will put in the buffer - * @return pointer to a free csp_packet_t or NULL if out of memory - */ -void * csp_buffer_get_isr(size_t buf_size); - -/** - * Free a buffer after use. - * @param packet pointer to memory area, must be acquired by csp_buffer_get(). - */ -void csp_buffer_free(void *packet); - -/** - * Free a buffer after use in ISR context. - * @param packet pointer to memory area, must be acquired by csp_buffer_get(). - */ -void csp_buffer_free_isr(void *packet); - -/** - * Clone an existing packet and increase/decrease cloned packet size. - * @param buffer Existing buffer to clone. - */ -void * csp_buffer_clone(void *buffer); - -/** - * Return how many buffers that are currently free. - * @return number of free buffers - */ -int csp_buffer_remaining(void); - -/** - * Return the size of the CSP buffers - * @return size of CSP buffers - */ -int csp_buffer_size(void); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif /* _CSP_BUFFER_H_ */ diff --git a/libcsp/include/csp/csp_cmp.h b/libcsp/include/csp/csp_cmp.h deleted file mode 100644 index 114a8eab..00000000 --- a/libcsp/include/csp/csp_cmp.h +++ /dev/null @@ -1,189 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#ifndef _CSP_CMP_H_ -#define _CSP_CMP_H_ - -/** - @file - CSP management protocol (CMP). -*/ - -#ifdef __cplusplus -extern "C" { -#endif - -#include -#include -#include - -/** - CMP type. - @{ -*/ -/** - CMP request. -*/ -#define CSP_CMP_REQUEST 0x00 -/** - CMP reply. -*/ -#define CSP_CMP_REPLY 0xff -/**@}*/ - -/** - CMP requests. - @{ -*/ -/** - CMP request codes. -*/ -/** - Request identification, compile time, revision, name. -*/ -#define CSP_CMP_IDENT 1 -/** - Set/configure routing. -*/ -#define CSP_CMP_ROUTE_SET 2 -/** - Request interface statistics. -*/ -#define CSP_CMP_IF_STATS 3 -/** - Peek/read data from memory. -*/ -#define CSP_CMP_PEEK 4 -/** - Poke/write data from memory. -*/ -#define CSP_CMP_POKE 5 -/** - Get/set clock. -*/ -#define CSP_CMP_CLOCK 6 -/**@}*/ - -/** - CMP identification - max revision length. -*/ -#define CSP_CMP_IDENT_REV_LEN 20 -/** - CMP identification - max date length. -*/ -#define CSP_CMP_IDENT_DATE_LEN 12 -/** - CMP identification - max time length. -*/ -#define CSP_CMP_IDENT_TIME_LEN 9 - -/** - CMP interface statistics - max interface name length. -*/ -#define CSP_CMP_ROUTE_IFACE_LEN 11 - -/** - CMP peek/read memeory - max read length. -*/ -#define CSP_CMP_PEEK_MAX_LEN 200 - -/** - CMP poke/write memeory - max write length. -*/ -#define CSP_CMP_POKE_MAX_LEN 200 - -/** - CSP management protocol description. -*/ -struct csp_cmp_message { - //! CMP request type. - uint8_t type; - //! CMP request code. - uint8_t code; - union { - struct { - char hostname[CSP_HOSTNAME_LEN]; - char model[CSP_MODEL_LEN]; - char revision[CSP_CMP_IDENT_REV_LEN]; - char date[CSP_CMP_IDENT_DATE_LEN]; - char time[CSP_CMP_IDENT_TIME_LEN]; - } ident; - struct { - uint8_t dest_node; - uint8_t next_hop_mac; - char interface[CSP_CMP_ROUTE_IFACE_LEN]; - } route_set; - struct __attribute__((__packed__)) { - char interface[CSP_CMP_ROUTE_IFACE_LEN]; - uint32_t tx; - uint32_t rx; - uint32_t tx_error; - uint32_t rx_error; - uint32_t drop; - uint32_t autherr; - uint32_t frame; - uint32_t txbytes; - uint32_t rxbytes; - uint32_t irq; - } if_stats; - struct { - uint32_t addr; - uint8_t len; - char data[CSP_CMP_PEEK_MAX_LEN]; - } peek; - struct { - uint32_t addr; - uint8_t len; - char data[CSP_CMP_POKE_MAX_LEN]; - } poke; - csp_timestamp_t clock; - }; -} __attribute__ ((packed)); - -/** - Macro for calculating size of management message. -*/ -#define CMP_SIZE(_memb) (sizeof(((struct csp_cmp_message *)0)->_memb) + sizeof(uint8_t) + sizeof(uint8_t)) - -/** - Generic send management message request. -*/ -int csp_cmp(uint8_t node, uint32_t timeout, uint8_t code, int membsize, struct csp_cmp_message *msg); - -/** - Macro for defining management handling function. -*/ -#define CMP_MESSAGE(_code, _memb) \ -static inline int csp_cmp_##_memb(uint8_t node, uint32_t timeout, struct csp_cmp_message *msg) { \ - return csp_cmp(node, timeout, _code, CMP_SIZE(_memb), msg); \ -} - -CMP_MESSAGE(CSP_CMP_IDENT, ident) -CMP_MESSAGE(CSP_CMP_ROUTE_SET, route_set) -CMP_MESSAGE(CSP_CMP_IF_STATS, if_stats) -CMP_MESSAGE(CSP_CMP_PEEK, peek) -CMP_MESSAGE(CSP_CMP_POKE, poke) -CMP_MESSAGE(CSP_CMP_CLOCK, clock) - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // _CSP_CMP_H_ diff --git a/libcsp/include/csp/csp_crc32.h b/libcsp/include/csp/csp_crc32.h deleted file mode 100644 index a474eaf8..00000000 --- a/libcsp/include/csp/csp_crc32.h +++ /dev/null @@ -1,63 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#ifndef _CSP_CRC32_H_ -#define _CSP_CRC32_H_ - -#include - -#ifdef __cplusplus -extern "C" { -#endif - -/** - * Generate precomputed CRC32 table - */ -void csp_crc32_gentab(void); - -/** - * Append CRC32 checksum to packet - * @param packet Packet to append checksum - * @param include_header use header in calculation (this will not modify the flags field) - * @return 0 on success, -1 on error - */ -int csp_crc32_append(csp_packet_t * packet, bool include_header); - -/** - * Verify CRC32 checksum on packet - * @param packet Packet to verify - * @param include_header use header in calculation (this will not modify the flags field) - * @return 0 if checksum is valid, -1 otherwise - */ -int csp_crc32_verify(csp_packet_t * packet, bool include_header); - -/** - * Calculate checksum for a given memory area - * @param data pointer to memory - * @param length length of memory to do checksum on - * @return return uint32_t checksum - */ -uint32_t csp_crc32_memory(const uint8_t * data, uint32_t length); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif /* _CSP_CRC32_H_ */ diff --git a/libcsp/include/csp/csp_debug.h b/libcsp/include/csp/csp_debug.h deleted file mode 100644 index 64429d49..00000000 --- a/libcsp/include/csp/csp_debug.h +++ /dev/null @@ -1,150 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#ifndef _CSP_DEBUG_H_ -#define _CSP_DEBUG_H_ - -#include -#include - -#ifdef __cplusplus -extern "C" { -#endif - -/** Debug levels */ -typedef enum { - CSP_ERROR = 0, - CSP_WARN = 1, - CSP_INFO = 2, - CSP_BUFFER = 3, - CSP_PACKET = 4, - CSP_PROTOCOL = 5, - CSP_LOCK = 6, -} csp_debug_level_t; - -/* Extract filename component from path */ -#define BASENAME(_file) ((strrchr(_file, '/') ? : (strrchr(_file, '\\') ? : _file)) + 1) - -/* Implement csp_assert_fail_action to override default failure action */ -extern void __attribute__((weak)) csp_assert_fail_action(const char *assertion, const char *file, int line); - -#ifndef NDEBUG - #define csp_assert(exp) \ - do { \ - if (!(exp)) { \ - const char *assertion = #exp; \ - const char *file = BASENAME(__FILE__); \ - int line = __LINE__; \ - printf("\E[1;31m[%02" PRIu8 "] Assertion \'%s\' failed in %s:%d\E[0m\r\n", \ - csp_get_address(), assertion, file, line); \ - if (csp_assert_fail_action) \ - csp_assert_fail_action(assertion, file, line); \ - } \ - } while (0) -#else - #define csp_assert(...) do {} while (0) -#endif - -#ifdef __AVR__ - #include - #include - #define CONSTSTR(data) PSTR(data) - #undef printf - #undef sscanf - #undef scanf - #undef sprintf - #undef snprintf - #define printf(s, ...) printf_P(PSTR(s), ## __VA_ARGS__) - #define sscanf(buf, s, ...) sscanf_P(buf, PSTR(s), ## __VA_ARGS__) - #define scanf(s, ...) scanf_P(PSTR(s), ## __VA_ARGS__) - #define sprintf(buf, s, ...) sprintf_P(buf, PSTR(s), ## __VA_ARGS__) - #define snprintf(buf, size, s, ...) snprintf_P(buf, size, PSTR(s), ## __VA_ARGS__) -#else - #define CONSTSTR(data) data -#endif - -#ifdef CSP_DEBUG - #define csp_debug(level, format, ...) do { do_csp_debug(level, CONSTSTR(format), ##__VA_ARGS__); } while(0) -#else - #define csp_debug(...) do {} while (0) -#endif - -#ifdef CSP_LOG_LEVEL_ERROR - #define csp_log_error(format, ...) csp_debug(CSP_ERROR, format, ##__VA_ARGS__) -#else - #define csp_log_error(...) do {} while (0) -#endif - -#ifdef CSP_LOG_LEVEL_WARN - #define csp_log_warn(format, ...) csp_debug(CSP_WARN, format, ##__VA_ARGS__) -#else - #define csp_log_warn(...) do {} while (0) -#endif - -#ifdef CSP_LOG_LEVEL_INFO - #define csp_log_info(format, ...) csp_debug(CSP_INFO, format, ##__VA_ARGS__) -#else - #define csp_log_info(...) do {} while (0) -#endif - -#ifdef CSP_LOG_LEVEL_DEBUG - #define csp_log_buffer(format, ...) csp_debug(CSP_BUFFER, format, ##__VA_ARGS__) - #define csp_log_packet(format, ...) csp_debug(CSP_PACKET, format, ##__VA_ARGS__) - #define csp_log_protocol(format, ...) csp_debug(CSP_PROTOCOL, format, ##__VA_ARGS__) - #define csp_log_lock(format, ...) csp_debug(CSP_LOCK, format, ##__VA_ARGS__) -#else - #define csp_log_buffer(...) do {} while (0) - #define csp_log_packet(...) do {} while (0) - #define csp_log_protocol(...) do {} while (0) - #define csp_log_lock(...) do {} while (0) -#endif - -/** - * This function should not be used directly, use csp_log_() macro instead - * @param level - * @param format - */ -void do_csp_debug(csp_debug_level_t level, const char *format, ...); - -/** - * Toggle debug level on/off - * @param level Level to toggle - */ -void csp_debug_toggle_level(csp_debug_level_t level); - -/** - * Set debug level - * @param level Level to set - * @param value New level value - */ -void csp_debug_set_level(csp_debug_level_t level, bool value); - -/** - * Get current debug level value - * @param level Level value to get - * @return Level value - */ -int csp_debug_get_level(csp_debug_level_t level); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // _CSP_DEBUG_H_ diff --git a/libcsp/include/csp/csp_endian.h b/libcsp/include/csp/csp_endian.h deleted file mode 100644 index e63a73c2..00000000 --- a/libcsp/include/csp/csp_endian.h +++ /dev/null @@ -1,170 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#ifndef _CSP_ENDIAN_H_ -#define _CSP_ENDIAN_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include - -/** - * Convert 16-bit integer from host byte order to network byte order - * @param h16 Host byte order 16-bit integer - */ -uint16_t csp_hton16(uint16_t h16); - -/** - * Convert 16-bit integer from host byte order to host byte order - * @param n16 Network byte order 16-bit integer - */ -uint16_t csp_ntoh16(uint16_t n16); - -/** - * Convert 32-bit integer from host byte order to network byte order - * @param h32 Host byte order 32-bit integer - */ -uint32_t csp_hton32(uint32_t h32); - -/** - * Convert 32-bit integer from host byte order to host byte order - * @param n32 Network byte order 32-bit integer - */ -uint32_t csp_ntoh32(uint32_t n32); - -/** - * Convert 64-bit integer from host byte order to network byte order - * @param h64 Host byte order 64-bit integer - */ -uint64_t csp_hton64(uint64_t h64); - -/** - * Convert 64-bit integer from host byte order to host byte order - * @param n64 Network byte order 64-bit integer - */ -uint64_t csp_ntoh64(uint64_t n64); - -/** - * Convert 16-bit integer from host byte order to big endian byte order - * @param h16 Host byte order 16-bit integer - */ -uint16_t csp_htobe16(uint16_t h16); - -/** - * Convert 16-bit integer from host byte order to little endian byte order - * @param h16 Host byte order 16-bit integer - */ -uint16_t csp_htole16(uint16_t h16); - -/** - * Convert 16-bit integer from big endian byte order to little endian byte order - * @param be16 Big endian byte order 16-bit integer - */ -uint16_t csp_betoh16(uint16_t be16); - -/** - * Convert 16-bit integer from little endian byte order to host byte order - * @param le16 Little endian byte order 16-bit integer - */ -uint16_t csp_letoh16(uint16_t le16); - -/** - * Convert 32-bit integer from host byte order to big endian byte order - * @param h32 Host byte order 32-bit integer - */ -uint32_t csp_htobe32(uint32_t h32); - -/** - * Convert 32-bit integer from little endian byte order to host byte order - * @param h32 Host byte order 32-bit integer - */ -uint32_t csp_htole32(uint32_t h32); - -/** - * Convert 32-bit integer from big endian byte order to host byte order - * @param be32 Big endian byte order 32-bit integer - */ -uint32_t csp_betoh32(uint32_t be32); - -/** - * Convert 32-bit integer from little endian byte order to host byte order - * @param le32 Little endian byte order 32-bit integer - */ -uint32_t csp_letoh32(uint32_t le32); - -/** - * Convert 64-bit integer from host byte order to big endian byte order - * @param h64 Host byte order 64-bit integer - */ -uint64_t csp_htobe64(uint64_t h64); - -/** - * Convert 64-bit integer from host byte order to little endian byte order - * @param h64 Host byte order 64-bit integer - */ -uint64_t csp_htole64(uint64_t h64); - -/** - * Convert 64-bit integer from big endian byte order to host byte order - * @param be64 Big endian byte order 64-bit integer - */ -uint64_t csp_betoh64(uint64_t be64); - -/** - * Convert 64-bit integer from little endian byte order to host byte order - * @param le64 Little endian byte order 64-bit integer - */ -uint64_t csp_letoh64(uint64_t le64); - -/** - * Convert float from host to network byte order - * @param f Float in host order - * @return Float in network order - */ -float csp_htonflt(float f); - -/** - * Convert float from network to host byte order - * @param f Float in network order - * @return Float in host order - */ -float csp_ntohflt(float f); - -/** - * Convert double from host to network byte order - * @param d Double in host order - * @return Double in network order - */ -double csp_htondbl(double d); - -/** - * Convert double from network to host order - * @param d Double in network order - * @return Double in host order - */ -double csp_ntohdbl(double d); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // _CSP_ENDIAN_H_ diff --git a/libcsp/include/csp/csp_error.h b/libcsp/include/csp/csp_error.h deleted file mode 100644 index 31866607..00000000 --- a/libcsp/include/csp/csp_error.h +++ /dev/null @@ -1,50 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#ifndef _CSP_ERROR_H_ -#define _CSP_ERROR_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#define CSP_ERR_NONE 0 /* No error */ -#define CSP_ERR_NOMEM -1 /* Not enough memory */ -#define CSP_ERR_INVAL -2 /* Invalid argument */ -#define CSP_ERR_TIMEDOUT -3 /* Operation timed out */ -#define CSP_ERR_USED -4 /* Resource already in use */ -#define CSP_ERR_NOTSUP -5 /* Operation not supported */ -#define CSP_ERR_BUSY -6 /* Device or resource busy */ -#define CSP_ERR_ALREADY -7 /* Connection already in progress */ -#define CSP_ERR_RESET -8 /* Connection reset */ -#define CSP_ERR_NOBUFS -9 /* No more buffer space available */ -#define CSP_ERR_TX -10 /* Transmission failed */ -#define CSP_ERR_DRIVER -11 /* Error in driver layer */ -#define CSP_ERR_AGAIN -12 /* Resource temporarily unavailable */ - -#define CSP_ERR_HMAC -100 /* HMAC failed */ -#define CSP_ERR_XTEA -101 /* XTEA failed */ -#define CSP_ERR_CRC32 -102 /* CRC32 failed */ - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // _CSP_ERROR_H_ diff --git a/libcsp/include/csp/csp_iflist.h b/libcsp/include/csp/csp_iflist.h deleted file mode 100644 index 55875657..00000000 --- a/libcsp/include/csp/csp_iflist.h +++ /dev/null @@ -1,56 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#ifndef CSP_IFLIST_H_ -#define CSP_IFLIST_H_ - -#include - -#ifdef __cplusplus -extern "C" { -#endif - -/** - * Add interface to list - * @param ifc Pointer to interface to add - */ -void csp_iflist_add(csp_iface_t *ifc); - -/** - * Lookup interface by name - * @param name String with interface name - * @return Pointer to interface or NULL if not found - */ -csp_iface_t * csp_iflist_get_by_name(const char *name); - -/** - * Print list of interfaces to stdout - */ -void csp_iflist_print(void); - -/** - * Return list of registered interfaces. - */ -csp_iface_t * csp_iflist_get(void); - -#ifdef __cplusplus -} -#endif -#endif /* CSP_IFLIST_H_ */ diff --git a/libcsp/include/csp/csp_interface.h b/libcsp/include/csp/csp_interface.h deleted file mode 100644 index 8f04bee3..00000000 --- a/libcsp/include/csp/csp_interface.h +++ /dev/null @@ -1,54 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#ifndef _CSP_INTERFACE_H_ -#define _CSP_INTERFACE_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include - -/** - * Inputs a new packet into the system - * This function is called from interface drivers ISR to route and accept packets. - * But it can also be called from a task, provided that the pxTaskWoken parameter is NULL! - * - * EXTREMELY IMPORTANT: - * pxTaskWoken arg must ALWAYS be NULL if called from task, - * and ALWAYS be NON NULL if called from ISR! - * If this condition is met, this call is completely thread-safe - * - * This function is fire and forget, it returns void, meaning - * that a packet will always be either accepted or dropped - * so the memory will always be freed. - * - * @param packet A pointer to the incoming packet - * @param interface A pointer to the incoming interface TX function. - * @param pxTaskWoken This must be a pointer a valid variable if called from ISR or NULL otherwise! - */ -void csp_qfifo_write(csp_packet_t *packet, csp_iface_t *interface, CSP_BASE_TYPE *pxTaskWoken); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // _CSP_INTERFACE_H_ diff --git a/libcsp/include/csp/csp_platform.h b/libcsp/include/csp/csp_platform.h deleted file mode 100644 index b33292e9..00000000 --- a/libcsp/include/csp/csp_platform.h +++ /dev/null @@ -1,56 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#ifndef _CSP_PLATFORM_H_ -#define _CSP_PLATFORM_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include - -/* Set OS */ -#if defined(CSP_POSIX) || defined(CSP_WINDOWS) || defined(CSP_MACOSX) - #define CSP_BASE_TYPE int - #define CSP_MAX_DELAY (UINT32_MAX) - #define CSP_INFINITY (UINT32_MAX) - #define CSP_DEFINE_CRITICAL(lock) static csp_bin_sem_handle_t lock - #define CSP_INIT_CRITICAL(lock) ({(csp_bin_sem_create(&lock) == CSP_SEMAPHORE_OK) ? CSP_ERR_NONE : CSP_ERR_NOMEM;}) - #define CSP_ENTER_CRITICAL(lock) do { csp_bin_sem_wait(&lock, CSP_MAX_DELAY); } while(0) - #define CSP_EXIT_CRITICAL(lock) do { csp_bin_sem_post(&lock); } while(0) -#elif defined(CSP_FREERTOS) - #include "FreeRTOS.h" - #define CSP_BASE_TYPE portBASE_TYPE - #define CSP_MAX_DELAY portMAX_DELAY - #define CSP_INFINITY portMAX_DELAY - #define CSP_DEFINE_CRITICAL(lock) - #define CSP_INIT_CRITICAL(lock) ({CSP_ERR_NONE;}) - #define CSP_ENTER_CRITICAL(lock) do { portENTER_CRITICAL(); } while (0) - #define CSP_EXIT_CRITICAL(lock) do { portEXIT_CRITICAL(); } while (0) -#else - #error "OS must be either CSP_POSIX, CSP_MACOSX, CSP_FREERTOS OR CSP_WINDOWS" -#endif - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // _CSP_PLATFORM_H_ diff --git a/libcsp/include/csp/csp_rtable.h b/libcsp/include/csp/csp_rtable.h deleted file mode 100644 index 34cd18e2..00000000 --- a/libcsp/include/csp/csp_rtable.h +++ /dev/null @@ -1,149 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#ifndef CSP_RTABLE_H_ -#define CSP_RTABLE_H_ - -#include - -#ifdef __cplusplus -extern "C" { -#endif - -#define CSP_NODE_MAC 0xFF -#define CSP_ROUTE_COUNT (CSP_ID_HOST_MAX + 2) -#define CSP_ROUTE_TABLE_SIZE 5 * CSP_ROUTE_COUNT - -/** - * Find outgoing interface in routing table - * @param id Destination node - * @return pointer to outgoing interface or NULL - */ -csp_iface_t * csp_rtable_find_iface(uint8_t id); - -/** - * Find MAC address associated with node - * @param id Destination node - * @return MAC address - */ -uint8_t csp_rtable_find_mac(uint8_t id); - -/** - * Setup routing entry - * @param node Host - * @param mask Number of bits in netmask - * @param ifc Interface - * @param mac MAC address - * @return CSP error type - */ -int csp_rtable_set(uint8_t node, uint8_t mask, csp_iface_t *ifc, uint8_t mac); - -/** - * Print routing table to stdout - */ -void csp_rtable_print(void); - - -/** - * Load the routing table from a buffer - * (deprecated, please use new csp_rtable_load) - * - * Warning: - * The table will be RAW from memory and contains direct pointers, not interface names. - * Therefore it's very important that a saved routing table is deleted after a firmware update - * - * @param route_table_in pointer to routing table buffer - */ -void csp_route_table_load(uint8_t route_table_in[CSP_ROUTE_TABLE_SIZE]); - -/** - * Save the routing table to a buffer - * (deprecated, please use new csp_rtable_save) - * - * Warning: - * The table will be RAW from memory and contains direct pointers, not interface names. - * Therefore it's very important that a saved routing table is deleted after a firmware update - * - * @param route_table_out pointer to routing table buffer - */ -void csp_route_table_save(uint8_t route_table_out[CSP_ROUTE_TABLE_SIZE]); - -/** - * Save routing table as a string to a buffer, which can be parsed - * again by csp_rtable_load. - * @param buffer pointer to buffer - * @param maxlen length of buffer - * @return length of saved string - */ -int csp_rtable_save(char * buffer, int maxlen); - -/** - * Load routing table from a string in the format - * %u/%u %s %u - * - Address - * - Netmask - * - Ifname - * - Mac Address (this field is optional) - * An example routing string is "0/0 I2C, 8/2 KISS" - * The string must be \0 null terminated - * @param buffer Pointer to string - */ -void csp_rtable_load(const char * buffer); - -/** - * Check string for valid routing table - * @param buffer Pointer to string - * @return number of valid entries found - */ -int csp_rtable_check(const char * buffer); - -/** - * Clear routing table: - * This could be done before load to ensure an entire clean table is loaded. - */ -void csp_rtable_clear(void); - -/** - * Setup routing entry to single node - * (deprecated, please use csp_rtable_set) - * - * @param node Host - * @param ifc Interface - * @param mac MAC address - * @return CSP error type - */ -#define csp_route_set(node, ifc, mac) csp_rtable_set(node, CSP_ID_HOST_SIZE, ifc, mac) - -/** - * Print routing table - * (deprecated, please use csp_rtable_print) - */ -#define csp_route_print_table() csp_rtable_print(); - -/** - * Print list of interfaces - * (deprecated, please use csp_iflist_print) - */ -#define csp_route_print_interfaces() csp_iflist_print(); - -#ifdef __cplusplus -} -#endif -#endif /* CSP_RTABLE_H_ */ diff --git a/libcsp/include/csp/csp_types.h b/libcsp/include/csp/csp_types.h deleted file mode 100644 index a9cc28cd..00000000 --- a/libcsp/include/csp/csp_types.h +++ /dev/null @@ -1,235 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#ifndef CSP_TYPES_H_ -#define CSP_TYPES_H_ - -#include -#include // -> CSP_HAVE_X defines -#ifdef CSP_HAVE_STDBOOL_H -#include -#endif - -#ifdef __cplusplus -extern "C" { -#endif - -/* Make bool for compilers without stdbool.h */ -#ifndef CSP_HAVE_STDBOOL_H -#define bool int -#define false 0 -#define true !false -#endif - -/** - * RESERVED PORTS (SERVICES) - */ - -enum csp_reserved_ports_e { - CSP_CMP = 0, - CSP_PING = 1, - CSP_PS = 2, - CSP_MEMFREE = 3, - CSP_REBOOT = 4, - CSP_BUF_FREE = 5, - CSP_UPTIME = 6, - CSP_ANY = (CSP_MAX_BIND_PORT + 1), - CSP_PROMISC = (CSP_MAX_BIND_PORT + 2) -}; - -typedef enum { - CSP_PRIO_CRITICAL = 0, - CSP_PRIO_HIGH = 1, - CSP_PRIO_NORM = 2, - CSP_PRIO_LOW = 3, -} csp_prio_t; - -#define CSP_PRIORITIES (1 << CSP_ID_PRIO_SIZE) - -#ifdef CSP_USE_QOS -#define CSP_RX_QUEUE_LENGTH (CSP_CONN_QUEUE_LENGTH / CSP_PRIORITIES) -#define CSP_ROUTE_FIFOS CSP_PRIORITIES -#define CSP_RX_QUEUES CSP_PRIORITIES -#else -#define CSP_RX_QUEUE_LENGTH CSP_CONN_QUEUE_LENGTH -#define CSP_ROUTE_FIFOS 1 -#define CSP_RX_QUEUES 1 -#endif - -/** Size of bit-fields in CSP header */ -#define CSP_ID_PRIO_SIZE 2 -#define CSP_ID_HOST_SIZE 5 -#define CSP_ID_PORT_SIZE 6 -#define CSP_ID_FLAGS_SIZE 8 - -#define CSP_HEADER_BITS (CSP_ID_PRIO_SIZE + 2 * CSP_ID_HOST_SIZE + 2 * CSP_ID_PORT_SIZE + CSP_ID_FLAGS_SIZE) -#define CSP_HEADER_LENGTH (CSP_HEADER_BITS / 8) - -#if CSP_HEADER_BITS != 32 && __GNUC__ -#error "Header length must be 32 bits" -#endif - -/** Highest number to be entered in field */ -#define CSP_ID_PRIO_MAX ((1 << (CSP_ID_PRIO_SIZE)) - 1) -#define CSP_ID_HOST_MAX ((1 << (CSP_ID_HOST_SIZE)) - 1) -#define CSP_ID_PORT_MAX ((1 << (CSP_ID_PORT_SIZE)) - 1) -#define CSP_ID_FLAGS_MAX ((1 << (CSP_ID_FLAGS_SIZE)) - 1) - -/** Identifier field masks */ -#define CSP_ID_PRIO_MASK ((uint32_t) CSP_ID_PRIO_MAX << (CSP_ID_FLAGS_SIZE + 2 * CSP_ID_PORT_SIZE + 2 * CSP_ID_HOST_SIZE)) -#define CSP_ID_SRC_MASK ((uint32_t) CSP_ID_HOST_MAX << (CSP_ID_FLAGS_SIZE + 2 * CSP_ID_PORT_SIZE + 1 * CSP_ID_HOST_SIZE)) -#define CSP_ID_DST_MASK ((uint32_t) CSP_ID_HOST_MAX << (CSP_ID_FLAGS_SIZE + 2 * CSP_ID_PORT_SIZE)) -#define CSP_ID_DPORT_MASK ((uint32_t) CSP_ID_PORT_MAX << (CSP_ID_FLAGS_SIZE + 1 * CSP_ID_PORT_SIZE)) -#define CSP_ID_SPORT_MASK ((uint32_t) CSP_ID_PORT_MAX << (CSP_ID_FLAGS_SIZE)) -#define CSP_ID_FLAGS_MASK ((uint32_t) CSP_ID_FLAGS_MAX << (0)) - -#define CSP_ID_CONN_MASK (CSP_ID_SRC_MASK | CSP_ID_DST_MASK | CSP_ID_DPORT_MASK | CSP_ID_SPORT_MASK) - -/** - CSP identifier. -*/ -typedef union { - //! Entire identifier. - uint32_t ext; - //! Individual fields. - struct __attribute__((__packed__)) { -#if defined(CSP_BIG_ENDIAN) && !defined(CSP_LITTLE_ENDIAN) - unsigned int pri : CSP_ID_PRIO_SIZE; - unsigned int src : CSP_ID_HOST_SIZE; - unsigned int dst : CSP_ID_HOST_SIZE; - unsigned int dport : CSP_ID_PORT_SIZE; - unsigned int sport : CSP_ID_PORT_SIZE; - unsigned int flags : CSP_ID_FLAGS_SIZE; -#elif defined(CSP_LITTLE_ENDIAN) && !defined(CSP_BIG_ENDIAN) - unsigned int flags : CSP_ID_FLAGS_SIZE; - unsigned int sport : CSP_ID_PORT_SIZE; - unsigned int dport : CSP_ID_PORT_SIZE; - unsigned int dst : CSP_ID_HOST_SIZE; - unsigned int src : CSP_ID_HOST_SIZE; - unsigned int pri : CSP_ID_PRIO_SIZE; -#else -#error "Must define one of CSP_BIG_ENDIAN or CSP_LITTLE_ENDIAN in csp_platform.h" -#endif - }; -} csp_id_t; - -/** Broadcast address */ -#define CSP_BROADCAST_ADDR CSP_ID_HOST_MAX - -/** Default routing address */ -#define CSP_DEFAULT_ROUTE (CSP_ID_HOST_MAX + 1) - -/** CSP Flags */ -#define CSP_FRES1 0x80 // Reserved for future use -#define CSP_FRES2 0x40 // Reserved for future use -#define CSP_FRES3 0x20 // Reserved for future use -#define CSP_FFRAG 0x10 // Use fragmentation -#define CSP_FHMAC 0x08 // Use HMAC verification -#define CSP_FXTEA 0x04 // Use XTEA encryption -#define CSP_FRDP 0x02 // Use RDP protocol -#define CSP_FCRC32 0x01 // Use CRC32 checksum - -/** CSP Socket options */ -#define CSP_SO_NONE 0x0000 // No socket options -#define CSP_SO_RDPREQ 0x0001 // Require RDP -#define CSP_SO_RDPPROHIB 0x0002 // Prohibit RDP -#define CSP_SO_HMACREQ 0x0004 // Require HMAC -#define CSP_SO_HMACPROHIB 0x0008 // Prohibit HMAC -#define CSP_SO_XTEAREQ 0x0010 // Require XTEA -#define CSP_SO_XTEAPROHIB 0x0020 // Prohibit HMAC -#define CSP_SO_CRC32REQ 0x0040 // Require CRC32 -#define CSP_SO_CRC32PROHIB 0x0080 // Prohibit CRC32 -#define CSP_SO_CONN_LESS 0x0100 // Enable Connection Less mode -#define CSP_SO_INTERNAL_LISTEN 0x1000 // Internal flag: listen called on socket - -/** CSP Connect options */ -#define CSP_O_NONE CSP_SO_NONE // No connection options -#define CSP_O_RDP CSP_SO_RDPREQ // Enable RDP -#define CSP_O_NORDP CSP_SO_RDPPROHIB // Disable RDP -#define CSP_O_HMAC CSP_SO_HMACREQ // Enable HMAC -#define CSP_O_NOHMAC CSP_SO_HMACPROHIB // Disable HMAC -#define CSP_O_XTEA CSP_SO_XTEAREQ // Enable XTEA -#define CSP_O_NOXTEA CSP_SO_XTEAPROHIB // Disable XTEA -#define CSP_O_CRC32 CSP_SO_CRC32REQ // Enable CRC32 -#define CSP_O_NOCRC32 CSP_SO_CRC32PROHIB // Disable CRC32 - -/** - * CSP PACKET STRUCTURE - * Note: This structure is constructed to fit - * with all interface frame types in order to - * have buffer reuse - */ -typedef struct __attribute__((__packed__)) { - uint8_t padding[CSP_PADDING_BYTES]; /**< Interface dependent padding */ - uint16_t length; /**< Length field must be just before CSP ID */ - csp_id_t id; /**< CSP id must be just before data */ - union { - uint8_t data[0]; /**< This just points to the rest of the buffer, without a size indication. */ - uint16_t data16[0]; /**< The data 16 and 32 types makes it easy to reference an integer (properly aligned) */ - uint32_t data32[0]; /**< without the compiler warning about strict aliasing rules. */ - }; -} csp_packet_t; - -/** Interface TX function */ -struct csp_iface_s; -typedef int (*nexthop_t)(struct csp_iface_s * interface, csp_packet_t *packet, uint32_t timeout); - -/** Interface struct */ -typedef struct csp_iface_s { - const char *name; /**< Interface name (keep below 10 bytes) */ - void * driver; /**< Pointer to interface handler structure */ - nexthop_t nexthop; /**< Next hop function */ - uint16_t mtu; /**< Maximum Transmission Unit of interface */ - uint8_t split_horizon_off; /**< Disable the route-loop prevention on if */ - uint32_t tx; /**< Successfully transmitted packets */ - uint32_t rx; /**< Successfully received packets */ - uint32_t tx_error; /**< Transmit errors */ - uint32_t rx_error; /**< Receive errors */ - uint32_t drop; /**< Dropped packets */ - uint32_t autherr; /**< Authentication errors */ - uint32_t frame; /**< Frame format errors */ - uint32_t txbytes; /**< Transmitted bytes */ - uint32_t rxbytes; /**< Received bytes */ - uint32_t irq; /**< Interrupts */ - struct csp_iface_s *next; /**< Next interface */ -} csp_iface_t; - -/** - * This define must be equal to the size of the packet overhead in csp_packet_t. - * It is used in csp_buffer_get() to check the allocated buffer size against - * the required buffer size. - */ -#define CSP_BUFFER_PACKET_OVERHEAD (sizeof(csp_packet_t) - sizeof(((csp_packet_t *)0)->data)) - -/** Forward declaration of socket and connection structures */ -typedef struct csp_conn_s csp_socket_t; -typedef struct csp_conn_s csp_conn_t; - -#define CSP_HOSTNAME_LEN 20 -#define CSP_MODEL_LEN 30 - -/* CSP_REBOOT magic values */ -#define CSP_REBOOT_MAGIC 0x80078007 -#define CSP_REBOOT_SHUTDOWN_MAGIC 0xD1E5529A - -#ifdef __cplusplus -} -#endif -#endif /* CSP_TYPES_H_ */ diff --git a/libcsp/include/csp/drivers/can_socketcan.h b/libcsp/include/csp/drivers/can_socketcan.h deleted file mode 100644 index 0963b414..00000000 --- a/libcsp/include/csp/drivers/can_socketcan.h +++ /dev/null @@ -1,22 +0,0 @@ -/* - * can_socketcan.h - * - * Created on: Feb 6, 2017 - * Author: johan - */ - -#ifndef LIB_CSP_INCLUDE_CSP_DRIVERS_CAN_SOCKETCAN_H_ -#define LIB_CSP_INCLUDE_CSP_DRIVERS_CAN_SOCKETCAN_H_ - -#include - -#ifdef __cplusplus -extern "C" { -#endif - -csp_iface_t * csp_can_socketcan_init(const char * ifc, int bitrate, int promisc); - -#ifdef __cplusplus -} -#endif -#endif /* LIB_CSP_INCLUDE_CSP_DRIVERS_CAN_SOCKETCAN_H_ */ diff --git a/libcsp/include/csp/drivers/i2c.h b/libcsp/include/csp/drivers/i2c.h deleted file mode 100644 index 3cf605ee..00000000 --- a/libcsp/include/csp/drivers/i2c.h +++ /dev/null @@ -1,120 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -/** - * @file - * Common I2C interface, - * This file is derived from the Gomspace I2C driver, - * - */ - -#ifndef I2C_H_ -#define I2C_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -/** - * The return value of the driver is a bit strange, - * It should return E_NO_ERR if successfull and the value is -1 - */ -#define E_NO_ERR -1 - -/** - * Maximum transfer length on I2C - */ -#define I2C_MTU 256 - -/** - I2C device modes - @{ -*/ -/** - I2C Master mode. -*/ -#define I2C_MASTER 0 -/** - I2C Slave mode. -*/ -#define I2C_SLAVE 1 -/**@}*/ - -/** - Data structure for I2C frames. - This structs fits on top of #csp_packet_t, removing the need for copying data. -*/ -typedef struct __attribute__((packed)) i2c_frame_s { - //! Not used by CSP - uint8_t padding; - //! Not used by CSP - cleared before Tx - uint8_t retries; - //! Not used by CSP - uint32_t reserved; - //! Destination address - uint8_t dest; - //! Not used by CSP - cleared before Tx - uint8_t len_rx; - //! Length of \a data part - uint16_t len; - //! CSP data - uint8_t data[I2C_MTU]; -} i2c_frame_t; - -/** - Callback for receiving data. - - @param[in] frame received I2C frame - @param[out] pxTaskWoken can be set, if context switch is required due to received data. -*/ -typedef void (*i2c_callback_t) (i2c_frame_t * frame, void * pxTaskWoken); - -/** - Initialise the I2C driver - - Functions is called by csp_i2c_init(). - - @param handle Which I2C bus (if more than one exists) - @param mode I2C device mode. Must be either I2C_MASTER or I2C_SLAVE - @param addr Own slave address - @param speed Bus speed in kbps - @param queue_len_tx Length of transmit queue - @param queue_len_rx Length of receive queue - @param callback If this value is set, the driver will call this function instead of using an RX queue - @return Error code -*/ -int i2c_init(int handle, int mode, uint8_t addr, uint16_t speed, int queue_len_tx, int queue_len_rx, i2c_callback_t callback); - -/** - User I2C transmit function. - - Called by CSP, when sending message over I2C. - - @param handle Handle to the device - @param frame Pointer to I2C frame - @param timeout Ticks to wait - @return Error code -*/ -int i2c_send(int handle, i2c_frame_t * frame, uint16_t timeout); - -#ifdef __cplusplus -} -#endif -#endif diff --git a/libcsp/include/csp/drivers/usart.h b/libcsp/include/csp/drivers/usart.h deleted file mode 100644 index d2da8448..00000000 --- a/libcsp/include/csp/drivers/usart.h +++ /dev/null @@ -1,107 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -/** - * @file - * Common USART interface, - * This file is derived from the Gomspace USART driver, - * the main difference is the assumption that only one USART will be present on a PC - */ - -#ifndef USART_H_ -#define USART_H_ - -#include - -#ifdef __cplusplus -extern "C" { -#endif - -/** - Usart configuration, to be used with the usart_init call. -*/ -struct usart_conf { - //! USART device. - const char *device; - //! bits per second. - uint32_t baudrate; - //! Number of data bits. - uint8_t databits; - //! Number of stop bits. - uint8_t stopbits; - //! Parity setting. - uint8_t paritysetting; - //! Enable parity checking (Windows only). - uint8_t checkparity; -}; - -/** - Initialise UART with the usart_conf data structure - @param[in] conf full configuration structure -*/ -void usart_init(struct usart_conf *conf); - -/** - In order to catch incoming chars use the callback. - Only one callback per interface. - @param[in] handle usart[0,1,2,3] - @param[in] callback function pointer -*/ -typedef void (*usart_callback_t) (uint8_t *buf, int len, void *pxTaskWoken); - -/** - Set callback for receiving data. -*/ -void usart_set_callback(usart_callback_t callback); - -/** - Insert a character to the RX buffer of a usart - - @param[in] c character to insert - @param[out] pxTaskWoken can be set, if context switch is required due to received data. -*/ -void usart_insert(char c, void *pxTaskWoken); - -/** - Polling putchar (stdin). - - @param[in] c Character to transmit -*/ -void usart_putc(char c); - -/** - Send char buffer on UART (stdout). - - @param[in] buf Pointer to data - @param[in] len Length of data -*/ -void usart_putstr(char *buf, int len); - -/** - Buffered getchar (stdin). - - @return Character received -*/ -char usart_getc(void); - -#ifdef __cplusplus -} -#endif -#endif /* USART_H_ */ diff --git a/libcsp/include/csp/interfaces/csp_if_can.h b/libcsp/include/csp/interfaces/csp_if_can.h deleted file mode 100644 index 229671f2..00000000 --- a/libcsp/include/csp/interfaces/csp_if_can.h +++ /dev/null @@ -1,76 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#ifndef _CSP_IF_CAN_H_ -#define _CSP_IF_CAN_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include - -#include -#include - -/* CAN header macros */ -#define CFP_HOST_SIZE 5 -#define CFP_TYPE_SIZE 1 -#define CFP_REMAIN_SIZE 8 -#define CFP_ID_SIZE 10 - -/* Macros for extracting header fields */ -#define CFP_FIELD(id,rsiz,fsiz) ((uint32_t)((uint32_t)((id) >> (rsiz)) & (uint32_t)((1 << (fsiz)) - 1))) -#define CFP_SRC(id) CFP_FIELD(id, CFP_HOST_SIZE + CFP_TYPE_SIZE + CFP_REMAIN_SIZE + CFP_ID_SIZE, CFP_HOST_SIZE) -#define CFP_DST(id) CFP_FIELD(id, CFP_TYPE_SIZE + CFP_REMAIN_SIZE + CFP_ID_SIZE, CFP_HOST_SIZE) -#define CFP_TYPE(id) CFP_FIELD(id, CFP_REMAIN_SIZE + CFP_ID_SIZE, CFP_TYPE_SIZE) -#define CFP_REMAIN(id) CFP_FIELD(id, CFP_ID_SIZE, CFP_REMAIN_SIZE) -#define CFP_ID(id) CFP_FIELD(id, 0, CFP_ID_SIZE) - -/* Macros for building CFP headers */ -#define CFP_MAKE_FIELD(id,fsiz,rsiz) ((uint32_t)(((id) & (uint32_t)((uint32_t)(1 << (fsiz)) - 1)) << (rsiz))) -#define CFP_MAKE_SRC(id) CFP_MAKE_FIELD(id, CFP_HOST_SIZE, CFP_HOST_SIZE + CFP_TYPE_SIZE + CFP_REMAIN_SIZE + CFP_ID_SIZE) -#define CFP_MAKE_DST(id) CFP_MAKE_FIELD(id, CFP_HOST_SIZE, CFP_TYPE_SIZE + CFP_REMAIN_SIZE + CFP_ID_SIZE) -#define CFP_MAKE_TYPE(id) CFP_MAKE_FIELD(id, CFP_TYPE_SIZE, CFP_REMAIN_SIZE + CFP_ID_SIZE) -#define CFP_MAKE_REMAIN(id) CFP_MAKE_FIELD(id, CFP_REMAIN_SIZE, CFP_ID_SIZE) -#define CFP_MAKE_ID(id) CFP_MAKE_FIELD(id, CFP_ID_SIZE, 0) - -/* Mask to uniquely separate connections */ -#define CFP_ID_CONN_MASK (CFP_MAKE_SRC((uint32_t)(1 << CFP_HOST_SIZE) - 1) | \ - CFP_MAKE_DST((uint32_t)(1 << CFP_HOST_SIZE) - 1) | \ - CFP_MAKE_ID((uint32_t)(1 << CFP_ID_SIZE) - 1)) - -/** - Default Maximum Transmission Unit (MTU) for CSP over CAN. - Maximum value is 2042 bytes. -*/ -#define CSP_CAN_MTU 256 - -int csp_can_rx(csp_iface_t *interface, uint32_t id, const uint8_t * data, uint8_t dlc, CSP_BASE_TYPE *task_woken); -int csp_can_tx(csp_iface_t *interface, csp_packet_t *packet, uint32_t timeout); - -/* Must be implemented by the driver */ -int csp_can_tx_frame(csp_iface_t *interface, uint32_t id, const uint8_t * data, uint8_t dlc); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif /* _CSP_IF_CAN_H_ */ diff --git a/libcsp/include/csp/interfaces/csp_if_i2c.h b/libcsp/include/csp/interfaces/csp_if_i2c.h deleted file mode 100644 index c2169843..00000000 --- a/libcsp/include/csp/interfaces/csp_if_i2c.h +++ /dev/null @@ -1,51 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#ifndef _CSP_IF_I2C_H_ -#define _CSP_IF_I2C_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include - -#include -#include -#include - -extern csp_iface_t csp_if_i2c; - -/** - * Capture I2C RX events for CSP - * @param opt_addr local i2c address - * @param handle which i2c device to use - * @param speed interface speed in kHz (normally 100 or 400) - * @return csp_error.h code - */ -int csp_i2c_init(uint8_t opt_addr, int handle, int speed); - -void csp_i2c_rx(i2c_frame_t * frame, void * pxTaskWoken); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif /* _CSP_IF_I2C_H_ */ diff --git a/libcsp/include/csp/interfaces/csp_if_kiss.h b/libcsp/include/csp/interfaces/csp_if_kiss.h deleted file mode 100644 index f164cad1..00000000 --- a/libcsp/include/csp/interfaces/csp_if_kiss.h +++ /dev/null @@ -1,110 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#ifndef _CSP_IF_KISS_H_ -#define _CSP_IF_KISS_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include - -#include -#include - -/** - * The KISS interface relies on the USART callback in order to parse incoming - * messaged from the serial interface. The USART callback however does not - * support passing the handle number of the responding USART, so you need to implement - * a USART callback for each handle and then call kiss_rx subsequently. - * - * In order to initialize the KISS interface. Fist call kiss_init() and then - * setup your usart to call csp_kiss_rx when new data is available. - * - * When a byte is not a part of a kiss packet, it will be returned to your - * usart driver using the usart_insert funtion that you provide. - * - * @param csp_iface pointer to interface - * @param buf pointer to incoming data - * @param len length of incoming data - * @param pxTaskWoken NULL if task context, pointer to variable if ISR - */ -void csp_kiss_rx(csp_iface_t * interface, uint8_t *buf, int len, void *pxTaskWoken); - -/** - * The putc function is used by the kiss interface to send - * a string of data to the serial port. This function must - * be implemented by the user, and passed to the kiss - * interface through the kiss_init function. - * @param buf byte to push - */ -typedef void (*csp_kiss_putc_f)(char buf); - -/** - * The characters not accepted by the kiss interface, are discarded - * using this function, which must be implemented by the user - * and passed through the kiss_init function. - * - * This reject function is typically used to display ASCII strings - * sent over the serial port, which are not in KISS format. Such as - * debugging information. - * - * @param c rejected character - * @param pxTaskWoken NULL if task context, pointer to variable if ISR - */ -typedef void (*csp_kiss_discard_f)(char c, void *pxTaskWoken); - -typedef enum { - KISS_MODE_NOT_STARTED, - KISS_MODE_STARTED, - KISS_MODE_ESCAPED, - KISS_MODE_SKIP_FRAME, -} kiss_mode_e; - -/** - * This structure should be statically allocated by the user - * and passed to the kiss interface during the init function - * no member information should be changed - */ -typedef struct csp_kiss_handle_s { - //! Put character on usart (tx). - csp_kiss_putc_f kiss_putc; - //! Discard - not KISS data (rx). - csp_kiss_discard_f kiss_discard; - //! Internal KISS state. - unsigned int rx_length; - //! Internal KISS state. - kiss_mode_e rx_mode; - //! Internal KISS state. - unsigned int rx_first; - //! Not used. - volatile unsigned char *rx_cbuf; - //! Internal KISS state. - csp_packet_t * rx_packet; -} csp_kiss_handle_t; - -void csp_kiss_init(csp_iface_t * csp_iface, csp_kiss_handle_t * csp_kiss_handle, csp_kiss_putc_f kiss_putc_f, csp_kiss_discard_f kiss_discard_f, const char * name); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif /* _CSP_IF_KISS_H_ */ diff --git a/libcsp/include/csp/interfaces/csp_if_lo.h b/libcsp/include/csp/interfaces/csp_if_lo.h deleted file mode 100644 index 793c45ac..00000000 --- a/libcsp/include/csp/interfaces/csp_if_lo.h +++ /dev/null @@ -1,38 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#ifndef _CSP_IF_LO_H_ -#define _CSP_IF_LO_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -/* CSP includes */ -#include -#include - -extern csp_iface_t csp_if_lo; - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // _CSP_IF_LO_H_ diff --git a/libcsp/include/csp/interfaces/csp_if_zmqhub.h b/libcsp/include/csp/interfaces/csp_if_zmqhub.h deleted file mode 100644 index f9ab43bf..00000000 --- a/libcsp/include/csp/interfaces/csp_if_zmqhub.h +++ /dev/null @@ -1,26 +0,0 @@ -#ifndef CSP_IF_ZMQHUB_H_ -#define CSP_IF_ZMQHUB_H_ - -#include - -extern csp_iface_t csp_if_zmqhub; - -/** - * Setup ZMQ interface - * @param addr only receive messages matching this address (255 means all) - * @param host Pointer to string containing zmqproxy host - * @return CSP_ERR - */ -int csp_zmqhub_init(uint8_t addr, const char * host); - -/** - * Setup ZMQ interface - * @param addr only receive messages matching this address (255 means all) - * @param publisher_endpoint Pointer to string containing zmqproxy publisher endpoint - * @param subscriber_endpoint Pointer to string containing zmqproxy subscriber endpoint - * @return CSP_ERR - */ -int csp_zmqhub_init_w_endpoints(uint8_t addr, const char * publisher_url, - const char * subscriber_url); - -#endif /* CSP_IF_ZMQHUB_H_ */ diff --git a/libcsp/libcsp.mk b/libcsp/libcsp.mk deleted file mode 100644 index febffad7..00000000 --- a/libcsp/libcsp.mk +++ /dev/null @@ -1,12 +0,0 @@ -CSRC += $(wildcard $(CURRENTPATH)/src/drivers/can/*.c) -CSRC += $(wildcard $(CURRENTPATH)/src/*.c) -CSRC += $(wildcard $(CURRENTPATH)/src/interfaces/*.c) -CSRC += $(wildcard $(CURRENTPATH)/src/rtable/csp_rtable_cidr.c) -CSRC += $(wildcard $(CURRENTPATH)/src/crypto/*.c) -CSRC += $(wildcard $(CURRENTPATH)/src/arch/posix/*.c) -CSRC += $(wildcard $(CURRENTPATH)/src/transport/*.c) - -INCLUDES += $(CURRENTPATH)/include -INCLUDES += $(CURRENTPATH)/include/csp -INCLUDES += $(CURRENTPATH)/include/csp/crypto -INCLUDES += $(CURRENTPATH) \ No newline at end of file diff --git a/libcsp/src/CMakeLists.txt b/libcsp/src/CMakeLists.txt deleted file mode 100644 index 39c67877..00000000 --- a/libcsp/src/CMakeLists.txt +++ /dev/null @@ -1,27 +0,0 @@ -target_sources(${LIB_CSP_NAME} PRIVATE - csp_bridge.c - csp_buffer.c - csp_conn.c - csp_crc32.c - csp_debug.c - csp_dedup.c - csp_endian.c - csp_hex_dump.c - csp_iflist.c - csp_io.c - csp_port.c - csp_promisc.c - csp_qfifo.c - csp_route.c - csp_service_handler.c - csp_services.c - csp_sfp.c -) - -add_subdirectory(drivers) -add_subdirectory(crypto) -add_subdirectory(interfaces) -add_subdirectory(rtable) -add_subdirectory(transport) -add_subdirectory(arch) - diff --git a/libcsp/src/arch/CMakeLists.txt b/libcsp/src/arch/CMakeLists.txt deleted file mode 100644 index aa0e4ca6..00000000 --- a/libcsp/src/arch/CMakeLists.txt +++ /dev/null @@ -1,3 +0,0 @@ -add_subdirectory(posix) - - diff --git a/libcsp/src/arch/freertos/csp_malloc.c b/libcsp/src/arch/freertos/csp_malloc.c deleted file mode 100644 index 97e5c8f4..00000000 --- a/libcsp/src/arch/freertos/csp_malloc.c +++ /dev/null @@ -1,33 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include -#include - -/* FreeRTOS includes */ -#include - -void * csp_malloc(size_t size) { - return pvPortMalloc(size); -} - -void csp_free(void *ptr) { - vPortFree(ptr); -} diff --git a/libcsp/src/arch/freertos/csp_queue.c b/libcsp/src/arch/freertos/csp_queue.c deleted file mode 100644 index 44efd0eb..00000000 --- a/libcsp/src/arch/freertos/csp_queue.c +++ /dev/null @@ -1,66 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include - -/* FreeRTOS includes */ -#include -#include - -/* CSP includes */ -#include - -#include - -csp_queue_handle_t csp_queue_create(int length, size_t item_size) { - return xQueueCreate(length, item_size); -} - -void csp_queue_remove(csp_queue_handle_t queue) { - vQueueDelete(queue); -} - -int csp_queue_enqueue(csp_queue_handle_t handle, void * value, uint32_t timeout) { - if (timeout != CSP_MAX_DELAY) - timeout = timeout / portTICK_RATE_MS; - return xQueueSendToBack(handle, value, timeout); -} - -int csp_queue_enqueue_isr(csp_queue_handle_t handle, void * value, CSP_BASE_TYPE * task_woken) { - return xQueueSendToBackFromISR(handle, value, task_woken); -} - -int csp_queue_dequeue(csp_queue_handle_t handle, void * buf, uint32_t timeout) { - if (timeout != CSP_MAX_DELAY) - timeout = timeout / portTICK_RATE_MS; - return xQueueReceive(handle, buf, timeout); -} - -int csp_queue_dequeue_isr(csp_queue_handle_t handle, void * buf, CSP_BASE_TYPE * task_woken) { - return xQueueReceiveFromISR(handle, buf, task_woken); -} - -int csp_queue_size(csp_queue_handle_t handle) { - return uxQueueMessagesWaiting(handle); -} - -int csp_queue_size_isr(csp_queue_handle_t handle) { - return uxQueueMessagesWaitingFromISR(handle); -} diff --git a/libcsp/src/arch/freertos/csp_semaphore.c b/libcsp/src/arch/freertos/csp_semaphore.c deleted file mode 100644 index b91757e5..00000000 --- a/libcsp/src/arch/freertos/csp_semaphore.c +++ /dev/null @@ -1,96 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include -#include - -/* FreeRTOS includes */ -#include -#include - -/* CSP includes */ -#include - -#include -#include -#include - -int csp_mutex_create(csp_mutex_t * mutex) { - *mutex = xSemaphoreCreateMutex(); - if (*mutex) { - return CSP_SEMAPHORE_OK; - } else { - return CSP_SEMAPHORE_ERROR; - } -} - -int csp_mutex_remove(csp_mutex_t * mutex) { - return csp_bin_sem_remove(mutex); -} - -int csp_mutex_lock(csp_mutex_t * mutex, uint32_t timeout) { - return csp_bin_sem_wait(mutex, timeout); -} - -int csp_mutex_unlock(csp_mutex_t * mutex) { - return csp_bin_sem_post(mutex); -} - -int csp_bin_sem_create(csp_bin_sem_handle_t * sem) { - vSemaphoreCreateBinary(*sem); - return CSP_SEMAPHORE_OK; -} - -int csp_bin_sem_remove(csp_bin_sem_handle_t * sem) { - if ((sem != NULL) && (*sem != NULL)) { - csp_queue_remove(*sem); - } - return CSP_SEMAPHORE_OK; -} - -int csp_bin_sem_wait(csp_bin_sem_handle_t * sem, uint32_t timeout) { - csp_log_lock("Wait: %p", sem); - if (timeout != CSP_MAX_DELAY) - timeout = timeout / portTICK_RATE_MS; - if (xSemaphoreTake(*sem, timeout) == pdPASS) { - return CSP_SEMAPHORE_OK; - } else { - return CSP_SEMAPHORE_ERROR; - } -} - -int csp_bin_sem_post(csp_bin_sem_handle_t * sem) { - csp_log_lock("Post: %p", sem); - if (xSemaphoreGive(*sem) == pdPASS) { - return CSP_SEMAPHORE_OK; - } else { - return CSP_SEMAPHORE_ERROR; - } -} - -int csp_bin_sem_post_isr(csp_bin_sem_handle_t * sem, CSP_BASE_TYPE * task_woken) { - csp_log_lock("Post: %p", sem); - if (xSemaphoreGiveFromISR(*sem, task_woken) == pdPASS) { - return CSP_SEMAPHORE_OK; - } else { - return CSP_SEMAPHORE_ERROR; - } -} - diff --git a/libcsp/src/arch/freertos/csp_system.c b/libcsp/src/arch/freertos/csp_system.c deleted file mode 100644 index a81c84b4..00000000 --- a/libcsp/src/arch/freertos/csp_system.c +++ /dev/null @@ -1,139 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include -#include -#include -#include - -#include -#include - -#include - -int csp_sys_tasklist(char * out) { -#if (tskKERNEL_VERSION_MAJOR < 8) - vTaskList((signed portCHAR *) out); -#else - vTaskList(out); -#endif - return CSP_ERR_NONE; -} - -int csp_sys_tasklist_size(void) { - return 40 * uxTaskGetNumberOfTasks(); -} - -uint32_t csp_sys_memfree(void) { - - uint32_t total = 0, max = UINT32_MAX, size; - void * pmem; - - /* If size_t is less than 32 bits, start with 10 KiB */ - size = sizeof(uint32_t) > sizeof(size_t) ? 10000 : 1000000; - - while (1) { - pmem = pvPortMalloc(size + total); - if (pmem == NULL) { - max = size + total; - size = size / 2; - } else { - total += size; - if (total + size >= max) - size = size / 2; - vPortFree(pmem); - } - if (size < 32) break; - } - - return total; -} - -int csp_sys_reboot(void) { - - extern void __attribute__((weak)) cpu_set_reset_cause(unsigned int); - if (cpu_set_reset_cause) - cpu_set_reset_cause(1); - - extern void __attribute__((weak)) cpu_reset(void); - if (cpu_reset) { - cpu_reset(); - while (1); - } - - csp_log_error("Failed to reboot"); - - return CSP_ERR_INVAL; -} - -int csp_sys_shutdown(void) { - - extern void __attribute__((weak)) cpu_shutdown(void); - if (cpu_shutdown) { - cpu_shutdown(); - while (1); - } - - csp_log_error("Failed to shutdown"); - - return CSP_ERR_INVAL; -} - -void csp_sys_set_color(csp_color_t color) { - - unsigned int color_code, modifier_code; - switch (color & COLOR_MASK_COLOR) { - case COLOR_BLACK: - color_code = 30; break; - case COLOR_RED: - color_code = 31; break; - case COLOR_GREEN: - color_code = 32; break; - case COLOR_YELLOW: - color_code = 33; break; - case COLOR_BLUE: - color_code = 34; break; - case COLOR_MAGENTA: - color_code = 35; break; - case COLOR_CYAN: - color_code = 36; break; - case COLOR_WHITE: - color_code = 37; break; - case COLOR_RESET: - default: - color_code = 0; break; - } - - switch (color & COLOR_MASK_MODIFIER) { - case COLOR_BOLD: - modifier_code = 1; break; - case COLOR_UNDERLINE: - modifier_code = 2; break; - case COLOR_BLINK: - modifier_code = 3; break; - case COLOR_HIDE: - modifier_code = 4; break; - case COLOR_NORMAL: - default: - modifier_code = 0; break; - } - - printf("\033[%u;%um", modifier_code, color_code); -} diff --git a/libcsp/src/arch/freertos/csp_thread.c b/libcsp/src/arch/freertos/csp_thread.c deleted file mode 100644 index af8296cd..00000000 --- a/libcsp/src/arch/freertos/csp_thread.c +++ /dev/null @@ -1,38 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include -#include - -/* CSP includes */ -#include - -#include - -int csp_thread_create(csp_thread_return_t (* routine)(void *), const char * const thread_name, unsigned short stack_depth, void * parameters, unsigned int priority, csp_thread_handle_t * handle) { -#if (tskKERNEL_VERSION_MAJOR >= 8) - portBASE_TYPE ret = xTaskCreate(routine, thread_name, stack_depth, parameters, priority, handle); -#else - portBASE_TYPE ret = xTaskCreate(routine, (signed char *) thread_name, stack_depth, parameters, priority, handle); -#endif - if (ret != pdTRUE) - return CSP_ERR_NOMEM; - return CSP_ERR_NONE; -} diff --git a/libcsp/src/arch/freertos/csp_time.c b/libcsp/src/arch/freertos/csp_time.c deleted file mode 100644 index fd54a8cb..00000000 --- a/libcsp/src/arch/freertos/csp_time.c +++ /dev/null @@ -1,46 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include - -/* FreeRTOS includes */ -#include -#include - -/* CSP includes */ -#include - -#include - -uint32_t csp_get_ms(void) { - return (uint32_t)(xTaskGetTickCount() * (1000/configTICK_RATE_HZ)); -} - -uint32_t csp_get_ms_isr(void) { - return (uint32_t)(xTaskGetTickCountFromISR() * (1000/configTICK_RATE_HZ)); -} - -uint32_t csp_get_s(void) { - return (uint32_t)(xTaskGetTickCount()/configTICK_RATE_HZ); -} - -uint32_t csp_get_s_isr(void) { - return (uint32_t)(xTaskGetTickCountFromISR()/configTICK_RATE_HZ); -} diff --git a/libcsp/src/arch/macosx/csp_malloc.c b/libcsp/src/arch/macosx/csp_malloc.c deleted file mode 100644 index 95bb8cc7..00000000 --- a/libcsp/src/arch/macosx/csp_malloc.c +++ /dev/null @@ -1,31 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include -#include - -void * csp_malloc(size_t size) { - return malloc(size); -} - -void csp_free(void *ptr) { - free(ptr); -} - diff --git a/libcsp/src/arch/macosx/csp_queue.c b/libcsp/src/arch/macosx/csp_queue.c deleted file mode 100644 index a2fb1b4f..00000000 --- a/libcsp/src/arch/macosx/csp_queue.c +++ /dev/null @@ -1,64 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include -#include - -/* CSP includes */ -#include - -#include -#include - - -csp_queue_handle_t csp_queue_create(int length, size_t item_size) { - return pthread_queue_create(length, item_size); -} - -void csp_queue_remove(csp_queue_handle_t queue) { - return pthread_queue_delete(queue); -} - -int csp_queue_enqueue(csp_queue_handle_t handle, void *value, uint32_t timeout) { - return pthread_queue_enqueue(handle, value, timeout); -} - -int csp_queue_enqueue_isr(csp_queue_handle_t handle, void * value, CSP_BASE_TYPE * task_woken) { - if (task_woken != NULL) - *task_woken = 0; - return csp_queue_enqueue(handle, value, 0); -} - -int csp_queue_dequeue(csp_queue_handle_t handle, void *buf, uint32_t timeout) { - return pthread_queue_dequeue(handle, buf, timeout); -} - -int csp_queue_dequeue_isr(csp_queue_handle_t handle, void *buf, CSP_BASE_TYPE * task_woken) { - *task_woken = 0; - return csp_queue_dequeue(handle, buf, 0); -} - -int csp_queue_size(csp_queue_handle_t handle) { - return pthread_queue_items(handle); -} - -int csp_queue_size_isr(csp_queue_handle_t handle) { - return pthread_queue_items(handle); -} diff --git a/libcsp/src/arch/macosx/csp_semaphore.c b/libcsp/src/arch/macosx/csp_semaphore.c deleted file mode 100644 index 915447f3..00000000 --- a/libcsp/src/arch/macosx/csp_semaphore.c +++ /dev/null @@ -1,105 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -/* CSP includes */ -#include - -#include - -int csp_mutex_create(csp_mutex_t * mutex) { - csp_log_lock("Mutex init: %p", mutex); - *mutex = pthread_queue_create(1, sizeof(int)); - if (mutex) { - int dummy = 0; - pthread_queue_enqueue(*mutex, &dummy, 0); - return CSP_SEMAPHORE_OK; - } else { - return CSP_SEMAPHORE_ERROR; - } -} - -int csp_mutex_remove(csp_mutex_t * mutex) { - pthread_queue_delete(*mutex); - return CSP_SEMAPHORE_OK; -} - -int csp_mutex_lock(csp_mutex_t * mutex, uint32_t timeout) { - - int ret; - csp_log_lock("Wait: %p timeout %"PRIu32, mutex, timeout); - - if (timeout == CSP_INFINITY) { - /* TODO: fix this to be infinite */ - int dummy = 0; - if (pthread_queue_dequeue(*mutex, &dummy, timeout) == PTHREAD_QUEUE_OK) - ret = CSP_MUTEX_OK; - else - ret = CSP_MUTEX_ERROR; - } else { - int dummy = 0; - if (pthread_queue_dequeue(*mutex, &dummy, timeout) == PTHREAD_QUEUE_OK) - ret = CSP_MUTEX_OK; - else - ret = CSP_MUTEX_ERROR; - } - - return ret == CSP_MUTEX_ERROR ? CSP_SEMAPHORE_ERROR : CSP_SEMAPHORE_OK; -} - -int csp_mutex_unlock(csp_mutex_t * mutex) { - int dummy = 0; - if (pthread_queue_enqueue(*mutex, &dummy, 0) == PTHREAD_QUEUE_OK) { - return CSP_SEMAPHORE_OK; - } else { - return CSP_SEMAPHORE_ERROR; - } -} - -int csp_bin_sem_create(csp_bin_sem_handle_t * sem) { - return csp_mutex_create(sem); -} - -int csp_bin_sem_remove(csp_bin_sem_handle_t * sem) { - return csp_mutex_remove(sem); -} - -int csp_bin_sem_wait(csp_bin_sem_handle_t * sem, uint32_t timeout) { - return csp_mutex_lock(sem, timeout); -} - -int csp_bin_sem_post(csp_bin_sem_handle_t * sem) { - return csp_mutex_unlock(sem); -} - -int csp_bin_sem_post_isr(csp_bin_sem_handle_t * sem, CSP_BASE_TYPE * task_woken) { - return csp_mutex_unlock(sem); -} diff --git a/libcsp/src/arch/macosx/csp_system.c b/libcsp/src/arch/macosx/csp_system.c deleted file mode 100644 index 834cb210..00000000 --- a/libcsp/src/arch/macosx/csp_system.c +++ /dev/null @@ -1,99 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include -#include -#include - -#include -#include - -#include - -int csp_sys_tasklist(char * out) { - strcpy(out, "Tasklist not available on OSX"); - return CSP_ERR_NONE; -} - -int csp_sys_tasklist_size(void) { - return 100; -} - -uint32_t csp_sys_memfree(void) { - /* TODO: Fix memory free on OSX */ - uint32_t total = 0; - return total; -} - -int csp_sys_reboot(void) { - /* TODO: Fix reboot on OSX */ - csp_log_error("Failed to reboot"); - - return CSP_ERR_INVAL; -} - -int csp_sys_shutdown(void) { - /* TODO: Fix shutdown on OSX */ - csp_log_error("Failed to shutdown"); - - return CSP_ERR_INVAL; -} - -void csp_sys_set_color(csp_color_t color) { - - unsigned int color_code, modifier_code; - switch (color & COLOR_MASK_COLOR) { - case COLOR_BLACK: - color_code = 30; break; - case COLOR_RED: - color_code = 31; break; - case COLOR_GREEN: - color_code = 32; break; - case COLOR_YELLOW: - color_code = 33; break; - case COLOR_BLUE: - color_code = 34; break; - case COLOR_MAGENTA: - color_code = 35; break; - case COLOR_CYAN: - color_code = 36; break; - case COLOR_WHITE: - color_code = 37; break; - case COLOR_RESET: - default: - color_code = 0; break; - } - - switch (color & COLOR_MASK_MODIFIER) { - case COLOR_BOLD: - modifier_code = 1; break; - case COLOR_UNDERLINE: - modifier_code = 2; break; - case COLOR_BLINK: - modifier_code = 3; break; - case COLOR_HIDE: - modifier_code = 4; break; - case COLOR_NORMAL: - default: - modifier_code = 0; break; - } - - printf("\033[%u;%um", modifier_code, color_code); -} diff --git a/libcsp/src/arch/macosx/csp_thread.c b/libcsp/src/arch/macosx/csp_thread.c deleted file mode 100644 index ed64856a..00000000 --- a/libcsp/src/arch/macosx/csp_thread.c +++ /dev/null @@ -1,31 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include -#include - -/* CSP includes */ -#include - -#include - -int csp_thread_create(csp_thread_return_t (* routine)(void *), const char * const thread_name, unsigned short stack_depth, void * parameters, unsigned int priority, csp_thread_handle_t * handle) { - return pthread_create(handle, NULL, routine, parameters); -} diff --git a/libcsp/src/arch/macosx/csp_time.c b/libcsp/src/arch/macosx/csp_time.c deleted file mode 100644 index a53f27e6..00000000 --- a/libcsp/src/arch/macosx/csp_time.c +++ /dev/null @@ -1,65 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include -#include -#include -#include - -/* CSP includes */ -#include - -#include - -uint32_t csp_get_ms(void) { - struct timespec ts; - - clock_serv_t cclock; - mach_timespec_t mts; - host_get_clock_service(mach_host_self(), CALENDAR_CLOCK, &cclock); - clock_get_time(cclock, &mts); - mach_port_deallocate(mach_task_self(), cclock); - ts.tv_sec = mts.tv_sec; - ts.tv_nsec = mts.tv_nsec; - - return (uint32_t)(ts.tv_sec*1000+ts.tv_nsec/1000000); -} - -uint32_t csp_get_ms_isr(void) { - return csp_get_ms(); -} - -uint32_t csp_get_s(void) { - struct timespec ts; - - clock_serv_t cclock; - mach_timespec_t mts; - host_get_clock_service(mach_host_self(), CALENDAR_CLOCK, &cclock); - clock_get_time(cclock, &mts); - mach_port_deallocate(mach_task_self(), cclock); - ts.tv_sec = mts.tv_sec; - ts.tv_nsec = mts.tv_nsec; - - return (uint32_t)ts.tv_sec; -} - -uint32_t csp_get_s_isr(void) { - return csp_get_s(); -} diff --git a/libcsp/src/arch/macosx/pthread_queue.c b/libcsp/src/arch/macosx/pthread_queue.c deleted file mode 100644 index c4ac8c1d..00000000 --- a/libcsp/src/arch/macosx/pthread_queue.c +++ /dev/null @@ -1,179 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -/* -Inspired by c-pthread-queue by Matthew Dickinson -http://code.google.com/p/c-pthread-queue/ -*/ - -#include -#include -#include -#include -#include -#include -#include - -/* CSP includes */ -#include - -pthread_queue_t * pthread_queue_create(int length, size_t item_size) { - - pthread_queue_t * q = malloc(sizeof(pthread_queue_t)); - - if (q != NULL) { - q->buffer = malloc(length*item_size); - if (q->buffer != NULL) { - q->size = length; - q->item_size = item_size; - q->items = 0; - q->in = 0; - q->out = 0; - if (pthread_mutex_init(&(q->mutex), NULL) || pthread_cond_init(&(q->cond_full), NULL) || pthread_cond_init(&(q->cond_empty), NULL)) { - free(q->buffer); - free(q); - q = NULL; - } - } else { - free(q); - q = NULL; - } - } - - return q; - -} - -void pthread_queue_delete(pthread_queue_t * q) { - - if (q == NULL) - return; - - free(q->buffer); - free(q); - - return; - -} - -int pthread_queue_enqueue(pthread_queue_t * queue, void * value, uint32_t timeout) { - - int ret; - - /* Calculate timeout */ - struct timespec ts; - - clock_serv_t cclock; - mach_timespec_t mts; - host_get_clock_service(mach_host_self(), CALENDAR_CLOCK, &cclock); - clock_get_time(cclock, &mts); - mach_port_deallocate(mach_task_self(), cclock); - ts.tv_sec = mts.tv_sec; - ts.tv_nsec = mts.tv_nsec; - - uint32_t sec = timeout / 1000; - uint32_t nsec = (timeout - 1000 * sec) * 1000000; - - ts.tv_sec += sec; - - if (ts.tv_nsec + nsec > 1000000000) - ts.tv_sec++; - - ts.tv_nsec = (ts.tv_nsec + nsec) % 1000000000; - - /* Get queue lock */ - pthread_mutex_lock(&(queue->mutex)); - while (queue->items == queue->size) { - ret = pthread_cond_timedwait(&(queue->cond_full), &(queue->mutex), &ts); - if (ret != 0) { - pthread_mutex_unlock(&(queue->mutex)); - return PTHREAD_QUEUE_FULL; - } - } - - /* Coby object from input buffer */ - memcpy(queue->buffer+(queue->in * queue->item_size), value, queue->item_size); - queue->items++; - queue->in = (queue->in + 1) % queue->size; - pthread_mutex_unlock(&(queue->mutex)); - - /* Nofify blocked threads */ - pthread_cond_broadcast(&(queue->cond_empty)); - - return PTHREAD_QUEUE_OK; - -} - -int pthread_queue_dequeue(pthread_queue_t * queue, void * buf, uint32_t timeout) { - - int ret; - - /* Calculate timeout */ - struct timespec ts; - clock_serv_t cclock; - mach_timespec_t mts; - host_get_clock_service(mach_host_self(), CALENDAR_CLOCK, &cclock); - clock_get_time(cclock, &mts); - mach_port_deallocate(mach_task_self(), cclock); - ts.tv_sec = mts.tv_sec; - ts.tv_nsec = mts.tv_nsec; - - uint32_t sec = timeout / 1000; - uint32_t nsec = (timeout - 1000 * sec) * 1000000; - - ts.tv_sec += sec; - - if (ts.tv_nsec + nsec > 1000000000) - ts.tv_sec++; - - ts.tv_nsec = (ts.tv_nsec + nsec) % 1000000000; - - /* Get queue lock */ - pthread_mutex_lock(&(queue->mutex)); - while (queue->items == 0) { - ret = pthread_cond_timedwait(&(queue->cond_empty), &(queue->mutex), &ts); - if (ret != 0) { - pthread_mutex_unlock(&(queue->mutex)); - return PTHREAD_QUEUE_EMPTY; - } - } - - /* Coby object to output buffer */ - memcpy(buf, queue->buffer+(queue->out * queue->item_size), queue->item_size); - queue->items--; - queue->out = (queue->out + 1) % queue->size; - pthread_mutex_unlock(&(queue->mutex)); - - /* Nofify blocked threads */ - pthread_cond_broadcast(&(queue->cond_full)); - - return PTHREAD_QUEUE_OK; - -} - -int pthread_queue_items(pthread_queue_t * queue) { - - pthread_mutex_lock(&(queue->mutex)); - int items = queue->items; - pthread_mutex_unlock(&(queue->mutex)); - - return items; - -} diff --git a/libcsp/src/arch/posix/CMakeLists.txt b/libcsp/src/arch/posix/CMakeLists.txt deleted file mode 100644 index 6bf13773..00000000 --- a/libcsp/src/arch/posix/CMakeLists.txt +++ /dev/null @@ -1,9 +0,0 @@ -target_sources(${LIB_CSP_NAME} PRIVATE - csp_malloc.c - csp_queue.c - csp_semaphore.c - csp_system.c - csp_thread.c - csp_time.c - pthread_queue.c -) diff --git a/libcsp/src/arch/posix/csp_malloc.c b/libcsp/src/arch/posix/csp_malloc.c deleted file mode 100644 index 95bb8cc7..00000000 --- a/libcsp/src/arch/posix/csp_malloc.c +++ /dev/null @@ -1,31 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include -#include - -void * csp_malloc(size_t size) { - return malloc(size); -} - -void csp_free(void *ptr) { - free(ptr); -} - diff --git a/libcsp/src/arch/posix/csp_queue.c b/libcsp/src/arch/posix/csp_queue.c deleted file mode 100644 index a2fb1b4f..00000000 --- a/libcsp/src/arch/posix/csp_queue.c +++ /dev/null @@ -1,64 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include -#include - -/* CSP includes */ -#include - -#include -#include - - -csp_queue_handle_t csp_queue_create(int length, size_t item_size) { - return pthread_queue_create(length, item_size); -} - -void csp_queue_remove(csp_queue_handle_t queue) { - return pthread_queue_delete(queue); -} - -int csp_queue_enqueue(csp_queue_handle_t handle, void *value, uint32_t timeout) { - return pthread_queue_enqueue(handle, value, timeout); -} - -int csp_queue_enqueue_isr(csp_queue_handle_t handle, void * value, CSP_BASE_TYPE * task_woken) { - if (task_woken != NULL) - *task_woken = 0; - return csp_queue_enqueue(handle, value, 0); -} - -int csp_queue_dequeue(csp_queue_handle_t handle, void *buf, uint32_t timeout) { - return pthread_queue_dequeue(handle, buf, timeout); -} - -int csp_queue_dequeue_isr(csp_queue_handle_t handle, void *buf, CSP_BASE_TYPE * task_woken) { - *task_woken = 0; - return csp_queue_dequeue(handle, buf, 0); -} - -int csp_queue_size(csp_queue_handle_t handle) { - return pthread_queue_items(handle); -} - -int csp_queue_size_isr(csp_queue_handle_t handle) { - return pthread_queue_items(handle); -} diff --git a/libcsp/src/arch/posix/csp_semaphore.c b/libcsp/src/arch/posix/csp_semaphore.c deleted file mode 100644 index 6829dec2..00000000 --- a/libcsp/src/arch/posix/csp_semaphore.c +++ /dev/null @@ -1,164 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -/* CSP includes */ -#include - -#include - -int csp_mutex_create(csp_mutex_t * mutex) { - csp_log_lock("Mutex init: %p", mutex); - if (pthread_mutex_init(mutex, NULL) == 0) { - return CSP_SEMAPHORE_OK; - } else { - return CSP_SEMAPHORE_ERROR; - } -} - -int csp_mutex_remove(csp_mutex_t * mutex) { - if (pthread_mutex_destroy(mutex) == 0) { - return CSP_SEMAPHORE_OK; - } else { - return CSP_SEMAPHORE_ERROR; - } -} - -int csp_mutex_lock(csp_mutex_t * mutex, uint32_t timeout) { - - int ret; - struct timespec ts; - uint32_t sec, nsec; - - csp_log_lock("Wait: %p timeout %"PRIu32, mutex, timeout); - - if (timeout == CSP_INFINITY) { - ret = pthread_mutex_lock(mutex); - } else { - if (clock_gettime(CLOCK_REALTIME, &ts)) - return CSP_SEMAPHORE_ERROR; - - sec = timeout / 1000; - nsec = (timeout - 1000 * sec) * 1000000; - - ts.tv_sec += sec; - - if (ts.tv_nsec + nsec >= 1000000000) - ts.tv_sec++; - - ts.tv_nsec = (ts.tv_nsec + nsec) % 1000000000; - - ret = pthread_mutex_timedlock(mutex, &ts); - } - - if (ret != 0) - return CSP_SEMAPHORE_ERROR; - - return CSP_SEMAPHORE_OK; -} - -int csp_mutex_unlock(csp_mutex_t * mutex) { - if (pthread_mutex_unlock(mutex) == 0) { - return CSP_SEMAPHORE_OK; - } else { - return CSP_SEMAPHORE_ERROR; - } -} - -int csp_bin_sem_create(csp_bin_sem_handle_t * sem) { - csp_log_lock("Semaphore init: %p", sem); - if (sem_init(sem, 0, 1) == 0) { - return CSP_SEMAPHORE_OK; - } else { - return CSP_SEMAPHORE_ERROR; - } -} - -int csp_bin_sem_remove(csp_bin_sem_handle_t * sem) { - if (sem_destroy(sem) == 0) - return CSP_SEMAPHORE_OK; - else - return CSP_SEMAPHORE_ERROR; -} - -int csp_bin_sem_wait(csp_bin_sem_handle_t * sem, uint32_t timeout) { - - int ret; - struct timespec ts; - uint32_t sec, nsec; - - csp_log_lock("Wait: %p timeout %"PRIu32, sem, timeout); - - if (timeout == CSP_INFINITY) { - ret = sem_wait(sem); - } else { - if (clock_gettime(CLOCK_REALTIME, &ts)) - return CSP_SEMAPHORE_ERROR; - - sec = timeout / 1000; - nsec = (timeout - 1000 * sec) * 1000000; - - ts.tv_sec += sec; - - if (ts.tv_nsec + nsec >= 1000000000) - ts.tv_sec++; - - ts.tv_nsec = (ts.tv_nsec + nsec) % 1000000000; - - ret = sem_timedwait(sem, &ts); - } - - if (ret != 0) - return CSP_SEMAPHORE_ERROR; - - return CSP_SEMAPHORE_OK; -} - -int csp_bin_sem_post(csp_bin_sem_handle_t * sem) { - CSP_BASE_TYPE dummy = 0; - return csp_bin_sem_post_isr(sem, &dummy); -} - -int csp_bin_sem_post_isr(csp_bin_sem_handle_t * sem, CSP_BASE_TYPE * task_woken) { - csp_log_lock("Post: %p", sem); - *task_woken = 0; - - int value; - sem_getvalue(sem, &value); - if (value > 0) - return CSP_SEMAPHORE_OK; - - if (sem_post(sem) == 0) { - return CSP_SEMAPHORE_OK; - } else { - return CSP_SEMAPHORE_ERROR; - } -} diff --git a/libcsp/src/arch/posix/csp_system.c b/libcsp/src/arch/posix/csp_system.c deleted file mode 100644 index 6c882c7c..00000000 --- a/libcsp/src/arch/posix/csp_system.c +++ /dev/null @@ -1,131 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include -#include - -#include - -int csp_sys_tasklist(char * out) { - strcpy(out, "Tasklist not available on POSIX"); - return CSP_ERR_NONE; -} - -int csp_sys_tasklist_size(void) { - return 100; -} - -uint32_t csp_sys_memfree(void) { - uint32_t total = 0; - struct sysinfo info; - sysinfo(&info); - total = info.freeram * info.mem_unit; - return total; -} - -int csp_sys_reboot(void) { -#ifdef CSP_USE_INIT_SHUTDOWN - /* Let init(1) handle the reboot */ - int ret = system("reboot"); - (void) ret; /* Silence warning */ -#else - int magic = LINUX_REBOOT_CMD_RESTART; - - /* Sync filesystem before reboot */ - sync(); - reboot(magic); -#endif - - /* If reboot(2) returns, it is an error */ - csp_log_error("Failed to reboot: %s", strerror(errno)); - - return CSP_ERR_INVAL; -} - -int csp_sys_shutdown(void) { -#ifdef CSP_USE_INIT_SHUTDOWN - /* Let init(1) handle the shutdown */ - int ret = system("halt"); - (void) ret; /* Silence warning */ -#else - int magic = LINUX_REBOOT_CMD_HALT; - - /* Sync filesystem before reboot */ - sync(); - reboot(magic); -#endif - - /* If reboot(2) returns, it is an error */ - csp_log_error("Failed to shutdown: %s", strerror(errno)); - - return CSP_ERR_INVAL; -} - -void csp_sys_set_color(csp_color_t color) { - - unsigned int color_code, modifier_code; - switch (color & COLOR_MASK_COLOR) { - case COLOR_BLACK: - color_code = 30; break; - case COLOR_RED: - color_code = 31; break; - case COLOR_GREEN: - color_code = 32; break; - case COLOR_YELLOW: - color_code = 33; break; - case COLOR_BLUE: - color_code = 34; break; - case COLOR_MAGENTA: - color_code = 35; break; - case COLOR_CYAN: - color_code = 36; break; - case COLOR_WHITE: - color_code = 37; break; - case COLOR_RESET: - default: - color_code = 0; break; - } - - switch (color & COLOR_MASK_MODIFIER) { - case COLOR_BOLD: - modifier_code = 1; break; - case COLOR_UNDERLINE: - modifier_code = 2; break; - case COLOR_BLINK: - modifier_code = 3; break; - case COLOR_HIDE: - modifier_code = 4; break; - case COLOR_NORMAL: - default: - modifier_code = 0; break; - } - - printf("\033[%u;%um", modifier_code, color_code); -} diff --git a/libcsp/src/arch/posix/csp_thread.c b/libcsp/src/arch/posix/csp_thread.c deleted file mode 100644 index 3277d35d..00000000 --- a/libcsp/src/arch/posix/csp_thread.c +++ /dev/null @@ -1,55 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include -#include -#include - -/* CSP includes */ -#include - -#include - -int csp_thread_create(csp_thread_return_t (* routine)(void *), const char * const thread_name, unsigned short stack_depth, void * parameters, unsigned int priority, csp_thread_handle_t * handle) { - pthread_attr_t attributes, *attr_ref; - int return_code; - - if( pthread_attr_init(&attributes) == 0 ) - { - unsigned int stack_size = PTHREAD_STACK_MIN;// use at least one memory page - - while(stack_size < stack_depth)// must reach at least the provided size - { - stack_size += PTHREAD_STACK_MIN;// keep memory page boundary (some systems may fail otherwise)) - } - attr_ref = &attributes; - - pthread_attr_setdetachstate(attr_ref, PTHREAD_CREATE_DETACHED);// do not waste memory on each call - pthread_attr_setstacksize(attr_ref, stack_size); - } - else - { - attr_ref = NULL; - } - return_code = pthread_create(handle, attr_ref, routine, parameters); - if( attr_ref != NULL ) pthread_attr_destroy(attr_ref); - - return return_code; -} diff --git a/libcsp/src/arch/posix/csp_time.c b/libcsp/src/arch/posix/csp_time.c deleted file mode 100644 index c9677443..00000000 --- a/libcsp/src/arch/posix/csp_time.c +++ /dev/null @@ -1,54 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include -#include -#include - -/* CSP includes */ -#include - -#include - -uint32_t csp_get_ms(void) { - struct timespec ts; - - if (clock_gettime(CLOCK_MONOTONIC, &ts) == 0) - return (uint32_t)(ts.tv_sec*1000+ts.tv_nsec/1000000); - else - return 0; -} - -uint32_t csp_get_ms_isr(void) { - return csp_get_ms(); -} - -uint32_t csp_get_s(void) { - struct timespec ts; - - if (clock_gettime(CLOCK_MONOTONIC, &ts) == 0) - return (uint32_t)ts.tv_sec; - else - return 0; -} - -uint32_t csp_get_s_isr(void) { - return csp_get_s(); -} diff --git a/libcsp/src/arch/posix/pthread_queue.c b/libcsp/src/arch/posix/pthread_queue.c deleted file mode 100644 index e8b6d4ab..00000000 --- a/libcsp/src/arch/posix/pthread_queue.c +++ /dev/null @@ -1,243 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -/* -Inspired by c-pthread-queue by Matthew Dickinson -http://code.google.com/p/c-pthread-queue/ -*/ - -#include -#include -#include -#include -#include -#include -#include - -/* CSP includes */ -#include - -static inline int get_deadline(struct timespec *ts, uint32_t timeout_ms) -{ - int ret = clock_gettime(CLOCK_MONOTONIC, ts); - - if (ret < 0) { - return ret; - } - - uint32_t sec = timeout_ms / 1000; - uint32_t nsec = (timeout_ms - 1000 * sec) * 1000000; - - ts->tv_sec += sec; - - if (ts->tv_nsec + nsec >= 1000000000) { - ts->tv_sec++; - } - - ts->tv_nsec = (ts->tv_nsec + nsec) % 1000000000; - - return ret; -} - -static inline int init_cond_clock_monotonic(pthread_cond_t * cond) -{ - - int ret; - pthread_condattr_t attr; - - pthread_condattr_init(&attr); - ret = pthread_condattr_setclock(&attr, CLOCK_MONOTONIC); - - if (ret == 0) { - ret = pthread_cond_init(cond, &attr); - } - - pthread_condattr_destroy(&attr); - return ret; - -} - -pthread_queue_t * pthread_queue_create(int length, size_t item_size) { - - pthread_queue_t * q = malloc(sizeof(pthread_queue_t)); - - if (q != NULL) { - q->buffer = malloc(length*item_size); - if (q->buffer != NULL) { - q->size = length; - q->item_size = item_size; - q->items = 0; - q->in = 0; - q->out = 0; - if (pthread_mutex_init(&(q->mutex), NULL) || init_cond_clock_monotonic(&(q->cond_full)) || init_cond_clock_monotonic(&(q->cond_empty))) { - free(q->buffer); - free(q); - q = NULL; - } - } else { - free(q); - q = NULL; - } - } - - return q; - -} - -void pthread_queue_delete(pthread_queue_t * q) { - - if (q == NULL) - return; - - free(q->buffer); - free(q); - - return; - -} - - -static inline int wait_slot_available(pthread_queue_t * queue, struct timespec *ts) { - - int ret; - - while (queue->items == queue->size) { - - if (ts != NULL) { - ret = pthread_cond_timedwait(&(queue->cond_full), &(queue->mutex), ts); - } else { - ret = pthread_cond_wait(&(queue->cond_full), &(queue->mutex)); - } - - if (ret != 0 && errno != EINTR) { - return PTHREAD_QUEUE_FULL; //Timeout - } - } - - return PTHREAD_QUEUE_OK; - -} - -int pthread_queue_enqueue(pthread_queue_t * queue, void * value, uint32_t timeout) { - - int ret; - struct timespec ts; - struct timespec *pts = NULL; - - /* Calculate timeout */ - if (timeout != CSP_MAX_DELAY) { - if (get_deadline(&ts, timeout) != 0) { - return PTHREAD_QUEUE_ERROR; - } - pts = &ts; - } else { - pts = NULL; - } - - /* Get queue lock */ - pthread_mutex_lock(&(queue->mutex)); - - ret = wait_slot_available(queue, pts); - if (ret == PTHREAD_QUEUE_OK) { - /* Copy object from input buffer */ - memcpy(queue->buffer+(queue->in * queue->item_size), value, queue->item_size); - queue->items++; - queue->in = (queue->in + 1) % queue->size; - } - - pthread_mutex_unlock(&(queue->mutex)); - - if (ret == PTHREAD_QUEUE_OK) { - /* Nofify blocked threads */ - pthread_cond_broadcast(&(queue->cond_empty)); - } - - return ret; - -} - -static inline int wait_item_available(pthread_queue_t * queue, struct timespec *ts) { - - int ret; - - while (queue->items == 0) { - - if (ts != NULL) { - ret = pthread_cond_timedwait(&(queue->cond_empty), &(queue->mutex), ts); - } else { - ret = pthread_cond_wait(&(queue->cond_empty), &(queue->mutex)); - } - - if (ret != 0 && errno != EINTR) { - return PTHREAD_QUEUE_EMPTY; //Timeout - } - } - - return PTHREAD_QUEUE_OK; - -} - -int pthread_queue_dequeue(pthread_queue_t * queue, void * buf, uint32_t timeout) { - - int ret; - struct timespec ts; - struct timespec *pts; - - /* Calculate timeout */ - if (timeout != CSP_MAX_DELAY) { - if (get_deadline(&ts, timeout) != 0) { - return PTHREAD_QUEUE_ERROR; - } - pts = &ts; - } else { - pts = NULL; - } - - /* Get queue lock */ - pthread_mutex_lock(&(queue->mutex)); - - ret = wait_item_available(queue, pts); - if (ret == PTHREAD_QUEUE_OK) { - /* Coby object to output buffer */ - memcpy(buf, queue->buffer+(queue->out * queue->item_size), queue->item_size); - queue->items--; - queue->out = (queue->out + 1) % queue->size; - } - - pthread_mutex_unlock(&(queue->mutex)); - - if (ret == PTHREAD_QUEUE_OK) { - /* Nofify blocked threads */ - pthread_cond_broadcast(&(queue->cond_full)); - } - - return ret; - -} - -int pthread_queue_items(pthread_queue_t * queue) { - - pthread_mutex_lock(&(queue->mutex)); - int items = queue->items; - pthread_mutex_unlock(&(queue->mutex)); - - return items; - -} diff --git a/libcsp/src/arch/windows/README b/libcsp/src/arch/windows/README deleted file mode 100644 index b97ce7f5..00000000 --- a/libcsp/src/arch/windows/README +++ /dev/null @@ -1,18 +0,0 @@ -This directory contains files specific to the windows port of libcsp. - -To compile and create a static library, execute: - - python waf configure --with-os=windows build - -from the root of this project. Note python must be in PATH. - -The build requirements are: - * Windows Vista SP1 - * A recent version of MinGW _or_ MinGW-w64 - * Windows API headers - * cPython 2.5 or newer - -What provides the Windows API headers depends on the development environment: -Using MinGW: Headers provided by w32api package. windows_glue.h header is needed because these headers do not declare condition variables. -Using MinGW-w64: Headers should be available in the default configuration. You may have to compile the distribution from source. windows_glue.h should not be needed. - diff --git a/libcsp/src/arch/windows/csp_malloc.c b/libcsp/src/arch/windows/csp_malloc.c deleted file mode 100644 index 4b301e49..00000000 --- a/libcsp/src/arch/windows/csp_malloc.c +++ /dev/null @@ -1,9 +0,0 @@ -#include - -void * csp_malloc(size_t size) { - return malloc(size); -} - -void csp_free(void * ptr) { - free(ptr); -} diff --git a/libcsp/src/arch/windows/csp_queue.c b/libcsp/src/arch/windows/csp_queue.c deleted file mode 100644 index 177f8fa9..00000000 --- a/libcsp/src/arch/windows/csp_queue.c +++ /dev/null @@ -1,40 +0,0 @@ -#include -#include -#include -#include "windows_queue.h" - -csp_queue_handle_t csp_queue_create(int length, size_t item_size) { - return windows_queue_create(length, item_size); -} - -void csp_queue_remove(csp_queue_handle_t queue) { - windows_queue_delete(queue); -} - -int csp_queue_enqueue(csp_queue_handle_t handle, void *value, uint32_t timeout) { - return windows_queue_enqueue(handle, value, timeout); -} - -int csp_queue_enqueue_isr(csp_queue_handle_t handle, void * value, CSP_BASE_TYPE * task_woken) { - if( task_woken != NULL ) - *task_woken = 0; - return windows_queue_enqueue(handle, value, 0); -} - -int csp_queue_dequeue(csp_queue_handle_t handle, void *buf, uint32_t timeout) { - return windows_queue_dequeue(handle, buf, timeout); -} - -int csp_queue_dequeue_isr(csp_queue_handle_t handle, void * buf, CSP_BASE_TYPE * task_woken) { - if( task_woken != NULL ) - *task_woken = 0; - return windows_queue_dequeue(handle, buf, 0); -} - -int csp_queue_size(csp_queue_handle_t handle) { - return windows_queue_items(handle); -} - -int csp_queue_size_isr(csp_queue_handle_t handle) { - return windows_queue_items(handle); -} diff --git a/libcsp/src/arch/windows/csp_semaphore.c b/libcsp/src/arch/windows/csp_semaphore.c deleted file mode 100644 index aa69251e..00000000 --- a/libcsp/src/arch/windows/csp_semaphore.c +++ /dev/null @@ -1,74 +0,0 @@ -#include -#include -#include - -int csp_mutex_create(csp_mutex_t * mutex) { - HANDLE mutexHandle = CreateMutex(NULL, FALSE, FALSE); - if( mutexHandle == NULL ) { - return CSP_MUTEX_ERROR; - } - *mutex = mutexHandle; - return CSP_MUTEX_OK; -} - -int csp_mutex_remove(csp_mutex_t * mutex) { - if( !CloseHandle(*mutex) ) { - return CSP_MUTEX_ERROR; - } - return CSP_MUTEX_OK; -} - -int csp_mutex_lock(csp_mutex_t * mutex, uint32_t timeout) { - if(WaitForSingleObject(*mutex, timeout) == WAIT_OBJECT_0) { - return CSP_MUTEX_OK; - } - return CSP_MUTEX_ERROR; - -} - -int csp_mutex_unlock(csp_mutex_t * mutex) { - if( !ReleaseMutex(*mutex) ) { - return CSP_MUTEX_ERROR; - } - return CSP_MUTEX_OK; -} - -int csp_bin_sem_create(csp_bin_sem_handle_t * sem) { - HANDLE semHandle = CreateSemaphore(NULL, 1, 1, NULL); - if( semHandle == NULL ) { - return CSP_SEMAPHORE_ERROR; - } - *sem = semHandle; - return CSP_SEMAPHORE_OK; -} - -int csp_bin_sem_remove(csp_bin_sem_handle_t * sem) { - if( !CloseHandle(*sem) ) { - return CSP_SEMAPHORE_ERROR; - } - return CSP_SEMAPHORE_OK; -} - -int csp_bin_sem_wait(csp_bin_sem_handle_t * sem, uint32_t timeout) { - if( WaitForSingleObject(*sem, timeout) == WAIT_OBJECT_0 ) { - return CSP_SEMAPHORE_OK; - } - return CSP_SEMAPHORE_ERROR; - -} - -int csp_bin_sem_post(csp_bin_sem_handle_t * sem) { - if( !ReleaseSemaphore(*sem, 1, NULL) ) { - return CSP_SEMAPHORE_ERROR; - } - return CSP_SEMAPHORE_OK; -} - -int csp_bin_sem_post_isr(csp_bin_sem_handle_t * sem, CSP_BASE_TYPE * task_woken) { - if( task_woken != NULL ) { - *task_woken = 0; - } - return csp_bin_sem_post(sem); -} - - diff --git a/libcsp/src/arch/windows/csp_system.c b/libcsp/src/arch/windows/csp_system.c deleted file mode 100644 index 262c2052..00000000 --- a/libcsp/src/arch/windows/csp_system.c +++ /dev/null @@ -1,60 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include -#include -#include - -#include -#include - -#include - -int csp_sys_tasklist(char * out) { - strcpy(out, "Tasklist not available on Windows"); - return CSP_ERR_NONE; -} - -uint32_t csp_sys_memfree(void) { - MEMORYSTATUSEX statex; - statex.dwLength = sizeof(statex); - GlobalMemoryStatusEx(&statex); - DWORDLONG freePhysicalMem = statex.ullAvailPhys; - size_t total = (size_t) freePhysicalMem; - return (uint32_t)total; -} - -int csp_sys_reboot(void) { - /* TODO: Fix reboot on Windows */ - csp_log_error("Failed to reboot"); - - return CSP_ERR_INVAL; -} - -int csp_sys_shutdown(void) { - /* TODO: Fix shutdown on Windows */ - csp_log_error("Failed to shutdown"); - - return CSP_ERR_INVAL; -} - -void csp_sys_set_color(csp_color_t color) { - /* TODO: Add Windows color output here */ -} diff --git a/libcsp/src/arch/windows/csp_thread.c b/libcsp/src/arch/windows/csp_thread.c deleted file mode 100644 index ef46a948..00000000 --- a/libcsp/src/arch/windows/csp_thread.c +++ /dev/null @@ -1,11 +0,0 @@ -#include -#include -#include - -int csp_thread_create(csp_thread_return_t (* routine)(void *)__attribute__((stdcall)), const char * const thread_name, unsigned short stack_depth, void * parameters, unsigned int priority, csp_thread_handle_t * handle) { - HANDLE taskHandle = (HANDLE) _beginthreadex(NULL, stack_depth, routine, parameters, 0, 0); - if( taskHandle == 0 ) - return CSP_ERR_NOMEM; // Failure - *handle = taskHandle; - return CSP_ERR_NONE; -} diff --git a/libcsp/src/arch/windows/csp_time.c b/libcsp/src/arch/windows/csp_time.c deleted file mode 100644 index 618292ab..00000000 --- a/libcsp/src/arch/windows/csp_time.c +++ /dev/null @@ -1,20 +0,0 @@ -#include -#include -#include - -uint32_t csp_get_ms(void) { - return (uint32_t)GetTickCount(); -} - -uint32_t csp_get_ms_isr(void) { - return csp_get_ms(); -} - -uint32_t csp_get_s(void) { - uint32_t time_ms = csp_get_ms(); - return time_ms/1000; -} - -uint32_t csp_get_s_isr(void) { - return csp_get_s(); -} diff --git a/libcsp/src/arch/windows/windows_glue.h b/libcsp/src/arch/windows/windows_glue.h deleted file mode 100644 index 6e0cf6db..00000000 --- a/libcsp/src/arch/windows/windows_glue.h +++ /dev/null @@ -1,23 +0,0 @@ -#ifndef WINDOWS_GLUE_H -#define WINDOWS_GLUE_H - -#include -#undef interface - -#if (_WIN32_WINNT >= 0x0600) - -#define RTL_CONDITION_VARIABLE_INIT 0 -#define RTL_CONDITION_VARIABLE_LOCKMODE_SHARED 1 -#define CONDITION_VARIABLE_INIT RTL_CONDITION_VARIABLE_INIT -#define CONDITION_VARIABLE_LOCKMODE_SHARED RTL_CONDITION_VARIABLE_LOCKMODE_SHARED - -typedef PVOID RTL_CONDITION_VARIABLE; -typedef RTL_CONDITION_VARIABLE CONDITION_VARIABLE, *PCONDITION_VARIABLE; - -WINBASEAPI VOID WINAPI InitializeConditionVariable(PCONDITION_VARIABLE ConditionVariable); -WINBASEAPI WINBOOL WINAPI SleepConditionVariableCS(PCONDITION_VARIABLE ConditionVariable, PCRITICAL_SECTION CriticalSection, DWORD dwMilliseconds); -WINBASEAPI VOID WINAPI WakeAllConditionVariable(PCONDITION_VARIABLE ConditionVariable); -WINBASEAPI VOID WINAPI WakeConditionVariable(PCONDITION_VARIABLE ConditionVariable); - -#endif // _WIN#"_WINNT -#endif diff --git a/libcsp/src/arch/windows/windows_queue.c b/libcsp/src/arch/windows/windows_queue.c deleted file mode 100644 index aa337dc8..00000000 --- a/libcsp/src/arch/windows/windows_queue.c +++ /dev/null @@ -1,91 +0,0 @@ -#include "windows_queue.h" -#include "windows_glue.h" -#include - -static int queueFull(windows_queue_t * queue) { - return queue->items == queue->size; -} - -static int queueEmpty(windows_queue_t * queue) { - return queue->items == 0; -} - -windows_queue_t * windows_queue_create(int length, size_t item_size) { - windows_queue_t *queue = (windows_queue_t*)malloc(sizeof(windows_queue_t)); - if(queue == NULL) - goto queue_malloc_failed; - - queue->buffer = malloc(length*item_size); - if(queue->buffer == NULL) - goto buffer_malloc_failed; - - queue->size = length; - queue->item_size = item_size; - queue->items = 0; - queue->head_idx = 0; - - InitializeCriticalSection(&(queue->mutex)); - InitializeConditionVariable(&(queue->cond_full)); - InitializeConditionVariable(&(queue->cond_empty)); - goto queue_init_success; - -buffer_malloc_failed: - free(queue); - queue = NULL; -queue_malloc_failed: -queue_init_success: - return queue; -} - -void windows_queue_delete(windows_queue_t * q) { - if(q==NULL) return; - DeleteCriticalSection(&(q->mutex)); - free(q->buffer); - free(q); -} - -int windows_queue_enqueue(windows_queue_t * queue, void * value, int timeout) { - int offset; - EnterCriticalSection(&(queue->mutex)); - while(queueFull(queue)) { - int ret = SleepConditionVariableCS(&(queue->cond_full), &(queue->mutex), timeout); - if( !ret ) { - LeaveCriticalSection(&(queue->mutex)); - return ret == WAIT_TIMEOUT ? WINDOWS_QUEUE_FULL : WINDOWS_QUEUE_ERROR; - } - } - offset = ((queue->head_idx+queue->items) % queue->size) * queue->item_size; - memcpy((unsigned char*)queue->buffer + offset, value, queue->item_size); - queue->items++; - - LeaveCriticalSection(&(queue->mutex)); - WakeAllConditionVariable(&(queue->cond_empty)); - return WINDOWS_QUEUE_OK; -} - -int windows_queue_dequeue(windows_queue_t * queue, void * buf, int timeout) { - EnterCriticalSection(&(queue->mutex)); - while(queueEmpty(queue)) { - int ret = SleepConditionVariableCS(&(queue->cond_empty), &(queue->mutex), timeout); - if( !ret ) { - LeaveCriticalSection(&(queue->mutex)); - return ret == WAIT_TIMEOUT ? WINDOWS_QUEUE_EMPTY : WINDOWS_QUEUE_ERROR; - } - } - memcpy(buf, (unsigned char*)queue->buffer+(queue->head_idx%queue->size*queue->item_size), queue->item_size); - queue->items--; - queue->head_idx = (queue->head_idx + 1) % queue->size; - - LeaveCriticalSection(&(queue->mutex)); - WakeAllConditionVariable(&(queue->cond_full)); - return WINDOWS_QUEUE_OK; -} - -int windows_queue_items(windows_queue_t * queue) { - int items; - EnterCriticalSection(&(queue->mutex)); - items = queue->items; - LeaveCriticalSection(&(queue->mutex)); - - return items; -} diff --git a/libcsp/src/arch/windows/windows_queue.h b/libcsp/src/arch/windows/windows_queue.h deleted file mode 100644 index e6bc5423..00000000 --- a/libcsp/src/arch/windows/windows_queue.h +++ /dev/null @@ -1,41 +0,0 @@ -#ifndef _WINDOWS_QUEUE_H_ -#define _WINDOWS_QUEUE_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include -#include "windows_glue.h" -#undef interface - -#include - -#define WINDOWS_QUEUE_ERROR CSP_QUEUE_ERROR -#define WINDOWS_QUEUE_EMPTY CSP_QUEUE_ERROR -#define WINDOWS_QUEUE_FULL CSP_QUEUE_ERROR -#define WINDOWS_QUEUE_OK CSP_QUEUE_OK - -typedef struct windows_queue_s { - void * buffer; - int size; - int item_size; - int items; - int head_idx; - CRITICAL_SECTION mutex; - CONDITION_VARIABLE cond_full; - CONDITION_VARIABLE cond_empty; -} windows_queue_t; - -windows_queue_t * windows_queue_create(int length, size_t item_size); -void windows_queue_delete(windows_queue_t * q); -int windows_queue_enqueue(windows_queue_t * queue, void * value, int timeout); -int windows_queue_dequeue(windows_queue_t * queue, void * buf, int timeout); -int windows_queue_items(windows_queue_t * queue); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // _WINDOWS_QUEUE_H_ - diff --git a/libcsp/src/bindings/python/pycsp.c b/libcsp/src/bindings/python/pycsp.c deleted file mode 100644 index f1009d1a..00000000 --- a/libcsp/src/bindings/python/pycsp.c +++ /dev/null @@ -1,1052 +0,0 @@ -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#if PY_MAJOR_VERSION == 3 -#define IS_PY3 -#endif - -static int is_capsule_of_type(PyObject* capsule, const char* expected_type) { - const char* capsule_name = PyCapsule_GetName(capsule); - if (strcmp(capsule_name, expected_type) != 0) { - PyErr_Format( - PyExc_TypeError, - "capsule contains unexpected type, expected=%s, got=%s", - expected_type, capsule_name); // TypeError is thrown - return 0; - } - return 1; -} - -/** - * csp/csp.h - */ - -/* - * void csp_service_handler(csp_conn_t *conn, csp_packet_t *packet); - */ -static PyObject* pycsp_service_handler(PyObject *self, PyObject *args) { - PyObject* conn_capsule; - PyObject* packet_capsule; - if (!PyArg_ParseTuple(args, "OO", &conn_capsule, &packet_capsule)) { - return NULL; // TypeError is thrown - } - - if (!is_capsule_of_type(conn_capsule, "csp_conn_t") || - !is_capsule_of_type(packet_capsule, "csp_packet_t")) { - return NULL; // TypeError is thrown - } - - csp_service_handler( - (csp_conn_t*)PyCapsule_GetPointer(conn_capsule, "csp_conn_t"), - (csp_packet_t*)PyCapsule_GetPointer(packet_capsule, "csp_packet_t")); - - Py_RETURN_NONE; -} - -/* - * int csp_init(uint8_t my_node_address); - */ -static PyObject* pycsp_init(PyObject *self, PyObject *args) { - uint8_t my_node_address; - if (!PyArg_ParseTuple(args, "b", &my_node_address)) { - return NULL; // TypeError is thrown - } - - return Py_BuildValue("i", csp_init(my_node_address)); -} - -/* - * void csp_set_hostname(const char *hostname); - */ -static PyObject* pycsp_set_hostname(PyObject *self, PyObject *args) { - char* hostname; - if (!PyArg_ParseTuple(args, "s", &hostname)) { - return NULL; // TypeError is thrown - } - - csp_set_hostname(hostname); - Py_RETURN_NONE; -} - -/* - * const char *csp_get_hostname(void); - */ -static PyObject* pycsp_get_hostname(PyObject *self, PyObject *args) { - return Py_BuildValue("s", csp_get_hostname()); -} - -/* - * void csp_set_model(const char *model); - */ -static PyObject* pycsp_set_model(PyObject *self, PyObject *args) { - char* model; - if (!PyArg_ParseTuple(args, "s", &model)) { - return NULL; // TypeError is thrown - } - - csp_set_model(model); - Py_RETURN_NONE; -} - -/* - * const char *csp_get_model(void); - */ -static PyObject* pycsp_get_model(PyObject *self, PyObject *args) { - return Py_BuildValue("s", csp_get_model()); -} - -/* - * void csp_set_revision(const char *revision); - */ -static PyObject* pycsp_set_revision(PyObject *self, PyObject *args) { - char* revision; - if (!PyArg_ParseTuple(args, "s", &revision)) { - return NULL; // TypeError is thrown - } - - csp_set_revision(revision); - Py_RETURN_NONE; -} - -/* - * const char *csp_get_revision(void); - */ -static PyObject* pycsp_get_revision(PyObject *self, PyObject *args) { - return Py_BuildValue("s", csp_get_revision()); -} - -/* - * csp_socket_t *csp_socket(uint32_t opts); - */ -static PyObject* pycsp_socket(PyObject *self, PyObject *args) { - uint32_t opts = CSP_SO_NONE; - if (!PyArg_ParseTuple(args, "|I", &opts)) { - return NULL; // TypeError is thrown - } - - return PyCapsule_New(csp_socket(opts), "csp_socket_t", NULL); -} - -/* - * csp_conn_t *csp_accept(csp_socket_t *socket, uint32_t timeout); - */ -static PyObject* pycsp_accept(PyObject *self, PyObject *args) { - PyObject* socket_capsule; - uint32_t timeout = 500; - if (!PyArg_ParseTuple(args, "O|I", &socket_capsule, &timeout)) { - return NULL; // TypeError is thrown - } - - if (!is_capsule_of_type(socket_capsule, "csp_socket_t")) { - return NULL; // TypeError is thrown - } - - void* socket = PyCapsule_GetPointer(socket_capsule, "csp_socket_t"); - csp_conn_t* conn = csp_accept((csp_socket_t*)socket, timeout); - if (conn == NULL) { - Py_RETURN_NONE; // because a capsule cannot contain a NULL-pointer - } - - return PyCapsule_New(conn, "csp_conn_t", NULL); -} - -/* - * csp_packet_t *csp_read(csp_conn_t *conn, uint32_t timeout); - */ -static PyObject* pycsp_read(PyObject *self, PyObject *args) { - PyObject* conn_capsule; - uint32_t timeout = 500; - if (!PyArg_ParseTuple(args, "O|I", &conn_capsule, &timeout)) { - return NULL; // TypeError is thrown - } - - if (!is_capsule_of_type(conn_capsule, "csp_conn_t")) { - return NULL; // TypeError is thrown - } - - void* conn = PyCapsule_GetPointer(conn_capsule, "csp_conn_t"); - csp_packet_t* packet = csp_read((csp_conn_t*)conn, timeout); - if (packet == NULL) { - Py_RETURN_NONE; // because capsule cannot contain a NULL-pointer - } - - return PyCapsule_New(packet, "csp_packet_t", NULL); -} - -/* -* int csp_send(csp_conn_t * conn, csp_packet_t * packet, uint32_t timeout) -*/ -static PyObject* pycsp_send(PyObject *self, PyObject *args) { - PyObject* conn_capsule; - PyObject* packet_capsule; - uint32_t timeout = 500; - if (!PyArg_ParseTuple(args, "OO|I", &conn_capsule, &packet_capsule, &timeout)) { - return NULL; // TypeError is thrown - } - - if (!is_capsule_of_type(conn_capsule, "csp_conn_t")) { - return NULL; // TypeError is thrown - } - - void* packet = PyCapsule_GetPointer(packet_capsule, "csp_packet_t"); - if (packet == NULL) { - Py_RETURN_NONE; - } - - void* conn = PyCapsule_GetPointer(conn_capsule, "csp_conn_t"); - - int result = csp_send(conn, packet, timeout); - - return Py_BuildValue("i", result); -} - -/* - * int csp_transaction(uint8_t prio, uint8_t dest, uint8_t port, - * uint32_t timeout, void *outbuf, int outlen, - * void *inbuf, int inlen); - */ -static PyObject* pycsp_transaction(PyObject *self, PyObject *args) { - uint8_t prio; - uint8_t dest; - uint8_t port; - uint32_t timeout; - Py_buffer inbuf; - Py_buffer outbuf; - if (!PyArg_ParseTuple(args, "bbbIw*w*", &prio, &dest, &port, &timeout, &outbuf, &inbuf)) { - return NULL; // TypeError is thrown - } - - int result = csp_transaction(prio, dest, port, timeout, - outbuf.buf, outbuf.len, - inbuf.buf, inbuf.len); - - return Py_BuildValue("i", result); -} - -/* int csp_sendto(uint8_t prio, uint8_t dest, uint8_t dport, uint8_t src_port, uint32_t opts, csp_packet_t *packet, uint32_t timeout); */ -static PyObject* pycsp_sendto(PyObject *self, PyObject *args) { - uint8_t prio; - uint8_t dest; - uint8_t dport; - uint8_t src_port; - uint32_t opts; - PyObject* packet_capsule; - uint32_t timeout; - if (!PyArg_ParseTuple(args, "bbbbIOI", &prio, &dest, &dport, &src_port, &opts, &packet_capsule, &timeout)) { - Py_RETURN_NONE; - } - - void* packet = PyCapsule_GetPointer(packet_capsule, "csp_packet_t"); - if (packet == NULL) { - Py_RETURN_NONE; - } - - return Py_BuildValue("i", csp_sendto(prio, - dest, - dport, - src_port, - opts, - (csp_packet_t*)packet, - timeout)); -} - - -/* - * int csp_sendto_reply(csp_packet_t * request_packet, - * csp_packet_t * reply_packet, - * uint32_t opts, uint32_t timeout); - */ -static PyObject* pycsp_sendto_reply(PyObject *self, PyObject *args) { - PyObject* request_packet_capsule; - PyObject* reply_packet_capsule; - uint32_t opts = CSP_O_NONE; - uint32_t timeout = 500; - if (!PyArg_ParseTuple(args, "OO|II", &request_packet_capsule, &reply_packet_capsule, &opts, &timeout)) { - return NULL; // TypeError is thrown - } - - if (!is_capsule_of_type(request_packet_capsule, "csp_packet_t") || - !is_capsule_of_type(reply_packet_capsule, "csp_packet_t")) { - return NULL; // TypeError is thrown - } - - void* request_packet = PyCapsule_GetPointer(request_packet_capsule, "csp_packet_t"); - void* reply_packet = PyCapsule_GetPointer(reply_packet_capsule, "csp_packet_t"); - - return Py_BuildValue("i", csp_sendto_reply((csp_packet_t*)request_packet, - (csp_packet_t*)reply_packet, - opts, - timeout)); -} - -/* - * csp_conn_t *csp_connect(uint8_t prio, uint8_t dest, uint8_t dport, uint32_t timeout, uint32_t opts); - */ -static PyObject* pycsp_connect(PyObject *self, PyObject *args) { - uint8_t prio; - uint8_t dest; - uint8_t dport; - uint32_t timeout; - uint32_t opts; - if (!PyArg_ParseTuple(args, "bbbII", &prio, &dest, &dport, &timeout, &opts)) { - return NULL; // TypeError is thrown - } - - csp_conn_t *conn = csp_connect(prio, dest, dport, timeout,opts); - - return PyCapsule_New(conn, "csp_conn_t", NULL); -} - -/* - * int csp_close(csp_conn_t *conn); - */ -static PyObject* pycsp_close(PyObject *self, PyObject *conn_capsule) { - if (!is_capsule_of_type(conn_capsule, "csp_conn_t")) { - return NULL; // TypeError is thrown - } - - void *conn = PyCapsule_GetPointer(conn_capsule, "csp_conn_t"); - return Py_BuildValue("i", csp_close((csp_conn_t*)conn)); -} - -/* - * int csp_conn_dport(csp_conn_t *conn); - */ -static PyObject* pycsp_conn_dport(PyObject *self, PyObject *conn_capsule) { - if (!is_capsule_of_type(conn_capsule, "csp_conn_t")) { - return NULL; // TypeError is thrown - } - - void* conn = PyCapsule_GetPointer(conn_capsule, "csp_conn_t"); - return Py_BuildValue("i", csp_conn_dport((csp_conn_t*)conn)); -} - -/* - * int csp_conn_sport(csp_conn_t *conn); - */ -static PyObject* pycsp_conn_sport(PyObject *self, PyObject *conn_capsule) { - if (!is_capsule_of_type(conn_capsule, "csp_conn_t")) { - return NULL; // TypeError is thrown - } - - void* conn = PyCapsule_GetPointer(conn_capsule, "csp_conn_t"); - return Py_BuildValue("i", csp_conn_sport((csp_conn_t*)conn)); -} - -/* int csp_conn_dst(csp_conn_t *conn); */ -static PyObject* pycsp_conn_dst(PyObject *self, PyObject *conn_capsule) { - if (!is_capsule_of_type(conn_capsule, "csp_conn_t")) { - return NULL; // TypeError is thrown - } - - void* conn = PyCapsule_GetPointer(conn_capsule, "csp_conn_t"); - return Py_BuildValue("i", csp_conn_dst((csp_conn_t*)conn)); -} - -/* - * int csp_conn_src(csp_conn_t *conn); - */ -static PyObject* pycsp_conn_src(PyObject *self, PyObject *conn_capsule) { - if (!is_capsule_of_type(conn_capsule, "csp_conn_t")) { - return NULL; // TypeError is thrown - } - - void* conn = PyCapsule_GetPointer(conn_capsule, "csp_conn_t"); - return Py_BuildValue("i", csp_conn_src((csp_conn_t*)conn)); -} - -/* int csp_listen(csp_socket_t *socket, size_t conn_queue_length); */ -static PyObject* pycsp_listen(PyObject *self, PyObject *args) { - PyObject* socket_capsule; - size_t conn_queue_len = 10; - if (!PyArg_ParseTuple(args, "O|n", &socket_capsule, &conn_queue_len)) { - return NULL; // TypeError is thrown - } - - if (!is_capsule_of_type(socket_capsule, "csp_socket_t")) { - return NULL; // TypeError is thrown - } - - void* sock = PyCapsule_GetPointer(socket_capsule, "csp_socket_t"); - return Py_BuildValue("i", csp_listen((csp_socket_t*)sock, conn_queue_len)); -} - -/* int csp_bind(csp_socket_t *socket, uint8_t port); */ -static PyObject* pycsp_bind(PyObject *self, PyObject *args) { - PyObject* socket_capsule; - uint8_t port; - if (!PyArg_ParseTuple(args, "Ob", &socket_capsule, &port)) { - return NULL; // TypeError is thrown - } - - if (!is_capsule_of_type(socket_capsule, "csp_socket_t")) { - return NULL; // TypeError is thrown - } - - void* sock = PyCapsule_GetPointer(socket_capsule, "csp_socket_t"); - return Py_BuildValue("i", csp_bind((csp_socket_t*)sock, port)); -} - -/* int csp_route_start_task(unsigned int task_stack_size, unsigned int priority); */ -static PyObject* pycsp_route_start_task(PyObject *self, PyObject *args) { - unsigned int priority = CSP_PRIO_NORM; - if (!PyArg_ParseTuple(args, "|I", &priority)) { - return NULL; // TypeError is thrown - } - - return Py_BuildValue("i", csp_route_start_task(0, priority)); -} - -/* - * int csp_ping(uint8_t node, uint32_t timeout, - * unsigned int size, uint8_t conn_options); - */ -static PyObject* pycsp_ping(PyObject *self, PyObject *args) { - uint8_t node; - uint32_t timeout = 500; - unsigned int size = 100; - uint8_t conn_options = CSP_O_NONE; - if (!PyArg_ParseTuple(args, "b|IIb", &node, &timeout, &size, &conn_options)) { - return NULL; // TypeError is thrown - } - - return Py_BuildValue("i", csp_ping(node, timeout, size, conn_options)); -} - -/* - * void csp_reboot(uint8_t node); - */ -static PyObject* pycsp_reboot(PyObject *self, PyObject *args) { - uint8_t node; - if (!PyArg_ParseTuple(args, "b", &node)) { - return NULL; // TypeError is thrown - } - - csp_reboot(node); - Py_RETURN_NONE; -} - -/* - * void csp_shutdown(uint8_t node); - */ -static PyObject* pycsp_shutdown(PyObject *self, PyObject *args) { - uint8_t node; - if (!PyArg_ParseTuple(args, "b", &node)) { - return NULL; // TypeError is thrown - } - - csp_shutdown(node); - Py_RETURN_NONE; -} - -/* - * void csp_rdp_set_opt(unsigned int window_size, - * unsigned int conn_timeout_ms, - * unsigned int packet_timeout_ms, - * unsigned int delayed_acks, - * unsigned int ack_timeout, - * unsigned int ack_delay_count); - */ -static PyObject* pycsp_rdp_set_opt(PyObject *self, PyObject *args) { - unsigned int window_size; - unsigned int conn_timeout_ms; - unsigned int packet_timeout_ms; - unsigned int delayed_acks; - unsigned int ack_timeout; - unsigned int ack_delay_count; - if (!PyArg_ParseTuple(args, "IIIIII", &window_size, &conn_timeout_ms, - &packet_timeout_ms, &delayed_acks, - &ack_timeout, &ack_delay_count)) { - return NULL; // TypeError is thrown - } -#ifdef CSP_USE_RDP - csp_rdp_set_opt(window_size, conn_timeout_ms, packet_timeout_ms, - delayed_acks, ack_timeout, ack_delay_count); -#endif - Py_RETURN_NONE; -} - -/* - * void csp_rdp_get_opt(unsigned int *window_size, - * unsigned int *conn_timeout_ms, - * unsigned int *packet_timeout_ms, - * unsigned int *delayed_acks, - * unsigned int *ack_timeout, - * unsigned int *ack_delay_count); - */ -static PyObject* pycsp_rdp_get_opt(PyObject *self, PyObject *args) { - - unsigned int window_size = 0; - unsigned int conn_timeout_ms = 0; - unsigned int packet_timeout_ms = 0; - unsigned int delayed_acks = 0; - unsigned int ack_timeout = 0; - unsigned int ack_delay_count = 0; -#ifdef CSP_USE_RDP - csp_rdp_get_opt(&window_size, - &conn_timeout_ms, - &packet_timeout_ms, - &delayed_acks, - &ack_timeout, - &ack_delay_count); -#endif - return Py_BuildValue("IIIIII", - window_size, - conn_timeout_ms, - packet_timeout_ms, - delayed_acks, - ack_timeout, - ack_delay_count); -} - - -/* - * - * int csp_xtea_set_key(char *key, uint32_t keylen); - */ -static PyObject* pycsp_xtea_set_key(PyObject *self, PyObject *args) { - char* key; - uint32_t keylen; - if (!PyArg_ParseTuple(args, "si", &key, &keylen)) { - return NULL; // TypeError is thrown - } - return Py_BuildValue("i", csp_xtea_set_key(key, keylen)); -} -/** - * csp/csp_rtable.h - */ - -/* - * int csp_rtable_set(uint8_t node, uint8_t mask, - * csp_iface_t *ifc, uint8_t mac); - */ -static PyObject* pycsp_rtable_set(PyObject *self, PyObject *args) { - uint8_t node; - uint8_t mask; - char* interface_name; - uint8_t mac = CSP_NODE_MAC; - if (!PyArg_ParseTuple(args, "bbs|b", &node, &mask, &interface_name, &mac)) { - return NULL; // TypeError is thrown - } - - return Py_BuildValue("i", csp_rtable_set(node, - mask, - csp_iflist_get_by_name(interface_name), - mac)); -} - -/* - * void csp_rtable_clear(void); - */ -static PyObject* pycsp_rtable_clear(PyObject *self, PyObject *args) { - csp_rtable_clear(); - Py_RETURN_NONE; -} - -/* -* int csp_rtable_check(const char * buffer) -*/ -static PyObject* pycsp_rtable_check(PyObject *self, PyObject *args) { - char* buffer; - if (!PyArg_ParseTuple(args, "s", &buffer)) { - return NULL; // TypeError is thrown - } - - return Py_BuildValue("i", csp_rtable_check(buffer)); -} - -/* -* void csp_rtable_load(const char * buffer) -*/ -static PyObject* pycsp_rtable_load(PyObject *self, PyObject *args) { - char* buffer; - if (!PyArg_ParseTuple(args, "s", &buffer)) { - return NULL; // TypeError is thrown - } - - csp_rtable_load(buffer); - Py_RETURN_NONE; -} - -/** - * csp/csp_buffer.h - */ - -/* - * int csp_buffer_init(int count, int size); - */ -static PyObject* pycsp_buffer_init(PyObject *self, PyObject *args) { - int count; - int size; - if (!PyArg_ParseTuple(args, "ii", &count, &size)) { - return NULL; // TypeError is thrown - } - - return Py_BuildValue("i", csp_buffer_init(count, size)); -} - -/* - * void * csp_buffer_get(size_t size); - */ -static PyObject* pycsp_buffer_get(PyObject *self, PyObject *args) { - size_t size; - if (!PyArg_ParseTuple(args, "n", &size)) { - return NULL; // TypeError is thrown - } - - void* packet = csp_buffer_get(size); - if (packet == NULL) { - Py_RETURN_NONE; - } - - return PyCapsule_New(packet, "csp_packet_t", NULL); -} -/* - * void csp_buffer_free(void *packet); - */ -static PyObject* pycsp_buffer_free(PyObject *self, PyObject *args) { - PyObject* packet_capsule; - if (!PyArg_ParseTuple(args, "O", &packet_capsule)) { - return NULL; // TypeError is thrown - } - - - if (!is_capsule_of_type(packet_capsule, "csp_packet_t")) { - return NULL; // TypeError is thrown - } - - csp_buffer_free(PyCapsule_GetPointer(packet_capsule, "csp_packet_t")); - Py_RETURN_NONE; -} - -/* - * int csp_buffer_remaining(void); - */ -static PyObject* pycsp_buffer_remaining(PyObject *self, PyObject *args) { - return Py_BuildValue("i", csp_buffer_remaining()); -} - -/** - * csp/csp_cmp.h - */ - -/* - * static inline int csp_cmp_ident(uint8_t node, uint32_t timeout, - * struct csp_cmp_message *msg) - */ -static PyObject* pycsp_cmp_ident(PyObject *self, PyObject *args) { - uint8_t node; - uint32_t timeout = 500; - if (!PyArg_ParseTuple(args, "b|i", &node, &timeout)) { - return NULL; // TypeError is thrown - } - - struct csp_cmp_message msg; - int rc = csp_cmp_ident(node, timeout, &msg); - return Py_BuildValue("isssss", - rc, - msg.ident.hostname, - msg.ident.model, - msg.ident.revision, - msg.ident.date, - msg.ident.time); -} - -/* - * static inline int csp_cmp_route_set(uint8_t node, uint32_t timeout, - * struct csp_cmp_message *msg) - */ -static PyObject* pycsp_cmp_route_set(PyObject *self, PyObject *args) { - uint8_t node; - uint32_t timeout = 500; - uint8_t addr; - uint8_t mac; - char* ifstr; - if (!PyArg_ParseTuple(args, "bibbs", &node, &timeout, &addr, &mac, &ifstr)) { - return NULL; // TypeError is thrown - } - - struct csp_cmp_message msg; - msg.route_set.dest_node = addr; - msg.route_set.next_hop_mac = mac; - strncpy(msg.route_set.interface, ifstr, CSP_CMP_ROUTE_IFACE_LEN); - int rc = csp_cmp_route_set(node, timeout, &msg); - return Py_BuildValue("i", - rc); -} - -/* static inline int pycsp_cmp_peek(uint8_t node, uint32_t timeout, struct csp_cmp_message *msg); */ -static PyObject* pycsp_cmp_peek(PyObject *self, PyObject *args) { - uint8_t node; - uint32_t timeout; - uint8_t len; - uint32_t addr; - Py_buffer outbuf; - - if (!PyArg_ParseTuple(args, "biibw*", &node, &timeout, &addr, &len, &outbuf)) { - Py_RETURN_NONE; - } - - if (len > CSP_CMP_PEEK_MAX_LEN) { - len = CSP_CMP_PEEK_MAX_LEN; - } - struct csp_cmp_message msg; - msg.peek.addr = csp_hton32(addr); - msg.peek.len = len; - int rc = csp_cmp_peek(node, timeout, &msg); - if (rc != CSP_ERR_NONE) { - Py_RETURN_NONE; - } - memcpy(outbuf.buf, msg.peek.data, len); - outbuf.len = len; - - return Py_BuildValue("i", rc); -} - -/* static inline int pycsp_cmp_poke(uint8_t node, uint32_t timeout, struct csp_cmp_message *msg); */ -static PyObject* pycsp_cmp_poke(PyObject *self, PyObject *args) { - uint8_t node; - uint32_t timeout; - uint8_t len; - uint32_t addr; - Py_buffer inbuf; - - if (!PyArg_ParseTuple(args, "biibw*", &node, &timeout, &addr, &len, &inbuf)) { - Py_RETURN_NONE; - } - - if (len > CSP_CMP_POKE_MAX_LEN) { - len = CSP_CMP_POKE_MAX_LEN; - } - struct csp_cmp_message msg; - msg.poke.addr = csp_hton32(addr); - msg.poke.len = len; - memcpy(msg.poke.data, inbuf.buf, len); - int rc = csp_cmp_poke(node, timeout, &msg); - if (rc != CSP_ERR_NONE) { - Py_RETURN_NONE; - } - - return Py_BuildValue("i", rc); -} - -/* static inline int csp_cmp_clock(uint8_t node, uint32_t timeout, struct csp_cmp_message *msg); */ -static PyObject* pycsp_cmp_clock(PyObject *self, PyObject *args) { - uint8_t node; - uint32_t timeout; - uint32_t sec; - uint32_t nsec; - if (!PyArg_ParseTuple(args, "bIII", &node, &timeout, &sec, &nsec)) { - Py_RETURN_NONE; - } - - struct csp_cmp_message msg; - msg.clock.tv_sec = csp_hton32(sec); - msg.clock.tv_nsec = csp_hton32(nsec); - return Py_BuildValue("i", csp_cmp_clock(node, timeout, &msg)); -} - -/** - * csp/interfaces/csp_if_zmqhub.h - */ - -/* - * int csp_zmqhub_init(char addr, char * host); - */ -static PyObject* pycsp_zmqhub_init(PyObject *self, PyObject *args) { - char addr; - char* host; - if (!PyArg_ParseTuple(args, "bs", &addr, &host)) { - return NULL; // TypeError is thrown - } - - return Py_BuildValue("i", csp_zmqhub_init(addr, host)); -} - -/** - * csp/drivers/can_socketcan.h - */ - -/* - * csp_iface_t * csp_can_socketcan_init(const char * ifc, int bitrate, int promisc); - */ -static PyObject* pycsp_can_socketcan_init(PyObject *self, PyObject *args) -{ - char* ifc; - int bitrate = 1000000; - int promisc = 0; - - if (!PyArg_ParseTuple(args, "s|ii", &ifc, &bitrate, &promisc)) - { - return NULL; - } - - csp_can_socketcan_init(ifc, bitrate, promisc); - Py_RETURN_NONE; -} - - -/** - * csp/interfaces/csp_if_kiss.h - */ - -/* - * int csp_kiss_init(char addr, char * host); - */ -static PyObject* pycsp_kiss_init(PyObject *self, PyObject *args) { - char* device; - uint32_t baudrate = 500000; - uint32_t mtu = 512; - const char* if_name = "KISS"; - if (!PyArg_ParseTuple(args, "s|IIs", &device, &baudrate, &mtu, &if_name)) { - return NULL; // TypeError is thrown - } - - static csp_iface_t csp_if_kiss; - static csp_kiss_handle_t csp_kiss_driver; - csp_if_kiss.mtu = (uint16_t) mtu; - struct usart_conf conf = {.device = device, .baudrate = baudrate}; - csp_kiss_init(&csp_if_kiss, &csp_kiss_driver, usart_putc, usart_insert, if_name); - usart_init(&conf); - - void my_usart_rx(uint8_t * buf, int len, void * pxTaskWoken) { - csp_kiss_rx(&csp_if_kiss, buf, len, pxTaskWoken); - } - usart_set_callback(my_usart_rx); - - Py_RETURN_NONE; -} - -/** - * Helpers - accessing csp_packet_t members - */ -static PyObject* pycsp_packet_set_data(PyObject *self, PyObject *args) { - PyObject* packet_capsule; - Py_buffer data; - if (!PyArg_ParseTuple(args, "Ow*", &packet_capsule, &data)) { - return NULL; // TypeError is thrown - } - - if (!is_capsule_of_type(packet_capsule, "csp_packet_t")) { - return NULL; // TypeError is thrown - } - - csp_packet_t* packet = PyCapsule_GetPointer(packet_capsule, "csp_packet_t"); - - memcpy((char *)packet->data, data.buf, data.len); - packet->length = data.len; - - Py_RETURN_NONE; -} -static PyObject* pycsp_packet_get_data(PyObject *self, PyObject *packet_capsule) { - if (!is_capsule_of_type(packet_capsule, "csp_packet_t")) { - return NULL; // TypeError is thrown - } - - csp_packet_t* packet = PyCapsule_GetPointer(packet_capsule, "csp_packet_t"); -#ifdef IS_PY3 - return Py_BuildValue("y#", packet->data, packet->length); -#else - return Py_BuildValue("s#", packet->data, packet->length); -#endif -} - -static PyObject* pycsp_packet_get_length(PyObject *self, PyObject *packet_capsule) { - if (!is_capsule_of_type(packet_capsule, "csp_packet_t")) { - return NULL; // TypeError is thrown - } - - csp_packet_t* packet = PyCapsule_GetPointer(packet_capsule, "csp_packet_t"); - return Py_BuildValue("H", packet->length); -} - -static PyMethodDef methods[] = { - - /* csp/csp.h */ - {"service_handler", pycsp_service_handler, METH_VARARGS, ""}, - {"init", pycsp_init, METH_VARARGS, ""}, - {"set_hostname", pycsp_set_hostname, METH_VARARGS, ""}, - {"get_hostname", pycsp_get_hostname, METH_NOARGS, ""}, - {"set_model", pycsp_set_model, METH_VARARGS, ""}, - {"get_model", pycsp_get_model, METH_NOARGS, ""}, - {"set_revision", pycsp_set_revision, METH_VARARGS, ""}, - {"get_revision", pycsp_get_revision, METH_NOARGS, ""}, - {"socket", pycsp_socket, METH_VARARGS, ""}, - {"accept", pycsp_accept, METH_VARARGS, ""}, - {"read", pycsp_read, METH_VARARGS, ""}, - {"send", pycsp_send, METH_VARARGS, ""}, - {"transaction", pycsp_transaction, METH_VARARGS, ""}, - {"sendto_reply", pycsp_sendto_reply, METH_VARARGS, ""}, - {"sendto", pycsp_sendto, METH_VARARGS, ""}, - {"connect", pycsp_connect, METH_VARARGS, ""}, - {"close", pycsp_close, METH_O, ""}, - {"conn_dport", pycsp_conn_dport, METH_O, ""}, - {"conn_sport", pycsp_conn_sport, METH_O, ""}, - {"conn_dst", pycsp_conn_dst, METH_O, ""}, - {"conn_src", pycsp_conn_src, METH_O, ""}, - {"listen", pycsp_listen, METH_VARARGS, ""}, - {"bind", pycsp_bind, METH_VARARGS, ""}, - {"route_start_task", pycsp_route_start_task, METH_VARARGS, ""}, - {"ping", pycsp_ping, METH_VARARGS, ""}, - {"reboot", pycsp_reboot, METH_VARARGS, ""}, - {"shutdown", pycsp_shutdown, METH_VARARGS, ""}, - {"rdp_set_opt", pycsp_rdp_set_opt, METH_VARARGS, ""}, - {"rdp_get_opt", pycsp_rdp_get_opt, METH_NOARGS, ""}, - {"xtea_set_key", pycsp_xtea_set_key, METH_VARARGS, ""}, - - /* csp/csp_rtable.h */ - {"rtable_set", pycsp_rtable_set, METH_VARARGS, ""}, - {"rtable_clear", pycsp_rtable_clear, METH_NOARGS, ""}, - {"rtable_check", pycsp_rtable_check, METH_VARARGS, ""}, - {"rtable_load", pycsp_rtable_load, METH_VARARGS, ""}, - - /* csp/csp_buffer.h */ - {"buffer_init", pycsp_buffer_init, METH_VARARGS, ""}, - {"buffer_free", pycsp_buffer_free, METH_VARARGS, ""}, - {"buffer_get", pycsp_buffer_get, METH_VARARGS, ""}, - {"buffer_remaining", pycsp_buffer_remaining, METH_NOARGS, ""}, - - /* csp/csp_cmp.h */ - {"cmp_ident", pycsp_cmp_ident, METH_VARARGS, ""}, - {"cmp_route_set", pycsp_cmp_route_set, METH_VARARGS, ""}, - {"cmp_peek", pycsp_cmp_peek, METH_VARARGS, ""}, - {"cmp_poke", pycsp_cmp_poke, METH_VARARGS, ""}, - {"cmp_clock", pycsp_cmp_clock, METH_VARARGS, ""}, - - - /* csp/interfaces/csp_if_zmqhub.h */ - {"zmqhub_init", pycsp_zmqhub_init, METH_VARARGS, ""}, - {"kiss_init", pycsp_kiss_init, METH_VARARGS, ""}, - - /* csp/drivers/can_socketcan.h */ - {"can_socketcan_init", pycsp_can_socketcan_init, METH_VARARGS, ""}, - - /* helpers */ - {"packet_get_length", pycsp_packet_get_length, METH_O, ""}, - {"packet_get_data", pycsp_packet_get_data, METH_O, ""}, - {"packet_set_data", pycsp_packet_set_data, METH_VARARGS, ""}, - - /* sentinel */ - {NULL, NULL, 0, NULL} -}; - -#ifdef IS_PY3 -static struct PyModuleDef moduledef = { - PyModuleDef_HEAD_INIT, - "libcsp_py3", - NULL, - -1, - methods, - NULL, - NULL, - NULL, - NULL -}; -#endif - -#ifdef IS_PY3 -PyMODINIT_FUNC PyInit_libcsp_py3(void) { -#else - PyMODINIT_FUNC initlibcsp_py2(void) { -#endif - - PyObject* m; - -#ifdef IS_PY3 - m = PyModule_Create(&moduledef); -#else - m = Py_InitModule("libcsp_py2", methods); -#endif - /** - * csp/csp_types.h - */ - - /* RESERVED PORTS */ - PyModule_AddIntConstant(m, "CSP_CMP", CSP_CMP); - PyModule_AddIntConstant(m, "CSP_PING", CSP_PING); - PyModule_AddIntConstant(m, "CSP_PS", CSP_PS); - PyModule_AddIntConstant(m, "CSP_MEMFREE", CSP_MEMFREE); - PyModule_AddIntConstant(m, "CSP_REBOOT", CSP_REBOOT); - PyModule_AddIntConstant(m, "CSP_BUF_FREE", CSP_BUF_FREE); - PyModule_AddIntConstant(m, "CSP_UPTIME", CSP_UPTIME); - PyModule_AddIntConstant(m, "CSP_ANY", CSP_MAX_BIND_PORT + 1); - PyModule_AddIntConstant(m, "CSP_PROMISC", CSP_MAX_BIND_PORT + 2); - - /* PRIORITIES */ - PyModule_AddIntConstant(m, "CSP_PRIO_CRITICAL", CSP_PRIO_CRITICAL); - PyModule_AddIntConstant(m, "CSP_PRIO_HIGH", CSP_PRIO_HIGH); - PyModule_AddIntConstant(m, "CSP_PRIO_NORM", CSP_PRIO_NORM); - PyModule_AddIntConstant(m, "CSP_PRIO_LOW", CSP_PRIO_LOW); - - /* FLAGS */ - PyModule_AddIntConstant(m, "CSP_FFRAG", CSP_FFRAG); - PyModule_AddIntConstant(m, "CSP_FHMAC", CSP_FHMAC); - PyModule_AddIntConstant(m, "CSP_FXTEA", CSP_FXTEA); - PyModule_AddIntConstant(m, "CSP_FRDP", CSP_FRDP); - PyModule_AddIntConstant(m, "CSP_FCRC32", CSP_FCRC32); - - /* SOCKET OPTIONS */ - PyModule_AddIntConstant(m, "CSP_SO_NONE", CSP_SO_NONE); - PyModule_AddIntConstant(m, "CSP_SO_RDPREQ", CSP_SO_RDPREQ); - PyModule_AddIntConstant(m, "CSP_SO_RDPPROHIB", CSP_SO_RDPPROHIB); - PyModule_AddIntConstant(m, "CSP_SO_HMACREQ", CSP_SO_HMACREQ); - PyModule_AddIntConstant(m, "CSP_SO_HMACPROHIB", CSP_SO_HMACPROHIB); - PyModule_AddIntConstant(m, "CSP_SO_XTEAREQ", CSP_SO_XTEAREQ); - PyModule_AddIntConstant(m, "CSP_SO_XTEAPROHIB", CSP_SO_XTEAPROHIB); - PyModule_AddIntConstant(m, "CSP_SO_CRC32REQ", CSP_SO_CRC32REQ); - PyModule_AddIntConstant(m, "CSP_SO_CRC32PROHIB", CSP_SO_CRC32PROHIB); - PyModule_AddIntConstant(m, "CSP_SO_CONN_LESS", CSP_SO_CONN_LESS); - - /* CONNECT OPTIONS */ - PyModule_AddIntConstant(m, "CSP_O_NONE", CSP_O_NONE); - PyModule_AddIntConstant(m, "CSP_O_RDP", CSP_O_RDP); - PyModule_AddIntConstant(m, "CSP_O_NORDP", CSP_O_NORDP); - PyModule_AddIntConstant(m, "CSP_O_HMAC", CSP_O_HMAC); - PyModule_AddIntConstant(m, "CSP_O_NOHMAC", CSP_O_NOHMAC); - PyModule_AddIntConstant(m, "CSP_O_XTEA", CSP_O_XTEA); - PyModule_AddIntConstant(m, "CSP_O_NOXTEA", CSP_O_NOXTEA); - PyModule_AddIntConstant(m, "CSP_O_CRC32", CSP_O_CRC32); - PyModule_AddIntConstant(m, "CSP_O_NOCRC32", CSP_O_NOCRC32); - - - /** - * csp/csp_error.h - */ - - PyModule_AddIntConstant(m, "CSP_ERR_NONE", CSP_ERR_NONE); - PyModule_AddIntConstant(m, "CSP_ERR_NOMEM", CSP_ERR_NOMEM); - PyModule_AddIntConstant(m, "CSP_ERR_INVAL", CSP_ERR_INVAL); - PyModule_AddIntConstant(m, "CSP_ERR_TIMEDOUT", CSP_ERR_TIMEDOUT); - PyModule_AddIntConstant(m, "CSP_ERR_USED", CSP_ERR_USED); - PyModule_AddIntConstant(m, "CSP_ERR_NOTSUP", CSP_ERR_NOTSUP); - PyModule_AddIntConstant(m, "CSP_ERR_BUSY", CSP_ERR_BUSY); - PyModule_AddIntConstant(m, "CSP_ERR_ALREADY", CSP_ERR_ALREADY); - PyModule_AddIntConstant(m, "CSP_ERR_RESET", CSP_ERR_RESET); - PyModule_AddIntConstant(m, "CSP_ERR_NOBUFS", CSP_ERR_NOBUFS); - PyModule_AddIntConstant(m, "CSP_ERR_TX", CSP_ERR_TX); - PyModule_AddIntConstant(m, "CSP_ERR_DRIVER", CSP_ERR_DRIVER); - PyModule_AddIntConstant(m, "CSP_ERR_AGAIN", CSP_ERR_AGAIN); - PyModule_AddIntConstant(m, "CSP_ERR_HMAC", CSP_ERR_HMAC); - PyModule_AddIntConstant(m, "CSP_ERR_XTEA", CSP_ERR_XTEA); - PyModule_AddIntConstant(m, "CSP_ERR_CRC32", CSP_ERR_CRC32); - - /** - * csp/rtable.h - */ - PyModule_AddIntConstant(m, "CSP_NODE_MAC", CSP_NODE_MAC); - -#ifdef IS_PY3 - return m; -#endif - } - diff --git a/libcsp/src/crypto/CMakeLists.txt b/libcsp/src/crypto/CMakeLists.txt deleted file mode 100644 index 19cb878a..00000000 --- a/libcsp/src/crypto/CMakeLists.txt +++ /dev/null @@ -1,5 +0,0 @@ -target_sources(${LIB_CSP_NAME} PRIVATE - csp_hmac.c - csp_sha1.c - csp_xtea.c -) diff --git a/libcsp/src/crypto/csp_hmac.c b/libcsp/src/crypto/csp_hmac.c deleted file mode 100644 index ae7fbb00..00000000 --- a/libcsp/src/crypto/csp_hmac.c +++ /dev/null @@ -1,202 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -/* Hash-based Message Authentication Code - based on code from libtom.org */ - -#include -#include -#include - -/* CSP includes */ -#include - -#include -#include - -#ifdef CSP_USE_HMAC - -#define HMAC_KEY_LENGTH 16 - -/* HMAC key */ -static uint8_t csp_hmac_key[HMAC_KEY_LENGTH]; - -/* HMAC state structure */ -typedef struct { - csp_sha1_state md; - uint8_t key[SHA1_BLOCKSIZE]; -} hmac_state; - -static int csp_hmac_init(hmac_state * hmac, const uint8_t * key, uint32_t keylen) { - uint32_t i; - uint8_t buf[SHA1_BLOCKSIZE]; - - /* NULL pointer and key check */ - if (!hmac || !key || keylen < 1) - return CSP_ERR_INVAL; - - /* Make sure we have a large enough key */ - if(keylen > SHA1_BLOCKSIZE) { - csp_sha1_memory(key, keylen, hmac->key); - if(SHA1_DIGESTSIZE < SHA1_BLOCKSIZE) - memset((hmac->key) + SHA1_DIGESTSIZE, 0, (size_t)(SHA1_BLOCKSIZE - SHA1_DIGESTSIZE)); - } else { - memcpy(hmac->key, key, (size_t)keylen); - if(keylen < SHA1_BLOCKSIZE) - memset((hmac->key) + keylen, 0, (size_t)(SHA1_BLOCKSIZE - keylen)); - } - - /* Create the initial vector */ - for(i = 0; i < SHA1_BLOCKSIZE; i++) - buf[i] = hmac->key[i] ^ 0x36; - - /* Prepend to the hash data */ - csp_sha1_init(&hmac->md); - csp_sha1_process(&hmac->md, buf, SHA1_BLOCKSIZE); - - return CSP_ERR_NONE; -} - -static int csp_hmac_process(hmac_state * hmac, const uint8_t * in, uint32_t inlen) { - - /* NULL pointer check */ - if (!hmac || !in) - return CSP_ERR_INVAL; - - /* Process data */ - csp_sha1_process(&hmac->md, in, inlen); - - return CSP_ERR_NONE; -} - -static int csp_hmac_done(hmac_state * hmac, uint8_t * out) { - - uint32_t i; - uint8_t buf[SHA1_BLOCKSIZE]; - uint8_t isha[SHA1_DIGESTSIZE]; - - if (!hmac || !out) - return CSP_ERR_INVAL; - - /* Get the hash of the first HMAC vector plus the data */ - csp_sha1_done(&hmac->md, isha); - - /* Create the second HMAC vector vector */ - for(i = 0; i < SHA1_BLOCKSIZE; i++) - buf[i] = hmac->key[i] ^ 0x5C; - - /* Now calculate the outer hash */ - csp_sha1_init(&hmac->md); - csp_sha1_process(&hmac->md, buf, SHA1_BLOCKSIZE); - csp_sha1_process(&hmac->md, isha, SHA1_DIGESTSIZE); - csp_sha1_done(&hmac->md, buf); - - /* Copy to output */ - for (i = 0; i < SHA1_DIGESTSIZE; i++) - out[i] = buf[i]; - - return CSP_ERR_NONE; -} - -int csp_hmac_memory(const uint8_t * key, uint32_t keylen, const uint8_t * data, uint32_t datalen, uint8_t * hmac) { - hmac_state state; - - /* NULL pointer check */ - if (!key || !data || !hmac) - return CSP_ERR_INVAL; - - /* Init HMAC state */ - if (csp_hmac_init(&state, key, keylen) != 0) - return CSP_ERR_INVAL; - - /* Process data */ - if (csp_hmac_process(&state, data, datalen) != 0) - return CSP_ERR_INVAL; - - /* Output HMAC */ - if (csp_hmac_done(&state, hmac) != 0) - return CSP_ERR_INVAL; - - return CSP_ERR_NONE; -} - -int csp_hmac_set_key(char * key, uint32_t keylen) { - - /* Use SHA1 as KDF */ - uint8_t hash[SHA1_DIGESTSIZE]; - csp_sha1_memory((uint8_t *)key, keylen, hash); - - /* Copy key */ - memcpy(csp_hmac_key, hash, HMAC_KEY_LENGTH); - - return CSP_ERR_NONE; - -} - -int csp_hmac_append(csp_packet_t * packet, bool include_header) { - - /* NULL pointer check */ - if (packet == NULL) - return CSP_ERR_INVAL; - - uint8_t hmac[SHA1_DIGESTSIZE]; - - /* Calculate HMAC */ - if (include_header) { - csp_hmac_memory(csp_hmac_key, HMAC_KEY_LENGTH, (uint8_t *) &packet->id, packet->length + sizeof(packet->id), hmac); - } else { - csp_hmac_memory(csp_hmac_key, HMAC_KEY_LENGTH, packet->data, packet->length, hmac); - } - - /* Truncate hash and copy to packet */ - memcpy(&packet->data[packet->length], hmac, CSP_HMAC_LENGTH); - packet->length += CSP_HMAC_LENGTH; - - return CSP_ERR_NONE; - -} - -int csp_hmac_verify(csp_packet_t * packet, bool include_header) { - - /* NULL pointer check */ - if (packet == NULL) - return CSP_ERR_INVAL; - - uint8_t hmac[SHA1_DIGESTSIZE]; - - /* Calculate HMAC */ - if (include_header) { - csp_hmac_memory(csp_hmac_key, HMAC_KEY_LENGTH, (uint8_t *) &packet->id, packet->length + sizeof(packet->id) - CSP_HMAC_LENGTH, hmac); - } else { - csp_hmac_memory(csp_hmac_key, HMAC_KEY_LENGTH, packet->data, packet->length - CSP_HMAC_LENGTH, hmac); - } - - /* Compare calculated HMAC with packet header */ - if (memcmp(&packet->data[packet->length] - CSP_HMAC_LENGTH, hmac, CSP_HMAC_LENGTH) != 0) { - /* HMAC failed */ - return CSP_ERR_HMAC; - } else { - /* Strip HMAC */ - packet->length -= CSP_HMAC_LENGTH; - return CSP_ERR_NONE; - } - -} - -#endif // CSP_USE_HMAC diff --git a/libcsp/src/crypto/csp_sha1.c b/libcsp/src/crypto/csp_sha1.c deleted file mode 100644 index 6c3920e9..00000000 --- a/libcsp/src/crypto/csp_sha1.c +++ /dev/null @@ -1,217 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -/* Code originally from Python's SHA1 Module, who based it on libtom.org */ - -#include -#include - -/* CSP includes */ -#include - -#include - -#if defined(CSP_USE_HMAC) || defined(CSP_USE_XTEA) - -/* Rotate left macro */ -#define ROL(x,y) (((x) << (y)) | ((x) >> (32-y))) - -/* Endian Neutral macros that work on all platforms */ -#define STORE32H(x, y) do { (y)[0] = (uint8_t)(((x) >> 24) & 0xff); \ - (y)[1] = (uint8_t)(((x) >> 16) & 0xff); \ - (y)[2] = (uint8_t)(((x) >> 8) & 0xff); \ - (y)[3] = (uint8_t)(((x) >> 0) & 0xff); } while (0) - -#define LOAD32H(x, y) do { (x) = ((uint32_t)((y)[0] & 0xff) << 24) | \ - ((uint32_t)((y)[1] & 0xff) << 16) | \ - ((uint32_t)((y)[2] & 0xff) << 8) | \ - ((uint32_t)((y)[3] & 0xff) << 0); } while (0) - -#define STORE64H(x, y) do { (y)[0] = (uint8_t)(((x) >> 56) & 0xff); \ - (y)[1] = (uint8_t)(((x) >> 48) & 0xff); \ - (y)[2] = (uint8_t)(((x) >> 40) & 0xff); \ - (y)[3] = (uint8_t)(((x) >> 32) & 0xff); \ - (y)[4] = (uint8_t)(((x) >> 24) & 0xff); \ - (y)[5] = (uint8_t)(((x) >> 16) & 0xff); \ - (y)[6] = (uint8_t)(((x) >> 8) & 0xff); \ - (y)[7] = (uint8_t)(((x) >> 0) & 0xff); } while (0) - -#define MIN(x, y) (((x) < (y)) ? (x) : (y)) - -/* SHA1 macros */ -#define F0(x,y,z) (z ^ (x & (y ^ z))) -#define F1(x,y,z) (x ^ y ^ z) -#define F2(x,y,z) ((x & y) | (z & (x | y))) -#define F3(x,y,z) (x ^ y ^ z) - -#define FF_0(a, b, c, d, e, i) do {e = (ROL(a, 5) + F0(b,c,d) + e + W[i] + 0x5a827999UL); b = ROL(b, 30);} while (0) -#define FF_1(a, b, c, d, e, i) do {e = (ROL(a, 5) + F1(b,c,d) + e + W[i] + 0x6ed9eba1UL); b = ROL(b, 30);} while (0) -#define FF_2(a, b, c, d, e, i) do {e = (ROL(a, 5) + F2(b,c,d) + e + W[i] + 0x8f1bbcdcUL); b = ROL(b, 30);} while (0) -#define FF_3(a, b, c, d, e, i) do {e = (ROL(a, 5) + F3(b,c,d) + e + W[i] + 0xca62c1d6UL); b = ROL(b, 30);} while (0) - -static void csp_sha1_compress(csp_sha1_state * sha1, const uint8_t * buf) { - - uint32_t a, b, c, d, e, W[80], i; - - /* Copy the state into 512-bits into W[0..15] */ - for (i = 0; i < 16; i++) - LOAD32H(W[i], buf + (4*i)); - - /* Copy state */ - a = sha1->state[0]; - b = sha1->state[1]; - c = sha1->state[2]; - d = sha1->state[3]; - e = sha1->state[4]; - - /* Expand it */ - for (i = 16; i < 80; i++) - W[i] = ROL(W[i-3] ^ W[i-8] ^ W[i-14] ^ W[i-16], 1); - - /* Compress */ - i = 0; - - /* Round one */ - for (; i < 20;) { - FF_0(a, b, c, d, e, i++); - FF_0(e, a, b, c, d, i++); - FF_0(d, e, a, b, c, i++); - FF_0(c, d, e, a, b, i++); - FF_0(b, c, d, e, a, i++); - } - - /* Round two */ - for (; i < 40;) { - FF_1(a, b, c, d, e, i++); - FF_1(e, a, b, c, d, i++); - FF_1(d, e, a, b, c, i++); - FF_1(c, d, e, a, b, i++); - FF_1(b, c, d, e, a, i++); - } - - /* Round three */ - for (; i < 60;) { - FF_2(a, b, c, d, e, i++); - FF_2(e, a, b, c, d, i++); - FF_2(d, e, a, b, c, i++); - FF_2(c, d, e, a, b, i++); - FF_2(b, c, d, e, a, i++); - } - - /* Round four */ - for (; i < 80;) { - FF_3(a, b, c, d, e, i++); - FF_3(e, a, b, c, d, i++); - FF_3(d, e, a, b, c, i++); - FF_3(c, d, e, a, b, i++); - FF_3(b, c, d, e, a, i++); - } - - /* Store */ - sha1->state[0] += a; - sha1->state[1] += b; - sha1->state[2] += c; - sha1->state[3] += d; - sha1->state[4] += e; - -} - -void csp_sha1_init(csp_sha1_state * sha1) { - - sha1->state[0] = 0x67452301UL; - sha1->state[1] = 0xefcdab89UL; - sha1->state[2] = 0x98badcfeUL; - sha1->state[3] = 0x10325476UL; - sha1->state[4] = 0xc3d2e1f0UL; - sha1->curlen = 0; - sha1->length = 0; - -} - -void csp_sha1_process(csp_sha1_state * sha1, const uint8_t * in, uint32_t inlen) { - - uint32_t n; - while (inlen > 0) { - if (sha1->curlen == 0 && inlen >= SHA1_BLOCKSIZE) { - csp_sha1_compress(sha1, in); - sha1->length += SHA1_BLOCKSIZE * 8; - in += SHA1_BLOCKSIZE; - inlen -= SHA1_BLOCKSIZE; - } else { - n = MIN(inlen, (SHA1_BLOCKSIZE - sha1->curlen)); - memcpy(sha1->buf + sha1->curlen, in, (size_t)n); - sha1->curlen += n; - in += n; - inlen -= n; - if (sha1->curlen == SHA1_BLOCKSIZE) { - csp_sha1_compress(sha1, sha1->buf); - sha1->length += 8*SHA1_BLOCKSIZE; - sha1->curlen = 0; - } - } - } - -} - -void csp_sha1_done(csp_sha1_state * sha1, uint8_t * out) { - - uint32_t i; - - /* Increase the length of the message */ - sha1->length += sha1->curlen * 8; - - /* Append the '1' bit */ - sha1->buf[sha1->curlen++] = 0x80; - - /* If the length is currently above 56 bytes we append zeros - * then compress. Then we can fall back to padding zeros and length - * encoding like normal. - */ - if (sha1->curlen > 56) { - while (sha1->curlen < 64) - sha1->buf[sha1->curlen++] = 0; - csp_sha1_compress(sha1, sha1->buf); - sha1->curlen = 0; - } - - /* Pad up to 56 bytes of zeroes */ - while (sha1->curlen < 56) - sha1->buf[sha1->curlen++] = 0; - - /* Store length */ - STORE64H(sha1->length, sha1->buf + 56); - csp_sha1_compress(sha1, sha1->buf); - - /* Copy output */ - for (i = 0; i < 5; i++) - STORE32H(sha1->state[i], out + (4 * i)); - -} - -void csp_sha1_memory(const uint8_t * msg, uint32_t len, uint8_t * hash) { - - csp_sha1_state md; - csp_sha1_init(&md); - csp_sha1_process(&md, msg, len); - csp_sha1_done(&md, hash); - -} - -#endif // CSP_USE_HMAC diff --git a/libcsp/src/crypto/csp_xtea.c b/libcsp/src/crypto/csp_xtea.c deleted file mode 100644 index 718824d1..00000000 --- a/libcsp/src/crypto/csp_xtea.c +++ /dev/null @@ -1,134 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -/* Simple implementation of XTEA in CTR mode */ - -#include -#include - -/* CSP includes */ -#include -#include -#include -#include - -#ifdef CSP_USE_XTEA - -#define XTEA_BLOCKSIZE 8 -#define XTEA_ROUNDS 32 -#define XTEA_KEY_LENGTH 16 - -/* XTEA key */ -static uint32_t csp_xtea_key[XTEA_KEY_LENGTH/sizeof(uint32_t)] __attribute__ ((aligned(sizeof(uint32_t)))); - -#define STORE32L(x, y) do { (y)[3] = (uint8_t)(((x) >> 24) & 0xff); \ - (y)[2] = (uint8_t)(((x) >> 16) & 0xff); \ - (y)[1] = (uint8_t)(((x) >> 8) & 0xff); \ - (y)[0] = (uint8_t)(((x) >> 0) & 0xff); } while (0) - -#define LOAD32L(x, y) do { (x) = ((uint32_t)((y)[3] & 0xff) << 24) | \ - ((uint32_t)((y)[2] & 0xff) << 16) | \ - ((uint32_t)((y)[1] & 0xff) << 8) | \ - ((uint32_t)((y)[0] & 0xff) << 0); } while (0) - -/* This function takes 64 bits of data in block and the 128 bits key in key */ -static inline void csp_xtea_encrypt_block(uint8_t *block, uint8_t const *key) { - - uint32_t i, v0, v1, delta = 0x9E3779B9, sum = 0, k[4]; - - LOAD32L(k[0], &key[0]); - LOAD32L(k[1], &key[4]); - LOAD32L(k[2], &key[8]); - LOAD32L(k[3], &key[12]); - - LOAD32L(v0, &block[0]); - LOAD32L(v1, &block[4]); - - for (i = 0; i < XTEA_ROUNDS; i++) { - v0 += (((v1 << 4) ^ (v1 >> 5)) + v1) ^ (sum + k[sum & 3]); - sum += delta; - v1 += (((v0 << 4) ^ (v0 >> 5)) + v0) ^ (sum + k[(sum >> 11) & 3]); - } - - STORE32L(v0, &block[0]); - STORE32L(v1, &block[4]); - -} - -static inline void csp_xtea_xor_byte(uint8_t * dst, uint8_t * src, uint32_t len) { - - unsigned int i; - for (i = 0; i < len; i++) - dst[i] ^= src[i]; - -} - -int csp_xtea_set_key(char * key, uint32_t keylen) { - - /* Use SHA1 as KDF */ - uint8_t hash[SHA1_DIGESTSIZE]; - csp_sha1_memory((uint8_t *)key, keylen, hash); - - /* Copy key */ - memcpy(csp_xtea_key, hash, XTEA_KEY_LENGTH); - - return CSP_ERR_NONE; - -} - -int csp_xtea_encrypt(uint8_t * plain, const uint32_t len, uint32_t iv[2]) { - - unsigned int i; - uint32_t stream[2]; - - uint32_t blocks = (len + XTEA_BLOCKSIZE - 1)/ XTEA_BLOCKSIZE; - uint32_t remain; - - /* Initialize stream */ - stream[0] = csp_htobe32(iv[0]); - stream[1] = csp_htobe32(iv[1]); - - for (i = 0; i < blocks; i++) { - /* Create stream */ - csp_xtea_encrypt_block((uint8_t *)stream, (uint8_t *)csp_xtea_key); - - /* Calculate remaining bytes */ - remain = len - i * XTEA_BLOCKSIZE; - - /* XOR plain text with stream to generate cipher text */ - csp_xtea_xor_byte(&plain[len - remain], (uint8_t *)stream, remain < XTEA_BLOCKSIZE ? remain : XTEA_BLOCKSIZE); - - /* Increment counter */ - stream[0] = csp_htobe32(iv[0]); - stream[1] = csp_htobe32(iv[1]++); - } - - return CSP_ERR_NONE; - -} - -int csp_xtea_decrypt(uint8_t * cipher, const uint32_t len, uint32_t iv[2]) { - - /* Since we use counter mode, we can reuse the encryption function */ - return csp_xtea_encrypt(cipher, len, iv); - -} - -#endif // CSP_USE_XTEA diff --git a/libcsp/src/csp_bridge.c b/libcsp/src/csp_bridge.c deleted file mode 100644 index 1c579a9f..00000000 --- a/libcsp/src/csp_bridge.c +++ /dev/null @@ -1,94 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include -#include -#include -#include "csp_route.h" -#include "csp_qfifo.h" -#include "csp_io.h" -#include "csp_promisc.h" - -static csp_iface_t* if_a = NULL; -static csp_iface_t* if_b = NULL; - -static CSP_DEFINE_TASK(csp_bridge) { - - csp_qfifo_t input; - csp_packet_t * packet; - - /* Here there be bridging */ - while (1) { - - /* Get next packet to route */ - if (csp_qfifo_read(&input) != CSP_ERR_NONE) - continue; - - packet = input.packet; - - csp_log_packet("Input: Src %u, Dst %u, Dport %u, Sport %u, Pri %u, Flags 0x%02X, Size %"PRIu16, - packet->id.src, packet->id.dst, packet->id.dport, - packet->id.sport, packet->id.pri, packet->id.flags, packet->length); - - /* Here there be promiscuous mode */ -#ifdef CSP_USE_PROMISC - csp_promisc_add(packet); -#endif - - /* Find the opposing interface */ - csp_iface_t * ifout; - if (input.interface == if_a) { - ifout = if_b; - } else { - ifout = if_a; - } - - /* Send to the interface directly, no hassle */ - if (csp_send_direct(packet->id, packet, ifout, 0) != CSP_ERR_NONE) { - csp_log_warn("Router failed to send"); - csp_buffer_free(packet); - } - - /* Next message, please */ - continue; - - } - - return CSP_TASK_RETURN; - -} - -int csp_bridge_start(unsigned int task_stack_size, unsigned int task_priority, csp_iface_t * _if_a, csp_iface_t * _if_b) { - - /* Set static references to A/B side of bridge */ - if_a = _if_a; - if_b = _if_b; - - static csp_thread_handle_t handle; - int ret = csp_thread_create(csp_bridge, "BRIDGE", task_stack_size, NULL, task_priority, &handle); - - if (ret != 0) { - csp_log_error("Failed to start task"); - return CSP_ERR_NOMEM; - } - - return CSP_ERR_NONE; - -} diff --git a/libcsp/src/csp_buffer.c b/libcsp/src/csp_buffer.c deleted file mode 100644 index 8947f337..00000000 --- a/libcsp/src/csp_buffer.c +++ /dev/null @@ -1,224 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include -#include -#include - -/* CSP includes */ -#include -#include -#include -#include -#include - -#ifndef CSP_BUFFER_ALIGN -#define CSP_BUFFER_ALIGN (sizeof(int *)) -#endif - -typedef struct csp_skbf_s { - unsigned int refcount; - void * skbf_addr; - char skbf_data[]; -} csp_skbf_t; - -static csp_queue_handle_t csp_buffers; -static char * csp_buffer_pool; -static unsigned int count, size; - -CSP_DEFINE_CRITICAL(csp_critical_lock); - -int csp_buffer_init(int buf_count, int buf_size) { - - unsigned int i; - csp_skbf_t * buf; - - count = buf_count; - size = buf_size + CSP_BUFFER_PACKET_OVERHEAD; - unsigned int skbfsize = (sizeof(csp_skbf_t) + size); - skbfsize = CSP_BUFFER_ALIGN * ((skbfsize + CSP_BUFFER_ALIGN - 1) / CSP_BUFFER_ALIGN); - unsigned int poolsize = count * skbfsize; - - csp_buffer_pool = csp_malloc(poolsize); - if (csp_buffer_pool == NULL) - goto fail_malloc; - - csp_buffers = csp_queue_create(count, sizeof(void *)); - if (!csp_buffers) - goto fail_queue; - - if (CSP_INIT_CRITICAL(csp_critical_lock) != CSP_ERR_NONE) - goto fail_critical; - - memset(csp_buffer_pool, 0, poolsize); - - for (i = 0; i < count; i++) { - - /* We have already taken care of pointer alignment since - * skbfsize is an integer multiple of sizeof(int *) - * but the explicit cast to a void * is still necessary - * to tell the compiler so. - */ - buf = (void *) &csp_buffer_pool[i * skbfsize]; - buf->refcount = 0; - buf->skbf_addr = buf; - - csp_queue_enqueue(csp_buffers, &buf, 0); - - } - - return CSP_ERR_NONE; - -fail_critical: - csp_queue_remove(csp_buffers); -fail_queue: - csp_free(csp_buffer_pool); -fail_malloc: - return CSP_ERR_NOMEM; - -} - -void *csp_buffer_get_isr(size_t buf_size) { - - csp_skbf_t * buffer = NULL; - CSP_BASE_TYPE task_woken = 0; - - if (buf_size + CSP_BUFFER_PACKET_OVERHEAD > size) - return NULL; - - csp_queue_dequeue_isr(csp_buffers, &buffer, &task_woken); - if (buffer == NULL) - return NULL; - - if (buffer != buffer->skbf_addr) - return NULL; - - buffer->refcount++; - return buffer->skbf_data; - -} - -void *csp_buffer_get(size_t buf_size) { - - csp_skbf_t * buffer = NULL; - - if (buf_size + CSP_BUFFER_PACKET_OVERHEAD > size) { - csp_log_error("Attempt to allocate too large block %u", buf_size); - return NULL; - } - - csp_queue_dequeue(csp_buffers, &buffer, 0); - if (buffer == NULL) { - csp_log_error("Out of buffers"); - return NULL; - } - - csp_log_buffer("GET: %p %p", buffer, buffer->skbf_addr); - - if (buffer != buffer->skbf_addr) { - csp_log_error("Corrupt CSP buffer"); - return NULL; - } - - buffer->refcount++; - return buffer->skbf_data; -} - -void csp_buffer_free_isr(void *packet) { - CSP_BASE_TYPE task_woken = 0; - if (!packet) - return; - - csp_skbf_t * buf = packet - sizeof(csp_skbf_t); - - if (((uintptr_t) buf % CSP_BUFFER_ALIGN) > 0) - return; - - if (buf->skbf_addr != buf) - return; - - if (buf->refcount == 0) { - return; - } else if (buf->refcount > 1) { - buf->refcount--; - return; - } else { - buf->refcount = 0; - csp_queue_enqueue_isr(csp_buffers, &buf, &task_woken); - } - -} - -void csp_buffer_free(void *packet) { - if (!packet) { - csp_log_error("Attempt to free null pointer"); - return; - } - - csp_skbf_t * buf = packet - sizeof(csp_skbf_t); - - if (((uintptr_t) buf % CSP_BUFFER_ALIGN) > 0) { - csp_log_error("FREE: Unaligned CSP buffer pointer %p", packet); - return; - } - - if (buf->skbf_addr != buf) { - csp_log_error("FREE: Invalid CSP buffer pointer %p", packet); - return; - } - - if (buf->refcount == 0) { - csp_log_error("FREE: Buffer already free %p", buf); - return; - } else if (buf->refcount > 1) { - buf->refcount--; - csp_log_error("FREE: Buffer %p in use by %u users", buf, buf->refcount); - return; - } else { - buf->refcount = 0; - csp_log_buffer("FREE: %p", buf); - csp_queue_enqueue(csp_buffers, &buf, 0); - } - -} - -void *csp_buffer_clone(void *buffer) { - - csp_packet_t *packet = (csp_packet_t *) buffer; - - if (!packet) - return NULL; - - csp_packet_t *clone = csp_buffer_get(packet->length); - - if (clone) - memcpy(clone, packet, size); - - return clone; - -} - -int csp_buffer_remaining(void) { - return csp_queue_size(csp_buffers); -} - -int csp_buffer_size(void) { - return size; -} diff --git a/libcsp/src/csp_conn.c b/libcsp/src/csp_conn.c deleted file mode 100644 index 7daa569d..00000000 --- a/libcsp/src/csp_conn.c +++ /dev/null @@ -1,498 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include -#include -#include -#include - -/* CSP includes */ -#include -#include - -#include -#include -#include -#include -#include - -#include "csp_conn.h" -#include "transport/csp_transport.h" - -/* Static connection pool */ -static csp_conn_t arr_conn[CSP_CONN_MAX]; - -/* Connection pool lock */ -static csp_bin_sem_handle_t conn_lock; - -/* Source port */ -static uint8_t sport; - -/* Source port lock */ -static csp_bin_sem_handle_t sport_lock; - -void csp_conn_check_timeouts(void) { -#ifdef CSP_USE_RDP - int i; - for (i = 0; i < CSP_CONN_MAX; i++) - if (arr_conn[i].state == CONN_OPEN) - if (arr_conn[i].idin.flags & CSP_FRDP) - csp_rdp_check_timeouts(&arr_conn[i]); -#endif -} - -int csp_conn_get_rxq(int prio) { - -#ifdef CSP_USE_QOS - return prio; -#else - return 0; -#endif - -} - -int csp_conn_lock(csp_conn_t * conn, uint32_t timeout) { - - if (csp_mutex_lock(&conn->lock, timeout) != CSP_MUTEX_OK) - return CSP_ERR_TIMEDOUT; - - return CSP_ERR_NONE; - -} - -int csp_conn_unlock(csp_conn_t * conn) { - - csp_mutex_unlock(&conn->lock); - - return CSP_ERR_NONE; - -} - -int csp_conn_enqueue_packet(csp_conn_t * conn, csp_packet_t * packet) { - - if (!conn) - return CSP_ERR_INVAL; - - int rxq; - if (packet != NULL) { - rxq = csp_conn_get_rxq(packet->id.pri); - } else { - rxq = CSP_RX_QUEUES - 1; - } - - if (csp_queue_enqueue(conn->rx_queue[rxq], &packet, 0) != CSP_QUEUE_OK) { - csp_log_error("RX queue %p full with %u items", conn->rx_queue[rxq], csp_queue_size(conn->rx_queue[rxq])); - return CSP_ERR_NOMEM; - } - -#ifdef CSP_USE_QOS - int event = 0; - if (csp_queue_enqueue(conn->rx_event, &event, 0) != CSP_QUEUE_OK) { - csp_log_error("QOS event queue full"); - return CSP_ERR_NOMEM; - } -#endif - - return CSP_ERR_NONE; -} - -int csp_conn_init(void) { - - /* Initialize source port */ - srand(csp_get_ms()); - sport = (rand() % (CSP_ID_PORT_MAX - CSP_MAX_BIND_PORT)) + (CSP_MAX_BIND_PORT + 1); - - if (csp_bin_sem_create(&sport_lock) != CSP_SEMAPHORE_OK) { - csp_log_error("No more memory for sport semaphore"); - return CSP_ERR_NOMEM; - } - - int i, prio; - for (i = 0; i < CSP_CONN_MAX; i++) { - for (prio = 0; prio < CSP_RX_QUEUES; prio++) - arr_conn[i].rx_queue[prio] = csp_queue_create(CSP_RX_QUEUE_LENGTH, sizeof(csp_packet_t *)); - -#ifdef CSP_USE_QOS - arr_conn[i].rx_event = csp_queue_create(CSP_CONN_QUEUE_LENGTH, sizeof(int)); -#endif - arr_conn[i].state = CONN_CLOSED; - - if (csp_mutex_create(&arr_conn[i].lock) != CSP_MUTEX_OK) { - csp_log_error("Failed to create connection lock"); - return CSP_ERR_NOMEM; - } - -#ifdef CSP_USE_RDP - if (csp_rdp_allocate(&arr_conn[i]) != CSP_ERR_NONE) { - csp_log_error("Failed to create queues for RDP in csp_conn_init"); - return CSP_ERR_NOMEM; - } -#endif - } - - if (csp_bin_sem_create(&conn_lock) != CSP_SEMAPHORE_OK) { - csp_log_error("No more memory for conn semaphore"); - return CSP_ERR_NOMEM; - } - - return CSP_ERR_NONE; - -} - -csp_conn_t * csp_conn_find(uint32_t id, uint32_t mask) { - - /* Search for matching connection */ - int i; - csp_conn_t * conn; - id = (id & mask); - for (i = 0; i < CSP_CONN_MAX; i++) { - conn = &arr_conn[i]; - if ((conn->state != CONN_CLOSED) && (conn->type == CONN_CLIENT) && ((conn->idin.ext & mask) == id)) - return conn; - } - - return NULL; - -} - -static int csp_conn_flush_rx_queue(csp_conn_t * conn) { - - csp_packet_t * packet; - - int prio; - - /* Flush packet queues */ - for (prio = 0; prio < CSP_RX_QUEUES; prio++) { - while (csp_queue_dequeue(conn->rx_queue[prio], &packet, 0) == CSP_QUEUE_OK) - if (packet != NULL) - csp_buffer_free(packet); - } - - /* Flush event queue */ -#ifdef CSP_USE_QOS - int event; - while (csp_queue_dequeue(conn->rx_event, &event, 0) == CSP_QUEUE_OK); -#endif - - return CSP_ERR_NONE; - -} - -csp_conn_t * csp_conn_allocate(csp_conn_type_t type) { - - int i, j; - static uint8_t csp_conn_last_given = 0; - csp_conn_t * conn; - - if (csp_bin_sem_wait(&conn_lock, 100) != CSP_SEMAPHORE_OK) { - csp_log_error("Failed to lock conn array"); - return NULL; - } - - /* Search for free connection */ - i = csp_conn_last_given; - i = (i + 1) % CSP_CONN_MAX; - - for (j = 0; j < CSP_CONN_MAX; j++) { - conn = &arr_conn[i]; - if (conn->state == CONN_CLOSED) - break; - i = (i + 1) % CSP_CONN_MAX; - } - - if (conn->state == CONN_OPEN) { - csp_log_error("No more free connections"); - csp_bin_sem_post(&conn_lock); - return NULL; - } - - conn->idin.ext = 0; - conn->idout.ext = 0; - conn->socket = NULL; - conn->timestamp = 0; - conn->type = type; - conn->state = CONN_OPEN; - - csp_conn_last_given = i; - csp_bin_sem_post(&conn_lock); - - return conn; - -} - -csp_conn_t * csp_conn_new(csp_id_t idin, csp_id_t idout) { - - /* Allocate connection structure */ - csp_conn_t * conn = csp_conn_allocate(CONN_CLIENT); - - if (conn) { - /* No lock is needed here, because nobody else * - * has a reference to this connection yet. */ - conn->idin.ext = idin.ext; - conn->idout.ext = idout.ext; - conn->timestamp = csp_get_ms(); - - /* Ensure connection queue is empty */ - csp_conn_flush_rx_queue(conn); - } - - return conn; - -} - -int csp_close(csp_conn_t * conn) { - - if (conn == NULL) { - csp_log_error("NULL Pointer given to csp_close"); - return CSP_ERR_INVAL; - } - - if (conn->state == CONN_CLOSED) { - csp_log_protocol("Conn already closed"); - return CSP_ERR_NONE; - } - -#ifdef CSP_USE_RDP - /* Ensure RDP knows this connection is closing */ - if (conn->idin.flags & CSP_FRDP || conn->idout.flags & CSP_FRDP) - if (csp_rdp_close(conn) == CSP_ERR_AGAIN) - return CSP_ERR_NONE; -#endif - - /* Lock connection array while closing connection */ - if (csp_bin_sem_wait(&conn_lock, 100) != CSP_SEMAPHORE_OK) { - csp_log_error("Failed to lock conn array"); - return CSP_ERR_TIMEDOUT; - } - - /* Set to closed */ - conn->state = CONN_CLOSED; - - /* Ensure connection queue is empty */ - csp_conn_flush_rx_queue(conn); - - if (conn->socket && (conn->type == CONN_SERVER) && (conn->opts & (CSP_SO_CONN_LESS | CSP_SO_INTERNAL_LISTEN))) { - csp_queue_remove(conn->socket); - conn->socket = NULL; - } - - /* Reset RDP state */ -#ifdef CSP_USE_RDP - if (conn->idin.flags & CSP_FRDP) - csp_rdp_flush_all(conn); -#endif - - /* Unlock connection array */ - csp_bin_sem_post(&conn_lock); - - return CSP_ERR_NONE; -} - -csp_conn_t * csp_connect(uint8_t prio, uint8_t dest, uint8_t dport, uint32_t timeout, uint32_t opts) { - - /* Force options on all connections */ - opts |= CSP_CONNECTION_SO; - - /* Generate identifier */ - csp_id_t incoming_id, outgoing_id; - incoming_id.pri = prio; - incoming_id.dst = csp_get_address(); - incoming_id.src = dest; - incoming_id.sport = dport; - incoming_id.flags = 0; - outgoing_id.pri = prio; - outgoing_id.dst = dest; - outgoing_id.src = csp_get_address(); - outgoing_id.dport = dport; - outgoing_id.flags = 0; - - /* Set connection options */ - if (opts & CSP_O_NOCRC32) { - opts &= ~CSP_O_CRC32; - } - - if (opts & CSP_O_RDP) { -#ifdef CSP_USE_RDP - incoming_id.flags |= CSP_FRDP; - outgoing_id.flags |= CSP_FRDP; -#else - csp_log_error("Attempt to create RDP connection, but CSP was compiled without RDP support"); - return NULL; -#endif - } - - if (opts & CSP_O_HMAC) { -#ifdef CSP_USE_HMAC - outgoing_id.flags |= CSP_FHMAC; - incoming_id.flags |= CSP_FHMAC; -#else - csp_log_error("Attempt to create HMAC authenticated connection, but CSP was compiled without HMAC support"); - return NULL; -#endif - } - - if (opts & CSP_O_XTEA) { -#ifdef CSP_USE_XTEA - outgoing_id.flags |= CSP_FXTEA; - incoming_id.flags |= CSP_FXTEA; -#else - csp_log_error("Attempt to create XTEA encrypted connection, but CSP was compiled without XTEA support"); - return NULL; -#endif - } - - if (opts & CSP_O_CRC32) { -#ifdef CSP_USE_CRC32 - outgoing_id.flags |= CSP_FCRC32; - incoming_id.flags |= CSP_FCRC32; -#else - csp_log_error("Attempt to create CRC32 validated connection, but CSP was compiled without CRC32 support"); - return NULL; -#endif - } - - /* Find an unused ephemeral port */ - csp_conn_t * conn = NULL; - - /* Wait for sport lock - note that csp_conn_new(..) is called inside the lock! */ - if (csp_bin_sem_wait(&sport_lock, 1000) != CSP_SEMAPHORE_OK) - return NULL; - - const uint8_t start = sport; - while (++sport != start) { - if (sport > CSP_ID_PORT_MAX) - sport = CSP_MAX_BIND_PORT + 1; - - outgoing_id.sport = sport; - incoming_id.dport = sport; - - /* Match on destination port of _incoming_ identifier */ - if (csp_conn_find(incoming_id.ext, CSP_ID_DPORT_MASK) == NULL) { - /* Break - we found an unused ephemeral port - allocate connection while locked to mark port in use */ - conn = csp_conn_new(incoming_id, outgoing_id); - break; - } - } - - /* Post sport lock */ - csp_bin_sem_post(&sport_lock); - - if (conn == NULL) - return NULL; - - /* Set connection options */ - conn->opts = opts; - -#ifdef CSP_USE_RDP - /* Call Transport Layer connect */ - if (outgoing_id.flags & CSP_FRDP) { - /* If the transport layer has failed to connect - * deallocate connection structure again and return NULL */ - if (csp_rdp_connect(conn, timeout) != CSP_ERR_NONE) { - csp_close(conn); - return NULL; - } - } -#endif - - /* We have a successful connection */ - return conn; - -} - -inline int csp_conn_dport(csp_conn_t * conn) { - - return conn->idin.dport; - -} - -inline int csp_conn_sport(csp_conn_t * conn) { - - return conn->idin.sport; - -} - -inline int csp_conn_dst(csp_conn_t * conn) { - - return conn->idin.dst; - -} - -inline int csp_conn_src(csp_conn_t * conn) { - - return conn->idin.src; - -} - -inline int csp_conn_flags(csp_conn_t * conn) { - - return conn->idin.flags; - -} - -#ifdef CSP_DEBUG -void csp_conn_print_table(void) { - - int i; - csp_conn_t * conn; - - for (i = 0; i < CSP_CONN_MAX; i++) { - conn = &arr_conn[i]; - printf("[%02u %p] S:%u, %u -> %u, %u -> %u, sock: %p\r\n", - i, conn, conn->state, conn->idin.src, conn->idin.dst, - conn->idin.dport, conn->idin.sport, conn->socket); -#ifdef CSP_USE_RDP - if (conn->idin.flags & CSP_FRDP) - csp_rdp_conn_print(conn); -#endif - } -} - -int csp_conn_print_table_str(char * str_buf, int str_size) { - - int i, start = 0; - csp_conn_t * conn; - char buf[100]; - - /* Display up to 10 connections */ - if (CSP_CONN_MAX - 10 > 0) - start = CSP_CONN_MAX - 10; - - for (i = start; i < CSP_CONN_MAX; i++) { - conn = &arr_conn[i]; - snprintf(buf, sizeof(buf), "[%02u %p] S:%u, %u -> %u, %u -> %u, sock: %p\n", - i, conn, conn->state, conn->idin.src, conn->idin.dst, - conn->idin.dport, conn->idin.sport, conn->socket); - - strncat(str_buf, buf, str_size); - if ((str_size -= strlen(buf)) <= 0) - break; - } - - return CSP_ERR_NONE; -} -#endif - -const csp_conn_t * csp_conn_get_array(size_t * size) -{ - *size = CSP_CONN_MAX; - return arr_conn; -} diff --git a/libcsp/src/csp_conn.h b/libcsp/src/csp_conn.h deleted file mode 100644 index 3fa0ff52..00000000 --- a/libcsp/src/csp_conn.h +++ /dev/null @@ -1,112 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#ifndef _CSP_CONN_H_ -#define _CSP_CONN_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include - -#include - -#include -#include - -/** @brief Connection states */ -typedef enum { - CONN_CLOSED = 0, - CONN_OPEN = 1, -} csp_conn_state_t; - -/** @brief Connection types */ -typedef enum { - CONN_CLIENT = 0, - CONN_SERVER = 1, -} csp_conn_type_t; - -typedef enum { - RDP_CLOSED = 0, - RDP_SYN_SENT, - RDP_SYN_RCVD, - RDP_OPEN, - RDP_CLOSE_WAIT, -} csp_rdp_state_t; - -/** @brief RDP Connection header - * @note Do not try to pack this struct, the posix sem handle will stop working */ -typedef struct { - csp_rdp_state_t state; /**< Connection state */ - uint16_t snd_nxt; /**< The sequence number of the next segment that is to be sent */ - uint16_t snd_una; /**< The sequence number of the oldest unacknowledged segment */ - uint16_t snd_iss; /**< The initial send sequence number */ - uint16_t rcv_cur; /**< The sequence number of the last segment received correctly and in sequence */ - uint16_t rcv_irs; /**< The initial receive sequence number */ - uint16_t rcv_lsa; /**< The last sequence number acknowledged by the receiver */ - uint32_t window_size; - uint32_t conn_timeout; - uint32_t packet_timeout; - uint32_t delayed_acks; - uint32_t ack_timeout; - uint32_t ack_delay_count; - uint32_t ack_timestamp; - csp_bin_sem_handle_t tx_wait; - csp_queue_handle_t tx_queue; - csp_queue_handle_t rx_queue; -} csp_rdp_t; - -/** @brief Connection struct */ -struct csp_conn_s { - csp_conn_type_t type; /* Connection type (CONN_CLIENT or CONN_SERVER) */ - csp_conn_state_t state; /* Connection state (CONN_OPEN or CONN_CLOSED) */ - csp_mutex_t lock; /* Connection structure lock */ - csp_id_t idin; /* Identifier received */ - csp_id_t idout; /* Identifier transmitted */ -#ifdef CSP_USE_QOS - csp_queue_handle_t rx_event; /* Event queue for RX packets */ -#endif - csp_queue_handle_t rx_queue[CSP_RX_QUEUES]; /* Queue for RX packets */ - csp_queue_handle_t socket; /* Socket to be "woken" when first packet is ready */ - uint32_t timestamp; /* Time the connection was opened */ - uint32_t opts; /* Connection or socket options */ -#ifdef CSP_USE_RDP - csp_rdp_t rdp; /* RDP state */ -#endif -}; - -int csp_conn_lock(csp_conn_t * conn, uint32_t timeout); -int csp_conn_unlock(csp_conn_t * conn); -int csp_conn_enqueue_packet(csp_conn_t * conn, csp_packet_t * packet); -int csp_conn_init(void); -csp_conn_t * csp_conn_allocate(csp_conn_type_t type); -csp_conn_t * csp_conn_find(uint32_t id, uint32_t mask); -csp_conn_t * csp_conn_new(csp_id_t idin, csp_id_t idout); -void csp_conn_check_timeouts(void); -int csp_conn_get_rxq(int prio); - -const csp_conn_t * csp_conn_get_array(size_t * size); // for test purposes only! - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // _CSP_CONN_H_ diff --git a/libcsp/src/csp_crc32.c b/libcsp/src/csp_crc32.c deleted file mode 100644 index 8bf2145f..00000000 --- a/libcsp/src/csp_crc32.c +++ /dev/null @@ -1,140 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include -#include -#include - -#include -#include - -#include - -#ifdef CSP_USE_CRC32 - -#ifdef __AVR__ -#include -static const uint32_t crc_tab[256] PROGMEM = { -#else -static const uint32_t crc_tab[256] = { -#endif - 0x00000000, 0xF26B8303, 0xE13B70F7, 0x1350F3F4, 0xC79A971F, 0x35F1141C, 0x26A1E7E8, 0xD4CA64EB, - 0x8AD958CF, 0x78B2DBCC, 0x6BE22838, 0x9989AB3B, 0x4D43CFD0, 0xBF284CD3, 0xAC78BF27, 0x5E133C24, - 0x105EC76F, 0xE235446C, 0xF165B798, 0x030E349B, 0xD7C45070, 0x25AFD373, 0x36FF2087, 0xC494A384, - 0x9A879FA0, 0x68EC1CA3, 0x7BBCEF57, 0x89D76C54, 0x5D1D08BF, 0xAF768BBC, 0xBC267848, 0x4E4DFB4B, - 0x20BD8EDE, 0xD2D60DDD, 0xC186FE29, 0x33ED7D2A, 0xE72719C1, 0x154C9AC2, 0x061C6936, 0xF477EA35, - 0xAA64D611, 0x580F5512, 0x4B5FA6E6, 0xB93425E5, 0x6DFE410E, 0x9F95C20D, 0x8CC531F9, 0x7EAEB2FA, - 0x30E349B1, 0xC288CAB2, 0xD1D83946, 0x23B3BA45, 0xF779DEAE, 0x05125DAD, 0x1642AE59, 0xE4292D5A, - 0xBA3A117E, 0x4851927D, 0x5B016189, 0xA96AE28A, 0x7DA08661, 0x8FCB0562, 0x9C9BF696, 0x6EF07595, - 0x417B1DBC, 0xB3109EBF, 0xA0406D4B, 0x522BEE48, 0x86E18AA3, 0x748A09A0, 0x67DAFA54, 0x95B17957, - 0xCBA24573, 0x39C9C670, 0x2A993584, 0xD8F2B687, 0x0C38D26C, 0xFE53516F, 0xED03A29B, 0x1F682198, - 0x5125DAD3, 0xA34E59D0, 0xB01EAA24, 0x42752927, 0x96BF4DCC, 0x64D4CECF, 0x77843D3B, 0x85EFBE38, - 0xDBFC821C, 0x2997011F, 0x3AC7F2EB, 0xC8AC71E8, 0x1C661503, 0xEE0D9600, 0xFD5D65F4, 0x0F36E6F7, - 0x61C69362, 0x93AD1061, 0x80FDE395, 0x72966096, 0xA65C047D, 0x5437877E, 0x4767748A, 0xB50CF789, - 0xEB1FCBAD, 0x197448AE, 0x0A24BB5A, 0xF84F3859, 0x2C855CB2, 0xDEEEDFB1, 0xCDBE2C45, 0x3FD5AF46, - 0x7198540D, 0x83F3D70E, 0x90A324FA, 0x62C8A7F9, 0xB602C312, 0x44694011, 0x5739B3E5, 0xA55230E6, - 0xFB410CC2, 0x092A8FC1, 0x1A7A7C35, 0xE811FF36, 0x3CDB9BDD, 0xCEB018DE, 0xDDE0EB2A, 0x2F8B6829, - 0x82F63B78, 0x709DB87B, 0x63CD4B8F, 0x91A6C88C, 0x456CAC67, 0xB7072F64, 0xA457DC90, 0x563C5F93, - 0x082F63B7, 0xFA44E0B4, 0xE9141340, 0x1B7F9043, 0xCFB5F4A8, 0x3DDE77AB, 0x2E8E845F, 0xDCE5075C, - 0x92A8FC17, 0x60C37F14, 0x73938CE0, 0x81F80FE3, 0x55326B08, 0xA759E80B, 0xB4091BFF, 0x466298FC, - 0x1871A4D8, 0xEA1A27DB, 0xF94AD42F, 0x0B21572C, 0xDFEB33C7, 0x2D80B0C4, 0x3ED04330, 0xCCBBC033, - 0xA24BB5A6, 0x502036A5, 0x4370C551, 0xB11B4652, 0x65D122B9, 0x97BAA1BA, 0x84EA524E, 0x7681D14D, - 0x2892ED69, 0xDAF96E6A, 0xC9A99D9E, 0x3BC21E9D, 0xEF087A76, 0x1D63F975, 0x0E330A81, 0xFC588982, - 0xB21572C9, 0x407EF1CA, 0x532E023E, 0xA145813D, 0x758FE5D6, 0x87E466D5, 0x94B49521, 0x66DF1622, - 0x38CC2A06, 0xCAA7A905, 0xD9F75AF1, 0x2B9CD9F2, 0xFF56BD19, 0x0D3D3E1A, 0x1E6DCDEE, 0xEC064EED, - 0xC38D26C4, 0x31E6A5C7, 0x22B65633, 0xD0DDD530, 0x0417B1DB, 0xF67C32D8, 0xE52CC12C, 0x1747422F, - 0x49547E0B, 0xBB3FFD08, 0xA86F0EFC, 0x5A048DFF, 0x8ECEE914, 0x7CA56A17, 0x6FF599E3, 0x9D9E1AE0, - 0xD3D3E1AB, 0x21B862A8, 0x32E8915C, 0xC083125F, 0x144976B4, 0xE622F5B7, 0xF5720643, 0x07198540, - 0x590AB964, 0xAB613A67, 0xB831C993, 0x4A5A4A90, 0x9E902E7B, 0x6CFBAD78, 0x7FAB5E8C, 0x8DC0DD8F, - 0xE330A81A, 0x115B2B19, 0x020BD8ED, 0xF0605BEE, 0x24AA3F05, 0xD6C1BC06, 0xC5914FF2, 0x37FACCF1, - 0x69E9F0D5, 0x9B8273D6, 0x88D28022, 0x7AB90321, 0xAE7367CA, 0x5C18E4C9, 0x4F48173D, 0xBD23943E, - 0xF36E6F75, 0x0105EC76, 0x12551F82, 0xE03E9C81, 0x34F4F86A, 0xC69F7B69, 0xD5CF889D, 0x27A40B9E, - 0x79B737BA, 0x8BDCB4B9, 0x988C474D, 0x6AE7C44E, 0xBE2DA0A5, 0x4C4623A6, 0x5F16D052, 0xAD7D5351 }; - -uint32_t csp_crc32_memory(const uint8_t * data, uint32_t length) { - uint32_t crc; - - crc = 0xFFFFFFFF; - while (length--) -#ifdef __AVR__ - crc = pgm_read_dword(&crc_tab[(crc ^ *data++) & 0xFFL]) ^ (crc >> 8); -#else - crc = crc_tab[(crc ^ *data++) & 0xFFL] ^ (crc >> 8); -#endif - - return (crc ^ 0xFFFFFFFF); -} - -int csp_crc32_append(csp_packet_t * packet, bool include_header) { - - uint32_t crc; - - /* NULL pointer check */ - if (packet == NULL) - return CSP_ERR_INVAL; - - /* Calculate CRC32, convert to network byte order */ - if (include_header) { - crc = csp_crc32_memory((uint8_t *) &packet->id, packet->length + sizeof(packet->id)); - } else { - crc = csp_crc32_memory(packet->data, packet->length); - } - crc = csp_hton32(crc); - - /* Copy checksum to packet */ - memcpy(&packet->data[packet->length], &crc, sizeof(uint32_t)); - packet->length += sizeof(uint32_t); - - return CSP_ERR_NONE; - -} - -int csp_crc32_verify(csp_packet_t * packet, bool include_header) { - - uint32_t crc; - - /* NULL pointer check */ - if (packet == NULL) - return CSP_ERR_INVAL; - - if (packet->length < sizeof(uint32_t)) - return CSP_ERR_INVAL; - - /* Calculate CRC32, convert to network byte order */ - if (include_header) { - crc = csp_crc32_memory((uint8_t *) &packet->id, packet->length + sizeof(packet->id) - sizeof(uint32_t)); - } else { - crc = csp_crc32_memory(packet->data, packet->length - sizeof(uint32_t)); - } - crc = csp_hton32(crc); - - /* Compare calculated checksum with packet header */ - if (memcmp(&packet->data[packet->length] - sizeof(uint32_t), &crc, sizeof(uint32_t)) != 0) { - /* CRC32 failed */ - return CSP_ERR_INVAL; - } else { - /* Strip CRC32 */ - packet->length -= sizeof(uint32_t); - return CSP_ERR_NONE; - } - -} - -#endif // CSP_USE_CRC32 diff --git a/libcsp/src/csp_debug.c b/libcsp/src/csp_debug.c deleted file mode 100644 index 2e710cb3..00000000 --- a/libcsp/src/csp_debug.c +++ /dev/null @@ -1,133 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include -#include -#include -#include - -#ifdef __AVR__ -#include -#endif - -/* CSP includes */ -#include - -#include - -/* Custom debug function */ -csp_debug_hook_func_t csp_debug_hook_func = NULL; - -/* Debug levels */ -static bool csp_debug_level_enabled[] = { - [CSP_ERROR] = true, - [CSP_WARN] = true, - [CSP_INFO] = false, - [CSP_BUFFER] = false, - [CSP_PACKET] = false, - [CSP_PROTOCOL] = false, - [CSP_LOCK] = false, -}; - -/* Some compilers do not support weak symbols, so this function - * can be used instead to set a custom debug hook */ -void csp_debug_hook_set(csp_debug_hook_func_t f) -{ - csp_debug_hook_func = f; -} - -void do_csp_debug(csp_debug_level_t level, const char *format, ...) -{ - int color = COLOR_RESET; - va_list args; - - /* Don't print anything if log level is disabled */ - if (level > CSP_LOCK || !csp_debug_level_enabled[level]) - return; - - switch(level) { - case CSP_INFO: - color = COLOR_GREEN | COLOR_BOLD; - break; - case CSP_ERROR: - color = COLOR_RED | COLOR_BOLD; - break; - case CSP_WARN: - color = COLOR_YELLOW | COLOR_BOLD; - break; - case CSP_BUFFER: - color = COLOR_MAGENTA; - break; - case CSP_PACKET: - color = COLOR_GREEN; - break; - case CSP_PROTOCOL: - color = COLOR_BLUE; - break; - case CSP_LOCK: - color = COLOR_CYAN; - break; - default: - return; - } - - va_start(args, format); - - /* If csp_debug_hook symbol is defined, pass on the message. - * Otherwise, just print with pretty colors ... */ - if (csp_debug_hook_func) { - csp_debug_hook_func(level, format, args); - } else { - csp_sys_set_color(color); -#ifdef __AVR__ - vfprintf_P(stdout, format, args); -#else - vprintf(format, args); -#endif - printf("\r\n"); - csp_sys_set_color(COLOR_RESET); - } - - va_end(args); -} - -void csp_debug_set_level(csp_debug_level_t level, bool value) -{ - if (level > CSP_LOCK) - return; - csp_debug_level_enabled[level] = value; -} - -int csp_debug_get_level(csp_debug_level_t level) -{ - if (level > CSP_LOCK) - return 0; - return csp_debug_level_enabled[level]; -} - -void csp_debug_toggle_level(csp_debug_level_t level) -{ - if (level > CSP_LOCK) { - printf("Max level is 6\r\n"); - return; - } - csp_debug_level_enabled[level] = (csp_debug_level_enabled[level]) ? false : true; - printf("Level %u: value %u\r\n", level, csp_debug_level_enabled[level]); -} diff --git a/libcsp/src/csp_dedup.c b/libcsp/src/csp_dedup.c deleted file mode 100644 index d263c7a4..00000000 --- a/libcsp/src/csp_dedup.c +++ /dev/null @@ -1,66 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include -#include -#include -#include - -#include -#include -#include - -#include "csp_dedup.h" - -/* Check the last CSP_DEDUP_COUNT packets for duplicates */ -#define CSP_DEDUP_COUNT 16 - -/* Only consider packet a duplicate if received under CSP_DEDUP_WINDOW_MS ago */ -#define CSP_DEDUP_WINDOW_MS 1000 - -/* Store packet CRC's in a ringbuffer */ -static uint32_t csp_dedup_array[CSP_DEDUP_COUNT] = {}; -static uint32_t csp_dedup_timestamp[CSP_DEDUP_COUNT] = {}; -static int csp_dedup_in = 0; - -bool csp_dedup_is_duplicate(csp_packet_t *packet) -{ - /* Calculate CRC32 for packet */ - uint32_t crc = csp_crc32_memory((const uint8_t *) &packet->id, packet->length + sizeof(packet->id)); - - /* Check if we have received this packet before */ - for (int i = 0; i < CSP_DEDUP_COUNT; i++) { - - /* Check for match */ - if (crc == csp_dedup_array[i]) { - - /* Check the timestamp */ - if (csp_get_ms() < csp_dedup_timestamp[i] + CSP_DEDUP_WINDOW_MS) - return true; - } - } - - /* If not, insert packet into duplicate list */ - csp_dedup_array[csp_dedup_in] = crc; - csp_dedup_timestamp[csp_dedup_in] = csp_get_ms(); - csp_dedup_in = (csp_dedup_in + 1) % CSP_DEDUP_COUNT; - - return false; -} diff --git a/libcsp/src/csp_dedup.h b/libcsp/src/csp_dedup.h deleted file mode 100644 index 75a3f124..00000000 --- a/libcsp/src/csp_dedup.h +++ /dev/null @@ -1,31 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#ifndef CSP_DEDUP_H_ -#define CSP_DEDUP_H_ - -/** - * Check for a duplicate packet - * @param packet pointer to packet - * @return false if not a duplicate, true if duplicate - */ -bool csp_dedup_is_duplicate(csp_packet_t *packet); - -#endif /* CSP_DEDUP_H_ */ diff --git a/libcsp/src/csp_endian.c b/libcsp/src/csp_endian.c deleted file mode 100644 index 6d0ef226..00000000 --- a/libcsp/src/csp_endian.c +++ /dev/null @@ -1,204 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include - -/* CSP includes */ -#include -#include - -/* Convert 16-bit number from host byte order to network byte order */ -inline uint16_t __attribute__ ((__const__)) csp_hton16(uint16_t h16) { -#ifdef CSP_BIG_ENDIAN - return h16; -#else - return (((h16 & 0xff00) >> 8) | - ((h16 & 0x00ff) << 8)); -#endif -} - -/* Convert 16-bit number from network byte order to host byte order */ -inline uint16_t __attribute__ ((__const__)) csp_ntoh16(uint16_t n16) { - return csp_hton16(n16); -} - -/* Convert 32-bit number from host byte order to network byte order */ -inline uint32_t __attribute__ ((__const__)) csp_hton32(uint32_t h32) { -#ifdef CSP_BIG_ENDIAN - return h32; -#else - return (((h32 & 0xff000000) >> 24) | - ((h32 & 0x000000ff) << 24) | - ((h32 & 0x0000ff00) << 8) | - ((h32 & 0x00ff0000) >> 8)); -#endif -} - -/* Convert 32-bit number from network byte order to host byte order */ -inline uint32_t __attribute__ ((__const__)) csp_ntoh32(uint32_t n32) { - return csp_hton32(n32); -} - -/* Convert 64-bit number from host byte order to network byte order */ -inline uint64_t __attribute__ ((__const__)) csp_hton64(uint64_t h64) { -#ifdef CSP_BIG_ENDIAN - return h64; -#else - return (((h64 & 0xff00000000000000LL) >> 56) | - ((h64 & 0x00000000000000ffLL) << 56) | - ((h64 & 0x00ff000000000000LL) >> 40) | - ((h64 & 0x000000000000ff00LL) << 40) | - ((h64 & 0x0000ff0000000000LL) >> 24) | - ((h64 & 0x0000000000ff0000LL) << 24) | - ((h64 & 0x000000ff00000000LL) >> 8) | - ((h64 & 0x00000000ff000000LL) << 8)); -#endif -} - -/* Convert 64-bit number from host byte order to network byte order */ -inline uint64_t __attribute__ ((__const__)) csp_ntoh64(uint64_t n64) { - return csp_hton64(n64); -} - -/* Convert 16-bit number from host byte order to big endian byte order */ -inline uint16_t __attribute__ ((__const__)) csp_htobe16(uint16_t h16) { - return csp_hton16(h16); -} - -/* Convert 16-bit number from host byte order to little endian byte order */ -inline uint16_t __attribute__ ((__const__)) csp_htole16(uint16_t h16) { -#ifdef CSP_LITTLE_ENDIAN - return h16; -#else - return (((h16 & 0xff00) >> 8) | - ((h16 & 0x00ff) << 8)); -#endif -} - -/* Convert 16-bit number from big endian byte order to little endian byte order */ -inline uint16_t __attribute__ ((__const__)) csp_betoh16(uint16_t be16) { - return csp_ntoh16(be16); -} - -/* Convert 16-bit number from little endian byte order to host byte order */ -inline uint16_t __attribute__ ((__const__)) csp_letoh16(uint16_t le16) { - return csp_htole16(le16); -} - -/* Convert 32-bit number from host byte order to big endian byte order */ -inline uint32_t __attribute__ ((__const__)) csp_htobe32(uint32_t h32) { - return csp_hton32(h32); -} - -/* Convert 32-bit number from little endian byte order to host byte order */ -inline uint32_t __attribute__ ((__const__)) csp_htole32(uint32_t h32) { -#ifdef CSP_LITTLE_ENDIAN - return h32; -#else - return (((h32 & 0xff000000) >> 24) | - ((h32 & 0x000000ff) << 24) | - ((h32 & 0x0000ff00) << 8) | - ((h32 & 0x00ff0000) >> 8)); -#endif -} - -/* Convert 32-bit number from big endian byte order to host byte order */ -inline uint32_t __attribute__ ((__const__)) csp_betoh32(uint32_t be32) { - return csp_ntoh32(be32); -} - -/* Convert 32-bit number from little endian byte order to host byte order */ -inline uint32_t __attribute__ ((__const__)) csp_letoh32(uint32_t le32) { - return csp_htole32(le32); -} - -/* Convert 64-bit number from host byte order to big endian byte order */ -inline uint64_t __attribute__ ((__const__)) csp_htobe64(uint64_t h64) { - return csp_hton64(h64); -} - -/* Convert 64-bit number from host byte order to little endian byte order */ -inline uint64_t __attribute__ ((__const__)) csp_htole64(uint64_t h64) { -#ifdef CSP_LITTLE_ENDIAN - return h64; -#else - return (((h64 & 0xff00000000000000LL) >> 56) | - ((h64 & 0x00000000000000ffLL) << 56) | - ((h64 & 0x00ff000000000000LL) >> 40) | - ((h64 & 0x000000000000ff00LL) << 40) | - ((h64 & 0x0000ff0000000000LL) >> 24) | - ((h64 & 0x0000000000ff0000LL) << 24) | - ((h64 & 0x000000ff00000000LL) >> 8) | - ((h64 & 0x00000000ff000000LL) << 8)); -#endif -} - -/* Convert 64-bit number from big endian byte order to host byte order */ -inline uint64_t __attribute__ ((__const__)) csp_betoh64(uint64_t be64) { - return csp_ntoh64(be64); -} - -/* Convert 64-bit number from little endian byte order to host byte order */ -inline uint64_t __attribute__ ((__const__)) csp_letoh64(uint64_t le64) { - return csp_htole64(le64); -} - - -/* Convert float from host byte order to network byte order */ -inline float __attribute__ ((__const__)) csp_htonflt(float f) { -#ifdef CSP_BIG_ENDIAN - return f; -#else - union v { - float f; - uint32_t i; - }; - union v val; - val.f = f; - val.i = csp_hton32(val.i); - return val.f; -#endif -} - -/* Convert float from host byte order to network byte order */ -inline float __attribute__ ((__const__)) csp_ntohflt(float f) { - return csp_htonflt(f); -} - -/* Convert double from host byte order to network byte order */ -inline double __attribute__ ((__const__)) csp_htondbl(double d) { -#ifdef CSP_BIG_ENDIAN - return d; -#else - union v { - double d; - uint64_t i; - }; - union v val; - val.d = d; - val.i = csp_hton64(val.i); - return val.d; -#endif -} - -/* Convert float from host byte order to network byte order */ -inline double __attribute__ ((__const__)) csp_ntohdbl(double d) { - return csp_htondbl(d); -} diff --git a/libcsp/src/csp_hex_dump.c b/libcsp/src/csp_hex_dump.c deleted file mode 100644 index af0a2660..00000000 --- a/libcsp/src/csp_hex_dump.c +++ /dev/null @@ -1,55 +0,0 @@ -#include -#include - -void csp_hex_dump (const char *desc, void *addr, int len) -{ - int i; - unsigned char buff[17]; - unsigned char *pc = (unsigned char*)addr; - - // Output description if given. - if (desc != NULL) - printf ("%s:\r\n", desc); - - if (len == 0) { - printf(" ZERO LENGTH\r\n"); - return; - } - if (len < 0) { - printf(" NEGATIVE LENGTH: %i\r\n",len); - return; - } - - // Process every byte in the data. - for (i = 0; i < len; i++) { - // Multiple of 16 means new line (with line offset). - - if ((i % 16) == 0) { - // Just don't print ASCII for the zeroth line. - if (i != 0) - printf (" %s\r\n", buff); - - // Output the offset. - printf (" %p ", addr + i); - } - - // Now the hex code for the specific character. - printf (" %02x", pc[i]); - - // And store a printable ASCII character for later. - if ((pc[i] < 0x20) || (pc[i] > 0x7e)) - buff[i % 16] = '.'; - else - buff[i % 16] = pc[i]; - buff[(i % 16) + 1] = '\0'; - } - - // Pad out last line if not exactly 16 characters. - while ((i % 16) != 0) { - printf (" "); - i++; - } - - // And print the final ASCII bit. - printf (" %s\r\n", buff); -} diff --git a/libcsp/src/csp_iflist.c b/libcsp/src/csp_iflist.c deleted file mode 100644 index 2bfef422..00000000 --- a/libcsp/src/csp_iflist.c +++ /dev/null @@ -1,100 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include -#include - -/* Interfaces are stored in a linked list*/ -static csp_iface_t * interfaces = NULL; - -csp_iface_t * csp_iflist_get_by_name(const char *name) { - csp_iface_t *ifc = interfaces; - while(ifc) { - if (strncmp(ifc->name, name, 10) == 0) - break; - ifc = ifc->next; - } - return ifc; -} - -void csp_iflist_add(csp_iface_t *ifc) { - - /* Add interface to pool */ - if (interfaces == NULL) { - /* This is the first interface to be added */ - interfaces = ifc; - ifc->next = NULL; - } else { - /* One or more interfaces were already added */ - csp_iface_t * i = interfaces; - while (i != ifc && i->next) - i = i->next; - - /* Insert interface last if not already in pool */ - if (i != ifc && i->next == NULL) { - i->next = ifc; - ifc->next = NULL; - } - } - -} - -csp_iface_t * csp_iflist_get(void) -{ - return interfaces; -} - -#ifdef CSP_DEBUG -static int csp_bytesize(char *buf, int len, unsigned long int n) { - char postfix; - double size; - - if (n >= 1048576) { - size = n/1048576.0; - postfix = 'M'; - } else if (n >= 1024) { - size = n/1024.; - postfix = 'K'; - } else { - size = n; - postfix = 'B'; - } - - return snprintf(buf, len, "%.1f%c", size, postfix); -} - -void csp_iflist_print(void) { - csp_iface_t * i = interfaces; - char txbuf[25], rxbuf[25]; - - while (i) { - csp_bytesize(txbuf, 25, i->txbytes); - csp_bytesize(rxbuf, 25, i->rxbytes); - printf("%-5s tx: %05"PRIu32" rx: %05"PRIu32" txe: %05"PRIu32" rxe: %05"PRIu32"\r\n" - " drop: %05"PRIu32" autherr: %05"PRIu32 " frame: %05"PRIu32"\r\n" - " txb: %"PRIu32" (%s) rxb: %"PRIu32" (%s)\r\n\r\n", - i->name, i->tx, i->rx, i->tx_error, i->rx_error, i->drop, - i->autherr, i->frame, i->txbytes, txbuf, i->rxbytes, rxbuf); - i = i->next; - } - -} -#endif - diff --git a/libcsp/src/csp_io.c b/libcsp/src/csp_io.c deleted file mode 100644 index 3d7f614a..00000000 --- a/libcsp/src/csp_io.c +++ /dev/null @@ -1,502 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include -#include -#include -#include - -/* CSP includes */ -#include -#include -#include -#include -#include -#include - -#include -#include -#include -#include -#include - -#include -#include - -#include "csp_io.h" -#include "csp_port.h" -#include "csp_conn.h" -#include "csp_route.h" -#include "csp_promisc.h" -#include "csp_qfifo.h" -#include "transport/csp_transport.h" - -/** CSP address of this node */ -static uint8_t csp_my_address; - -/* Hostname, model and build revision */ -static const char *csp_hostname = NULL; -static const char *csp_model = NULL; -static const char *csp_revision = GIT_REV; - -#ifdef CSP_USE_PROMISC -extern csp_queue_handle_t csp_promisc_queue; -#endif - -void csp_set_address(uint8_t addr) -{ - csp_my_address = addr; -} - -uint8_t csp_get_address(void) -{ - return csp_my_address; -} - -void csp_set_hostname(const char *hostname) -{ - csp_hostname = hostname; -} - -const char *csp_get_hostname(void) -{ - return csp_hostname; -} - -void csp_set_model(const char *model) -{ - csp_model = model; -} - -const char *csp_get_model(void) -{ - return csp_model; -} - -void csp_set_revision(const char *revision) -{ - csp_revision = revision; -} - -const char *csp_get_revision(void) -{ - return csp_revision; -} - -int csp_init(unsigned char address) { - - int ret; - - /* Initialize CSP */ - csp_set_address(address); - - ret = csp_conn_init(); - if (ret != CSP_ERR_NONE) - return ret; - - ret = csp_port_init(); - if (ret != CSP_ERR_NONE) - return ret; - - ret = csp_qfifo_init(); - if (ret != CSP_ERR_NONE) - return ret; - - /* Loopback */ - csp_iflist_add(&csp_if_lo); - - /* Register loopback route */ - csp_route_set(csp_get_address(), &csp_if_lo, CSP_NODE_MAC); - - /* Also register loopback as default, until user redefines default route */ - csp_route_set(CSP_DEFAULT_ROUTE, &csp_if_lo, CSP_NODE_MAC); - - return CSP_ERR_NONE; - -} - -csp_socket_t * csp_socket(uint32_t opts) { - - /* Validate socket options */ -#ifndef CSP_USE_RDP - if (opts & CSP_SO_RDPREQ) { - csp_log_error("Attempt to create socket that requires RDP, but CSP was compiled without RDP support"); - return NULL; - } -#endif - -#ifndef CSP_USE_XTEA - if (opts & CSP_SO_XTEAREQ) { - csp_log_error("Attempt to create socket that requires XTEA, but CSP was compiled without XTEA support"); - return NULL; - } -#endif - -#ifndef CSP_USE_HMAC - if (opts & CSP_SO_HMACREQ) { - csp_log_error("Attempt to create socket that requires HMAC, but CSP was compiled without HMAC support"); - return NULL; - } -#endif - -#ifndef CSP_USE_CRC32 - if (opts & CSP_SO_CRC32REQ) { - csp_log_error("Attempt to create socket that requires CRC32, but CSP was compiled without CRC32 support"); - return NULL; - } -#endif - - /* Drop packet if reserved flags are set */ - if (opts & ~(CSP_SO_RDPREQ | CSP_SO_XTEAREQ | CSP_SO_HMACREQ | CSP_SO_CRC32REQ | CSP_SO_CONN_LESS)) { - csp_log_error("Invalid socket option"); - return NULL; - } - - /* Use CSP buffers instead? */ - csp_socket_t * sock = csp_conn_allocate(CONN_SERVER); - if (sock == NULL) - return NULL; - - /* If connectionless, init the queue to a pre-defined size - * if not, the user must init the queue using csp_listen */ - if (opts & CSP_SO_CONN_LESS) { - sock->socket = csp_queue_create(CSP_CONN_QUEUE_LENGTH, sizeof(csp_packet_t *)); - if (sock->socket == NULL) { - csp_close(sock); - return NULL; - } - } else { - sock->socket = NULL; - } - sock->opts = opts; - - return sock; - -} - -csp_conn_t * csp_accept(csp_socket_t * sock, uint32_t timeout) { - - if (sock == NULL) - return NULL; - - if (sock->socket == NULL) - return NULL; - - csp_conn_t * conn; - if (csp_queue_dequeue(sock->socket, &conn, timeout) == CSP_QUEUE_OK) - return conn; - - return NULL; - -} - -csp_packet_t * csp_read(csp_conn_t * conn, uint32_t timeout) { - - csp_packet_t * packet = NULL; - - if (conn == NULL || conn->state != CONN_OPEN) - return NULL; - -#ifdef CSP_USE_QOS - int prio, event; - if (csp_queue_dequeue(conn->rx_event, &event, timeout) != CSP_QUEUE_OK) - return NULL; - - for (prio = 0; prio < CSP_RX_QUEUES; prio++) - if (csp_queue_dequeue(conn->rx_queue[prio], &packet, 0) == CSP_QUEUE_OK) - break; -#else - if (csp_queue_dequeue(conn->rx_queue[0], &packet, timeout) != CSP_QUEUE_OK) - return NULL; -#endif - -#ifdef CSP_USE_RDP - /* Packet read could trigger ACK transmission */ - if (conn->idin.flags & CSP_FRDP && conn->rdp.delayed_acks) - csp_rdp_check_ack(conn); - -#endif - - return packet; - -} - -int csp_send_direct(csp_id_t idout, csp_packet_t * packet, csp_iface_t * ifout, uint32_t timeout) { - - if (packet == NULL) { - csp_log_error("csp_send_direct called with NULL packet"); - goto err; - } - - if ((ifout == NULL) || (ifout->nexthop == NULL)) { - csp_log_error("No route to host: %#08x", idout.ext); - goto err; - } - - csp_log_packet("OUT: S %u, D %u, Dp %u, Sp %u, Pr %u, Fl 0x%02X, Sz %u VIA: %s", - idout.src, idout.dst, idout.dport, idout.sport, idout.pri, idout.flags, packet->length, ifout->name); - - /* Copy identifier to packet (before crc, xtea and hmac) */ - packet->id.ext = idout.ext; - -#ifdef CSP_USE_PROMISC - /* Loopback traffic is added to promisc queue by the router */ - if (idout.dst != csp_get_address() && idout.src == csp_get_address()) { - packet->id.ext = idout.ext; - csp_promisc_add(packet); - } -#endif - - /* Only encrypt packets from the current node */ - if (idout.src == csp_get_address()) { - /* Append HMAC */ - if (idout.flags & CSP_FHMAC) { -#ifdef CSP_USE_HMAC - /* Calculate and add HMAC (does not include header for backwards compatability with csp1.x) */ - if (csp_hmac_append(packet, false) != 0) { - /* HMAC append failed */ - csp_log_warn("HMAC append failed!"); - goto tx_err; - } -#else - csp_log_warn("Attempt to send packet with HMAC, but CSP was compiled without HMAC support. Discarding packet"); - goto tx_err; -#endif - } - - /* Append CRC32 */ - if (idout.flags & CSP_FCRC32) { -#ifdef CSP_USE_CRC32 - /* Calculate and add CRC32 (does not include header for backwards compatability with csp1.x) */ - if (csp_crc32_append(packet, false) != 0) { - /* CRC32 append failed */ - csp_log_warn("CRC32 append failed!"); - goto tx_err; - } -#else - csp_log_warn("Attempt to send packet with CRC32, but CSP was compiled without CRC32 support. Sending without CRC32r"); - idout.flags &= ~(CSP_FCRC32); -#endif - } - - if (idout.flags & CSP_FXTEA) { -#ifdef CSP_USE_XTEA - /* Create nonce */ - uint32_t nonce, nonce_n; - nonce = (uint32_t)rand(); - nonce_n = csp_hton32(nonce); - memcpy(&packet->data[packet->length], &nonce_n, sizeof(nonce_n)); - - /* Create initialization vector */ - uint32_t iv[2] = {nonce, 1}; - - /* Encrypt data */ - if (csp_xtea_encrypt(packet->data, packet->length, iv) != 0) { - /* Encryption failed */ - csp_log_warn("Encryption failed! Discarding packet"); - goto tx_err; - } - - packet->length += sizeof(nonce_n); -#else - csp_log_warn("Attempt to send XTEA encrypted packet, but CSP was compiled without XTEA support. Discarding packet"); - goto tx_err; -#endif - } - } - - /* Store length before passing to interface */ - uint16_t bytes = packet->length; - uint16_t mtu = ifout->mtu; - - if (mtu > 0 && bytes > mtu) - goto tx_err; - - if ((*ifout->nexthop)(ifout, packet, timeout) != CSP_ERR_NONE) - goto tx_err; - - ifout->tx++; - ifout->txbytes += bytes; - return CSP_ERR_NONE; - -tx_err: - ifout->tx_error++; -err: - return CSP_ERR_TX; - -} - -int csp_send(csp_conn_t * conn, csp_packet_t * packet, uint32_t timeout) { - - int ret; - - if ((conn == NULL) || (packet == NULL) || (conn->state != CONN_OPEN)) { - csp_log_error("Invalid call to csp_send"); - return 0; - } - -#ifdef CSP_USE_RDP - if (conn->idout.flags & CSP_FRDP) { - if (csp_rdp_send(conn, packet, timeout) != CSP_ERR_NONE) { - csp_iface_t * ifout = csp_rtable_find_iface(conn->idout.dst); - if (ifout != NULL) - ifout->tx_error++; - csp_log_warn("RDP send failed!"); - return 0; - } - } -#endif - - csp_iface_t * ifout = csp_rtable_find_iface(conn->idout.dst); - ret = csp_send_direct(conn->idout, packet, ifout, timeout); - - return (ret == CSP_ERR_NONE) ? 1 : 0; - -} - -int csp_send_prio(uint8_t prio, csp_conn_t * conn, csp_packet_t * packet, uint32_t timeout) { - conn->idout.pri = prio; - return csp_send(conn, packet, timeout); -} - -int csp_transaction_persistent(csp_conn_t * conn, uint32_t timeout, void * outbuf, int outlen, void * inbuf, int inlen) { - - int size = (inlen > outlen) ? inlen : outlen; - csp_packet_t * packet = csp_buffer_get(size); - if (packet == NULL) - return 0; - - /* Copy the request */ - if (outlen > 0 && outbuf != NULL) - memcpy(packet->data, outbuf, outlen); - packet->length = outlen; - - if (!csp_send(conn, packet, timeout)) { - csp_buffer_free(packet); - return 0; - } - - /* If no reply is expected, return now */ - if (inlen == 0) - return 1; - - packet = csp_read(conn, timeout); - if (packet == NULL) - return 0; - - if ((inlen != -1) && ((int)packet->length != inlen)) { - csp_log_error("Reply length %u expected %u", packet->length, inlen); - csp_buffer_free(packet); - return 0; - } - - memcpy(inbuf, packet->data, packet->length); - int length = packet->length; - csp_buffer_free(packet); - return length; - -} - -int csp_transaction(uint8_t prio, uint8_t dest, uint8_t port, uint32_t timeout, void * outbuf, int outlen, void * inbuf, int inlen) { - return csp_transaction2(prio, dest, port, timeout, outbuf, outlen, inbuf, inlen, 0); -} - -int csp_transaction2(uint8_t prio, uint8_t dest, uint8_t port, uint32_t timeout, void * outbuf, int outlen, void * inbuf, int inlen, uint32_t opts) { - - csp_conn_t * conn = csp_connect(prio, dest, port, 0, opts); - if (conn == NULL) - return 0; - - int status = csp_transaction_persistent(conn, timeout, outbuf, outlen, inbuf, inlen); - - csp_close(conn); - - return status; - -} - -csp_packet_t * csp_recvfrom(csp_socket_t * socket, uint32_t timeout) { - - if ((socket == NULL) || (!(socket->opts & CSP_SO_CONN_LESS))) - return NULL; - - csp_packet_t * packet = NULL; - csp_queue_dequeue(socket->socket, &packet, timeout); - - return packet; - -} - -int csp_sendto(uint8_t prio, uint8_t dest, uint8_t dport, uint8_t src_port, uint32_t opts, csp_packet_t * packet, uint32_t timeout) { - - packet->id.flags = 0; - - if (opts & CSP_O_RDP) { - csp_log_error("Attempt to create RDP packet on connection-less socket"); - return CSP_ERR_INVAL; - } - - if (opts & CSP_O_HMAC) { -#ifdef CSP_USE_HMAC - packet->id.flags |= CSP_FHMAC; -#else - csp_log_error("Attempt to create HMAC authenticated packet, but CSP was compiled without HMAC support"); - return CSP_ERR_NOTSUP; -#endif - } - - if (opts & CSP_O_XTEA) { -#ifdef CSP_USE_XTEA - packet->id.flags |= CSP_FXTEA; -#else - csp_log_error("Attempt to create XTEA encrypted packet, but CSP was compiled without XTEA support"); - return CSP_ERR_NOTSUP; -#endif - } - - if (opts & CSP_O_CRC32) { -#ifdef CSP_USE_CRC32 - packet->id.flags |= CSP_FCRC32; -#else - csp_log_error("Attempt to create CRC32 validated packet, but CSP was compiled without CRC32 support"); - return CSP_ERR_NOTSUP; -#endif - } - - packet->id.dst = dest; - packet->id.dport = dport; - packet->id.src = csp_get_address(); - packet->id.sport = src_port; - packet->id.pri = prio; - - csp_iface_t * ifout = csp_rtable_find_iface(dest); - if (csp_send_direct(packet->id, packet, ifout, timeout) != CSP_ERR_NONE) - return CSP_ERR_NOTSUP; - - return CSP_ERR_NONE; - -} - -int csp_sendto_reply(csp_packet_t * request_packet, csp_packet_t * reply_packet, uint32_t opts, uint32_t timeout) { - if (request_packet == NULL) - return CSP_ERR_INVAL; - - return csp_sendto(request_packet->id.pri, request_packet->id.src, request_packet->id.sport, request_packet->id.dport, opts, reply_packet, timeout); -} diff --git a/libcsp/src/csp_io.h b/libcsp/src/csp_io.h deleted file mode 100644 index 6ea8dfec..00000000 --- a/libcsp/src/csp_io.h +++ /dev/null @@ -1,47 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#ifndef _CSP_IO_H_ -#define _CSP_IO_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include - -#include - -/** - * Function to transmit a frame without an existing connection structure. - * This function is used for stateless transmissions - * @param idout 32bit CSP identifier - * @param packet pointer to packet, - * @param ifout pointer to output interface - * @param timeout a timeout to wait for TX to complete. NOTE: not all underlying drivers supports flow-control. - * @return returns 1 if successful and 0 otherwise. you MUST free the frame yourself if the transmission was not successful. - */ -int csp_send_direct(csp_id_t idout, csp_packet_t * packet, csp_iface_t * ifout, uint32_t timeout); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // _CSP_IO_H_ diff --git a/libcsp/src/csp_port.c b/libcsp/src/csp_port.c deleted file mode 100644 index 2a4ac2a9..00000000 --- a/libcsp/src/csp_port.c +++ /dev/null @@ -1,105 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include -#include -#include - -/* CSP includes */ -#include -#include - -#include -#include -#include - -#include "csp_port.h" -#include "csp_conn.h" - -/* Allocation of ports */ -static csp_port_t ports[CSP_MAX_BIND_PORT + 2]; - -csp_socket_t * csp_port_get_socket(unsigned int port) { - - csp_socket_t * ret = NULL; - - if (port >= CSP_ANY) - return NULL; - - /* Match dport to socket or local "catch all" port number */ - if (ports[port].state == PORT_OPEN) - ret = ports[port].socket; - else if (ports[CSP_ANY].state == PORT_OPEN) - ret = ports[CSP_ANY].socket; - - return ret; - -} - -int csp_port_init(void) { - - memset(ports, PORT_CLOSED, sizeof(csp_port_t) * (CSP_MAX_BIND_PORT + 2)); - - return CSP_ERR_NONE; - -} - -int csp_listen(csp_socket_t * socket, size_t conn_queue_length) { - - if (socket == NULL) - return CSP_ERR_INVAL; - - socket->socket = csp_queue_create(conn_queue_length, sizeof(csp_conn_t *)); - if (socket->socket == NULL) - return CSP_ERR_NOMEM; - - socket->opts |= CSP_SO_INTERNAL_LISTEN; - - return CSP_ERR_NONE; - -} - -int csp_bind(csp_socket_t * socket, uint8_t port) { - - if (socket == NULL) - return CSP_ERR_INVAL; - - if (port > CSP_ANY) { - csp_log_error("Only ports from 0-%u (and CSP_ANY for default) are available for incoming ports", CSP_ANY); - return CSP_ERR_INVAL; - } - - /* Check if port number is valid */ - if (ports[port].state != PORT_CLOSED) { - csp_log_error("Port %d is already in use", port); - return CSP_ERR_USED; - } - - csp_log_info("Binding socket %p to port %u", socket, port); - - /* Save listener */ - ports[port].socket = socket; - ports[port].state = PORT_OPEN; - - return CSP_ERR_NONE; - -} - - diff --git a/libcsp/src/csp_port.h b/libcsp/src/csp_port.h deleted file mode 100644 index d2ec06e9..00000000 --- a/libcsp/src/csp_port.h +++ /dev/null @@ -1,55 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#ifndef _CSP_PORT_H_ -#define _CSP_PORT_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include - -#include - -/** @brief Port states */ -typedef enum { - PORT_CLOSED = 0, - PORT_OPEN = 1, -} csp_port_state_t; - -/** @brief Port struct */ -typedef struct { - csp_port_state_t state; // Port state - csp_socket_t * socket; // New connections are added to this socket's conn queue -} csp_port_t; - -/** - * Init ports array - */ -int csp_port_init(void); - -csp_socket_t * csp_port_get_socket(unsigned int dport); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // _CSP_PORT_H_ diff --git a/libcsp/src/csp_promisc.c b/libcsp/src/csp_promisc.c deleted file mode 100644 index 5f156c33..00000000 --- a/libcsp/src/csp_promisc.c +++ /dev/null @@ -1,82 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include -#include - -#ifdef CSP_USE_PROMISC - -static csp_queue_handle_t csp_promisc_queue = NULL; -static int csp_promisc_enabled = 0; - -int csp_promisc_enable(unsigned int buf_size) { - - /* If queue already initialised */ - if (csp_promisc_queue != NULL) { - csp_promisc_enabled = 1; - return CSP_ERR_NONE; - } - - /* Create packet queue */ - csp_promisc_queue = csp_queue_create(buf_size, sizeof(csp_packet_t *)); - - if (csp_promisc_queue == NULL) - return CSP_ERR_INVAL; - - csp_promisc_enabled = 1; - return CSP_ERR_NONE; - -} - -void csp_promisc_disable(void) { - csp_promisc_enabled = 0; -} - -csp_packet_t * csp_promisc_read(uint32_t timeout) { - - if (csp_promisc_queue == NULL) - return NULL; - - csp_packet_t * packet = NULL; - csp_queue_dequeue(csp_promisc_queue, &packet, timeout); - - return packet; - -} - -void csp_promisc_add(csp_packet_t * packet) { - - if (csp_promisc_enabled == 0) - return; - - if (csp_promisc_queue != NULL) { - /* Make a copy of the message and queue it to the promiscuous task */ - csp_packet_t *packet_copy = csp_buffer_clone(packet); - if (packet_copy != NULL) { - if (csp_queue_enqueue(csp_promisc_queue, &packet_copy, 0) != CSP_QUEUE_OK) { - csp_log_error("Promiscuous mode input queue full"); - csp_buffer_free(packet_copy); - } - } - } - -} - -#endif diff --git a/libcsp/src/csp_promisc.h b/libcsp/src/csp_promisc.h deleted file mode 100644 index be62edda..00000000 --- a/libcsp/src/csp_promisc.h +++ /dev/null @@ -1,30 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 Gomspace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#ifndef CSP_PROMISC_H_ -#define CSP_PROMISC_H_ - -/** - * Add packet to promiscuous mode packet queue - * @param packet Packet to add to the queue - */ -void csp_promisc_add(csp_packet_t * packet); - -#endif /* CSP_PROMISC_H_ */ diff --git a/libcsp/src/csp_qfifo.c b/libcsp/src/csp_qfifo.c deleted file mode 100644 index 9329b2ca..00000000 --- a/libcsp/src/csp_qfifo.c +++ /dev/null @@ -1,149 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include -#include -#include -#include "csp_qfifo.h" - -static csp_queue_handle_t qfifo[CSP_ROUTE_FIFOS]; -#ifdef CSP_USE_QOS -static csp_queue_handle_t qfifo_events; -#endif - -int csp_qfifo_init(void) { - int prio; - - /* Create router fifos for each priority */ - for (prio = 0; prio < CSP_ROUTE_FIFOS; prio++) { - if (qfifo[prio] == NULL) { - qfifo[prio] = csp_queue_create(CSP_FIFO_INPUT, sizeof(csp_qfifo_t)); - if (!qfifo[prio]) - return CSP_ERR_NOMEM; - } - } - -#ifdef CSP_USE_QOS - /* Create QoS fifo notification queue */ - qfifo_events = csp_queue_create(CSP_FIFO_INPUT, sizeof(int)); - if (!qfifo_events) - return CSP_ERR_NOMEM; -#endif - - return CSP_ERR_NONE; - -} - -int csp_qfifo_read(csp_qfifo_t * input) { - -#ifdef CSP_USE_QOS - int prio, found, event; - - /* Wait for packet in any queue */ - if (csp_queue_dequeue(qfifo_events, &event, FIFO_TIMEOUT) != CSP_QUEUE_OK) - return CSP_ERR_TIMEDOUT; - - /* Find packet with highest priority */ - found = 0; - for (prio = 0; prio < CSP_ROUTE_FIFOS; prio++) { - if (csp_queue_dequeue(qfifo[prio], input, 0) == CSP_QUEUE_OK) { - found = 1; - break; - } - } - - if (!found) { - csp_log_warn("Spurious wakeup: No packet found"); - return CSP_ERR_TIMEDOUT; - } -#else - if (csp_queue_dequeue(qfifo[0], input, FIFO_TIMEOUT) != CSP_QUEUE_OK) - return CSP_ERR_TIMEDOUT; -#endif - - return CSP_ERR_NONE; - -} - -void csp_qfifo_write(csp_packet_t * packet, csp_iface_t * interface, CSP_BASE_TYPE * pxTaskWoken) { - - int result; - - if (packet == NULL) { - if (pxTaskWoken == NULL) { // Only do logging in non-ISR context - csp_log_warn("csp_new packet called with NULL packet"); - } - return; - } else if (interface == NULL) { - if (pxTaskWoken == NULL) { // Only do logging in non-ISR context - csp_log_warn("csp_new packet called with NULL interface"); - } - if (pxTaskWoken == NULL) - csp_buffer_free(packet); - else - csp_buffer_free_isr(packet); - return; - } - - csp_qfifo_t queue_element; - queue_element.interface = interface; - queue_element.packet = packet; - -#ifdef CSP_USE_QOS - int fifo = packet->id.pri; -#else - int fifo = 0; -#endif - - if (pxTaskWoken == NULL) - result = csp_queue_enqueue(qfifo[fifo], &queue_element, 0); - else - result = csp_queue_enqueue_isr(qfifo[fifo], &queue_element, pxTaskWoken); - -#ifdef CSP_USE_QOS - static int event = 0; - - if (result == CSP_QUEUE_OK) { - if (pxTaskWoken == NULL) - csp_queue_enqueue(qfifo_events, &event, 0); - else - csp_queue_enqueue_isr(qfifo_events, &event, pxTaskWoken); - } -#endif - - if (result != CSP_QUEUE_OK) { - if (pxTaskWoken == NULL) { // Only do logging in non-ISR context - csp_log_warn("ERROR: Routing input FIFO is FULL. Dropping packet."); - } - interface->drop++; - if (pxTaskWoken == NULL) - csp_buffer_free(packet); - else - csp_buffer_free_isr(packet); - } - -} - -void csp_qfifo_wake_up(void) { - csp_qfifo_t queue_element; - queue_element.interface = NULL; - queue_element.packet = NULL; - csp_queue_enqueue(qfifo[0], &queue_element, 0); -} diff --git a/libcsp/src/csp_qfifo.h b/libcsp/src/csp_qfifo.h deleted file mode 100644 index 2910c48d..00000000 --- a/libcsp/src/csp_qfifo.h +++ /dev/null @@ -1,54 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#ifndef CSP_QFIFO_H_ -#define CSP_QFIFO_H_ - -#ifdef CSP_USE_RDP -#define FIFO_TIMEOUT 100 //! If RDP is enabled, the router needs to awake some times to check timeouts -#else -#define FIFO_TIMEOUT CSP_MAX_DELAY //! If no RDP, the router can sleep untill data arrives -#endif - -/** - * Init FIFO/QOS queues - * @return CSP_ERR type - */ -int csp_qfifo_init(void); - -typedef struct { - csp_iface_t * interface; - csp_packet_t * packet; -} csp_qfifo_t; - -/** - * Read next packet from router input queue - * @param input pointer to router queue item element - * @return CSP_ERR type - */ -int csp_qfifo_read(csp_qfifo_t * input); - -/** - * Wake up any task (e.g. router) waiting on messages. - * For testing. - */ -void csp_qfifo_wake_up(void); - -#endif /* CSP_QFIFO_H_ */ diff --git a/libcsp/src/csp_route.c b/libcsp/src/csp_route.c deleted file mode 100644 index bc843577..00000000 --- a/libcsp/src/csp_route.c +++ /dev/null @@ -1,346 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include -#include -#include - -/* CSP includes */ -#include -#include -#include - -#include -#include - -#include -#include - -#include "csp_port.h" -#include "csp_conn.h" -#include "csp_io.h" -#include "csp_promisc.h" -#include "csp_qfifo.h" -#include "csp_dedup.h" -#include "transport/csp_transport.h" - -/** - * Check supported packet options - * @param interface pointer to incoming interface - * @param packet pointer to packet - * @return CSP_ERR_NONE is all options are supported, CSP_ERR_NOTSUP if not - */ -static int csp_route_check_options(csp_iface_t *interface, csp_packet_t *packet) -{ -#ifndef CSP_USE_XTEA - /* Drop XTEA packets */ - if (packet->id.flags & CSP_FXTEA) { - csp_log_error("Received XTEA encrypted packet, but CSP was compiled without XTEA support. Discarding packet"); - interface->autherr++; - return CSP_ERR_NOTSUP; - } -#endif - -#ifndef CSP_USE_HMAC - /* Drop HMAC packets */ - if (packet->id.flags & CSP_FHMAC) { - csp_log_error("Received packet with HMAC, but CSP was compiled without HMAC support. Discarding packet"); - interface->autherr++; - return CSP_ERR_NOTSUP; - } -#endif - -#ifndef CSP_USE_RDP - /* Drop RDP packets */ - if (packet->id.flags & CSP_FRDP) { - csp_log_error("Received RDP packet, but CSP was compiled without RDP support. Discarding packet"); - interface->rx_error++; - return CSP_ERR_NOTSUP; - } -#endif - return CSP_ERR_NONE; -} - -/** - * Helper function to decrypt, check auth and CRC32 - * @param security_opts either socket_opts or conn_opts - * @param interface pointer to incoming interface - * @param packet pointer to packet - * @return -1 Missing feature, -2 XTEA error, -3 CRC error, -4 HMAC error, 0 = OK. - */ -static int csp_route_security_check(uint32_t security_opts, csp_iface_t * interface, csp_packet_t * packet) { - -#ifdef CSP_USE_XTEA - /* XTEA encrypted packet */ - if (packet->id.flags & CSP_FXTEA) { - /* Read nonce */ - uint32_t nonce; - memcpy(&nonce, &packet->data[packet->length - sizeof(nonce)], sizeof(nonce)); - nonce = csp_ntoh32(nonce); - packet->length -= sizeof(nonce); - - /* Create initialization vector */ - uint32_t iv[2] = {nonce, 1}; - - /* Decrypt data */ - if (csp_xtea_decrypt(packet->data, packet->length, iv) != 0) { - /* Decryption failed */ - csp_log_error("Decryption failed! Discarding packet"); - interface->autherr++; - return CSP_ERR_XTEA; - } - } else if (security_opts & CSP_SO_XTEAREQ) { - csp_log_warn("Received packet without XTEA encryption. Discarding packet"); - interface->autherr++; - return CSP_ERR_XTEA; - } -#endif - - /* CRC32 verified packet */ - if (packet->id.flags & CSP_FCRC32) { -#ifdef CSP_USE_CRC32 - if (packet->length < 4) - csp_log_error("Too short packet for CRC32, %u", packet->length); - /* Verify CRC32 (does not include header for backwards compatability with csp1.x) */ - if (csp_crc32_verify(packet, false) != 0) { - /* Checksum failed */ - csp_log_error("CRC32 verification error! Discarding packet"); - interface->rx_error++; - return CSP_ERR_CRC32; - } - } else if (security_opts & CSP_SO_CRC32REQ) { - csp_log_warn("Received packet without CRC32. Accepting packet"); -#else - /* Strip CRC32 field and accept the packet */ - csp_log_warn("Received packet with CRC32, but CSP was compiled without CRC32 support. Accepting packet"); - packet->length -= sizeof(uint32_t); -#endif - } - -#ifdef CSP_USE_HMAC - /* HMAC authenticated packet */ - if (packet->id.flags & CSP_FHMAC) { - /* Verify HMAC (does not include header for backwards compatability with csp1.x) */ - if (csp_hmac_verify(packet, false) != 0) { - /* HMAC failed */ - csp_log_error("HMAC verification error! Discarding packet"); - interface->autherr++; - return CSP_ERR_HMAC; - } - } else if (security_opts & CSP_SO_HMACREQ) { - csp_log_warn("Received packet without HMAC. Discarding packet"); - interface->autherr++; - return CSP_ERR_HMAC; - } -#endif - -#ifdef CSP_USE_RDP - /* RDP packet */ - if (!(packet->id.flags & CSP_FRDP)) { - if (security_opts & CSP_SO_RDPREQ) { - csp_log_warn("Received packet without RDP header. Discarding packet"); - interface->rx_error++; - return CSP_ERR_INVAL; - } - } -#endif - - return CSP_ERR_NONE; - -} - -int csp_route_work(uint32_t timeout) { - - csp_qfifo_t input; - csp_packet_t * packet; - csp_conn_t * conn; - csp_socket_t * socket; - -#ifdef CSP_USE_RDP - /* Check connection timeouts (currently only for RDP) */ - csp_conn_check_timeouts(); -#endif - - /* Get next packet to route */ - if (csp_qfifo_read(&input) != CSP_ERR_NONE) - return -1; - - packet = input.packet; - if (!packet) - return -1; - - csp_log_packet("INP: S %u, D %u, Dp %u, Sp %u, Pr %u, Fl 0x%02X, Sz %"PRIu16" VIA: %s", - packet->id.src, packet->id.dst, packet->id.dport, - packet->id.sport, packet->id.pri, packet->id.flags, packet->length, input.interface->name); - - /* Here there be promiscuous mode */ -#ifdef CSP_USE_PROMISC - csp_promisc_add(packet); -#endif - -#ifdef CSP_USE_DEDUP - /* Check for duplicates */ - if (csp_dedup_is_duplicate(packet)) { - /* Discard packet */ - csp_log_packet("Duplicate packet discarded"); - input.interface->drop++; - csp_buffer_free(packet); - return 0; - } -#endif - - /* Now we count the message (since its deduplicated) */ - input.interface->rx++; - input.interface->rxbytes += packet->length; - - /* If the message is not to me, route the message to the correct interface */ - if ((packet->id.dst != csp_get_address()) && (packet->id.dst != CSP_BROADCAST_ADDR)) { - - /* Find the destination interface */ - csp_iface_t * dstif = csp_rtable_find_iface(packet->id.dst); - - /* If the message resolves to the input interface, don't loop it back out */ - if ((dstif == NULL) || ((dstif == input.interface) && (input.interface->split_horizon_off == 0))) { - csp_buffer_free(packet); - return 0; - } - - /* Otherwise, actually send the message */ - if (csp_send_direct(packet->id, packet, dstif, 0) != CSP_ERR_NONE) { - csp_log_warn("Router failed to send"); - csp_buffer_free(packet); - } - - /* Next message, please */ - return 0; - } - - /* Discard packets with unsupported options */ - if (csp_route_check_options(input.interface, packet) != CSP_ERR_NONE) { - csp_buffer_free(packet); - return 0; - } - - /* The message is to me, search for incoming socket */ - socket = csp_port_get_socket(packet->id.dport); - - /* If the socket is connection-less, deliver now */ - if (socket && (socket->opts & CSP_SO_CONN_LESS)) { - if (csp_route_security_check(socket->opts, input.interface, packet) < 0) { - csp_buffer_free(packet); - return 0; - } - if (csp_queue_enqueue(socket->socket, &packet, 0) != CSP_QUEUE_OK) { - csp_log_error("Conn-less socket queue full"); - csp_buffer_free(packet); - return 0; - } - return 0; - } - - /* Search for an existing connection */ - conn = csp_conn_find(packet->id.ext, CSP_ID_CONN_MASK); - - /* If this is an incoming packet on a new connection */ - if (conn == NULL) { - - /* Reject packet if no matching socket is found */ - if (!socket) { - csp_buffer_free(packet); - return 0; - } - - /* Run security check on incoming packet */ - if (csp_route_security_check(socket->opts, input.interface, packet) < 0) { - csp_buffer_free(packet); - return 0; - } - - /* New incoming connection accepted */ - csp_id_t idout; - idout.pri = packet->id.pri; - idout.src = csp_get_address(); - - idout.dst = packet->id.src; - idout.dport = packet->id.sport; - idout.sport = packet->id.dport; - idout.flags = packet->id.flags; - - /* Create connection */ - conn = csp_conn_new(packet->id, idout); - - if (!conn) { - csp_log_error("No more connections available"); - csp_buffer_free(packet); - return 0; - } - - /* Store the socket queue and options */ - conn->socket = socket->socket; - conn->opts = socket->opts; - - /* Packet to existing connection */ - } else { - - /* Run security check on incoming packet */ - if (csp_route_security_check(conn->opts, input.interface, packet) < 0) { - csp_buffer_free(packet); - return 0; - } - - } - -#ifdef CSP_USE_RDP - /* Pass packet to RDP module */ - if (packet->id.flags & CSP_FRDP) { - csp_rdp_new_packet(conn, packet); - return 0; - } -#endif - - /* Pass packet to UDP module */ - csp_udp_new_packet(conn, packet); - return 0; -} - -static CSP_DEFINE_TASK(csp_task_router) { - - /* Here there be routing */ - while (1) { - csp_route_work(FIFO_TIMEOUT); - } - - return CSP_TASK_RETURN; - -} - -int csp_route_start_task(unsigned int task_stack_size, unsigned int priority) { - - static csp_thread_handle_t handle_router; - int ret = csp_thread_create(csp_task_router, "RTE", task_stack_size, NULL, priority, &handle_router); - - if (ret != 0) { - csp_log_error("Failed to start router task"); - return CSP_ERR_NOMEM; - } - - return CSP_ERR_NONE; - -} diff --git a/libcsp/src/csp_route.h b/libcsp/src/csp_route.h deleted file mode 100644 index 2a20f49f..00000000 --- a/libcsp/src/csp_route.h +++ /dev/null @@ -1,24 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#ifndef _CSP_ROUTE_H_ -#define _CSP_ROUTE_H_ - -#endif // _CSP_ROUTE_H_ diff --git a/libcsp/src/csp_service_handler.c b/libcsp/src/csp_service_handler.c deleted file mode 100644 index 0090afc1..00000000 --- a/libcsp/src/csp_service_handler.c +++ /dev/null @@ -1,334 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include -#include -#include - -/* CSP includes */ -#include -#include -#include -#include -#include - -#include -#include -#include -#include -#include "csp_route.h" - -#define CSP_RPS_MTU 196 - -/** - * The CSP CMP mempy function is used to, override the function used to - * read/write memory by peek and poke. - */ -#ifdef __AVR__ -static uint32_t wrap_32bit_memcpy(uint32_t to, const uint32_t from, size_t size) { - return (uint32_t) (uintptr_t) memcpy((void *) (uintptr_t) to, (const void *) (uintptr_t) from, size); -} -static csp_memcpy_fnc_t csp_cmp_memcpy_fnc = wrap_32bit_memcpy; -#else -static csp_memcpy_fnc_t csp_cmp_memcpy_fnc = (csp_memcpy_fnc_t) memcpy; -#endif - - -void csp_cmp_set_memcpy(csp_memcpy_fnc_t fnc) { - csp_cmp_memcpy_fnc = fnc; -} - -static int do_cmp_ident(struct csp_cmp_message *cmp) { - - /* Copy revision */ - strncpy(cmp->ident.revision, csp_get_revision(), CSP_CMP_IDENT_REV_LEN); - cmp->ident.revision[CSP_CMP_IDENT_REV_LEN - 1] = '\0'; - - /* Copy compilation date */ - strncpy(cmp->ident.date, __DATE__, CSP_CMP_IDENT_DATE_LEN); - cmp->ident.date[CSP_CMP_IDENT_DATE_LEN - 1] = '\0'; - - /* Copy compilation time */ - strncpy(cmp->ident.time, __TIME__, CSP_CMP_IDENT_TIME_LEN); - cmp->ident.time[CSP_CMP_IDENT_TIME_LEN - 1] = '\0'; - - /* Copy hostname */ - strncpy(cmp->ident.hostname, csp_get_hostname(), CSP_HOSTNAME_LEN); - cmp->ident.hostname[CSP_HOSTNAME_LEN - 1] = '\0'; - - /* Copy model name */ - strncpy(cmp->ident.model, csp_get_model(), CSP_MODEL_LEN); - cmp->ident.model[CSP_MODEL_LEN - 1] = '\0'; - - return CSP_ERR_NONE; - -} - -static int do_cmp_route_set(struct csp_cmp_message *cmp) { - - csp_iface_t *ifc = csp_iflist_get_by_name(cmp->route_set.interface); - if (ifc == NULL) - return CSP_ERR_INVAL; - - if (csp_route_set(cmp->route_set.dest_node, ifc, cmp->route_set.next_hop_mac) != CSP_ERR_NONE) - return CSP_ERR_INVAL; - - return CSP_ERR_NONE; - -} - -static int do_cmp_if_stats(struct csp_cmp_message *cmp) { - - csp_iface_t *ifc = csp_iflist_get_by_name(cmp->if_stats.interface); - if (ifc == NULL) - return CSP_ERR_INVAL; - - cmp->if_stats.tx = csp_hton32(ifc->tx); - cmp->if_stats.rx = csp_hton32(ifc->rx); - cmp->if_stats.tx_error = csp_hton32(ifc->tx_error); - cmp->if_stats.rx_error = csp_hton32(ifc->rx_error); - cmp->if_stats.drop = csp_hton32(ifc->drop); - cmp->if_stats.autherr = csp_hton32(ifc->autherr); - cmp->if_stats.frame = csp_hton32(ifc->frame); - cmp->if_stats.txbytes = csp_hton32(ifc->txbytes); - cmp->if_stats.rxbytes = csp_hton32(ifc->rxbytes); - cmp->if_stats.irq = csp_hton32(ifc->irq); - - return CSP_ERR_NONE; -} - -static int do_cmp_peek(struct csp_cmp_message *cmp) { - - cmp->peek.addr = csp_hton32(cmp->peek.addr); - if (cmp->peek.len > CSP_CMP_PEEK_MAX_LEN) - return CSP_ERR_INVAL; - - /* Dangerous, you better know what you are doing */ - csp_cmp_memcpy_fnc((csp_memptr_t) (uintptr_t) cmp->peek.data, (csp_memptr_t) (unsigned long) cmp->peek.addr, cmp->peek.len); - - return CSP_ERR_NONE; - -} - -static int do_cmp_poke(struct csp_cmp_message *cmp) { - - cmp->poke.addr = csp_hton32(cmp->poke.addr); - if (cmp->poke.len > CSP_CMP_POKE_MAX_LEN) - return CSP_ERR_INVAL; - - /* Extremely dangerous, you better know what you are doing */ - csp_cmp_memcpy_fnc((csp_memptr_t) (unsigned long) cmp->poke.addr, (csp_memptr_t) (uintptr_t) cmp->poke.data, cmp->poke.len); - - return CSP_ERR_NONE; - -} - -static int do_cmp_clock(struct csp_cmp_message *cmp) { - - cmp->clock.tv_sec = csp_ntoh32(cmp->clock.tv_sec); - cmp->clock.tv_nsec = csp_ntoh32(cmp->clock.tv_nsec); - - if ((cmp->clock.tv_sec != 0) && (clock_set_time != NULL)) { - clock_set_time(&cmp->clock); - } - - if (clock_get_time != NULL) { - clock_get_time(&cmp->clock); - } - - cmp->clock.tv_sec = csp_hton32(cmp->clock.tv_sec); - cmp->clock.tv_nsec = csp_hton32(cmp->clock.tv_nsec); - return CSP_ERR_NONE; - -} - -/* CSP Management Protocol handler */ -static int csp_cmp_handler(csp_conn_t * conn, csp_packet_t * packet) { - - int ret = CSP_ERR_INVAL; - struct csp_cmp_message * cmp = (struct csp_cmp_message *) packet->data; - - /* Ignore everything but requests */ - if (cmp->type != CSP_CMP_REQUEST) - return ret; - - switch (cmp->code) { - case CSP_CMP_IDENT: - ret = do_cmp_ident(cmp); - packet->length = CMP_SIZE(ident); - break; - - case CSP_CMP_ROUTE_SET: - ret = do_cmp_route_set(cmp); - packet->length = CMP_SIZE(route_set); - break; - - case CSP_CMP_IF_STATS: - ret = do_cmp_if_stats(cmp); - packet->length = CMP_SIZE(if_stats); - break; - - case CSP_CMP_PEEK: - ret = do_cmp_peek(cmp); - break; - - case CSP_CMP_POKE: - ret = do_cmp_poke(cmp); - break; - - case CSP_CMP_CLOCK: - ret = do_cmp_clock(cmp); - break; - - default: - ret = CSP_ERR_INVAL; - break; - } - - cmp->type = CSP_CMP_REPLY; - - return ret; -} - -void csp_service_handler(csp_conn_t * conn, csp_packet_t * packet) { - - switch (csp_conn_dport(conn)) { - - case CSP_CMP: - /* Pass to CMP handler */ - if (csp_cmp_handler(conn, packet) != CSP_ERR_NONE) { - csp_buffer_free(packet); - return; - } - break; - - case CSP_PING: - /* A ping means, just echo the packet, so no changes */ - csp_log_info("SERVICE: Ping received"); - break; - - case CSP_PS: { - /* Sanity check on request */ - if ((packet->length != 1) || (packet->data[0] != 0x55)) { - /* Sanity check failed */ - csp_buffer_free(packet); - /* Clear the packet, it has been freed */ - packet = NULL; - break; - } - /* Start by allocating just the right amount of memory */ - int task_list_size = csp_sys_tasklist_size(); - char * pslist = csp_malloc(task_list_size); - /* Check for malloc fail */ - if (pslist == NULL) { - /* Send out the data */ - strcpy((char *)packet->data, "Not enough memory"); - packet->length = strlen((char *)packet->data); - /* Break and let the default handling send packet */ - break; - } - - /* Retrieve the tasklist */ - csp_sys_tasklist(pslist); - int pslen = strnlen(pslist, task_list_size); - - /* Split the potentially very long string into packets */ - int i = 0; - while(i < pslen) { - - /* Allocate packet buffer, if need be */ - if (packet == NULL) - packet = csp_buffer_get(CSP_RPS_MTU); - if (packet == NULL) - break; - - /* Calculate length, either full MTU or the remainder */ - packet->length = (pslen - i > CSP_RPS_MTU) ? CSP_RPS_MTU : (pslen - i); - - /* Send out the data */ - memcpy(packet->data, &pslist[i], packet->length); - i += packet->length; - if (!csp_send(conn, packet, 0)) - csp_buffer_free(packet); - - /* Clear the packet reference when sent */ - packet = NULL; - - } - csp_free(pslist); - break; - } - - case CSP_MEMFREE: { - uint32_t total = csp_sys_memfree(); - - total = csp_hton32(total); - memcpy(packet->data, &total, sizeof(total)); - packet->length = sizeof(total); - - break; - } - - case CSP_REBOOT: { - uint32_t magic_word; - memcpy(&magic_word, packet->data, sizeof(magic_word)); - - magic_word = csp_ntoh32(magic_word); - - /* If the magic word is valid, reboot */ - if (magic_word == CSP_REBOOT_MAGIC) { - csp_sys_reboot(); - } else if (magic_word == CSP_REBOOT_SHUTDOWN_MAGIC) { - csp_sys_shutdown(); - } - - - - csp_buffer_free(packet); - return; - } - - case CSP_BUF_FREE: { - uint32_t size = csp_buffer_remaining(); - size = csp_hton32(size); - memcpy(packet->data, &size, sizeof(size)); - packet->length = sizeof(size); - break; - } - - case CSP_UPTIME: { - uint32_t time = csp_get_s(); - time = csp_hton32(time); - memcpy(packet->data, &time, sizeof(time)); - packet->length = sizeof(time); - break; - } - - default: - csp_buffer_free(packet); - return; - } - - if (packet != NULL) { - if (!csp_send(conn, packet, 0)) - csp_buffer_free(packet); - } - -} diff --git a/libcsp/src/csp_services.c b/libcsp/src/csp_services.c deleted file mode 100644 index 5392cb82..00000000 --- a/libcsp/src/csp_services.c +++ /dev/null @@ -1,233 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include -#include -#include -#include - -/* CSP includes */ -#include -#include -#include - -#include - -int csp_ping(uint8_t node, uint32_t timeout, unsigned int size, uint8_t conn_options) { - - unsigned int i; - uint32_t start, time, status = 0; - - /* Counter */ - start = csp_get_ms(); - - /* Open connection */ - csp_conn_t * conn = csp_connect(CSP_PRIO_NORM, node, CSP_PING, timeout, conn_options); - if (conn == NULL) - return -1; - - /* Prepare data */ - csp_packet_t * packet; - packet = csp_buffer_get(size); - if (packet == NULL) - goto out; - - /* Set data to increasing numbers */ - packet->length = size; - for (i = 0; i < size; i++) - packet->data[i] = i; - - /* Try to send frame */ - if (!csp_send(conn, packet, 0)) - goto out; - - /* Read incoming frame */ - packet = csp_read(conn, timeout); - if (packet == NULL) - goto out; - - /* Ensure that the data was actually echoed */ - for (i = 0; i < size; i++) - if (packet->data[i] != i % (0xff + 1)) - goto out; - - status = 1; - -out: - /* Clean up */ - if (packet != NULL) - csp_buffer_free(packet); - csp_close(conn); - - /* We have a reply */ - time = (csp_get_ms() - start); - - if (status) { - return time; - } else { - return -1; - } - -} - -void csp_ping_noreply(uint8_t node) { - - /* Prepare data */ - csp_packet_t * packet; - packet = csp_buffer_get(1); - - /* Check malloc */ - if (packet == NULL) - return; - - /* Open connection */ - csp_conn_t * conn = csp_connect(CSP_PRIO_NORM, node, CSP_PING, 0, 0); - if (conn == NULL) { - csp_buffer_free(packet); - return; - } - - packet->data[0] = 0x55; - packet->length = 1; - - printf("Ping ignore reply node %u.\r\n", (unsigned int) node); - - /* Try to send frame */ - if (!csp_send(conn, packet, 0)) - csp_buffer_free(packet); - - csp_close(conn); - -} - -void csp_reboot(uint8_t node) { - uint32_t magic_word = csp_hton32(CSP_REBOOT_MAGIC); - csp_transaction(CSP_PRIO_NORM, node, CSP_REBOOT, 0, &magic_word, sizeof(magic_word), NULL, 0); -} - -void csp_shutdown(uint8_t node) { - uint32_t magic_word = csp_hton32(CSP_REBOOT_SHUTDOWN_MAGIC); - csp_transaction(CSP_PRIO_NORM, node, CSP_REBOOT, 0, &magic_word, sizeof(magic_word), NULL, 0); -} - -void csp_ps(uint8_t node, uint32_t timeout) { - - /* Open connection */ - csp_conn_t * conn = csp_connect(CSP_PRIO_NORM, node, CSP_PS, 0, 0); - if (conn == NULL) - return; - - /* Prepare data */ - csp_packet_t * packet; - packet = csp_buffer_get(95); - - /* Check malloc */ - if (packet == NULL) - goto out; - - packet->data[0] = 0x55; - packet->length = 1; - - printf("PS node %u: \r\n", (unsigned int) node); - - /* Try to send frame */ - if (!csp_send(conn, packet, 0)) - goto out; - - while(1) { - - /* Read incoming frame */ - packet = csp_read(conn, timeout); - if (packet == NULL) - break; - - /* We have a reply, add our own NULL char */ - packet->data[packet->length] = 0; - printf("%s", packet->data); - - /* Each packet from csp_read must to be freed by user */ - csp_buffer_free(packet); - } - - printf("\r\n"); - - /* Clean up */ -out: - if (packet != NULL) - csp_buffer_free(packet); - csp_close(conn); - -} - -void csp_memfree(uint8_t node, uint32_t timeout) { - - uint32_t memfree; - - int status = csp_transaction(CSP_PRIO_NORM, node, CSP_MEMFREE, timeout, NULL, 0, &memfree, sizeof(memfree)); - if (status == 0) { - printf("Network error\r\n"); - return; - } - - /* Convert from network to host order */ - memfree = csp_ntoh32(memfree); - - printf("Free Memory at node %u is %"PRIu32" bytes\r\n", (unsigned int) node, memfree); - -} - -void csp_buf_free(uint8_t node, uint32_t timeout) { - - uint32_t size = 0; - - int status = csp_transaction(CSP_PRIO_NORM, node, CSP_BUF_FREE, timeout, NULL, 0, &size, sizeof(size)); - if (status == 0) { - printf("Network error\r\n"); - return; - } - size = csp_ntoh32(size); - printf("Free buffers at node %u is %"PRIu32"\r\n", (unsigned int) node, size); - -} - -void csp_uptime(uint8_t node, uint32_t timeout) { - - uint32_t uptime = 0; - - int status = csp_transaction(CSP_PRIO_NORM, node, CSP_UPTIME, timeout, NULL, 0, &uptime, sizeof(uptime)); - if (status == 0) { - printf("Network error\r\n"); - return; - } - uptime = csp_ntoh32(uptime); - printf("Uptime of node %u is %"PRIu32" s\r\n", (unsigned int) node, uptime); - -} - -int csp_cmp(uint8_t node, uint32_t timeout, uint8_t code, int membsize, struct csp_cmp_message * msg) { - msg->type = CSP_CMP_REQUEST; - msg->code = code; - int status = csp_transaction(CSP_PRIO_NORM, node, CSP_CMP, timeout, msg, membsize, msg, membsize); - if (status == 0) - return CSP_ERR_TIMEDOUT; - - return CSP_ERR_NONE; -} - diff --git a/libcsp/src/csp_sfp.c b/libcsp/src/csp_sfp.c deleted file mode 100644 index 96ef36e1..00000000 --- a/libcsp/src/csp_sfp.c +++ /dev/null @@ -1,170 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include -#include -#include -#include -#include -#include "csp_conn.h" - -typedef struct __attribute__((__packed__)) { - uint32_t offset; - uint32_t totalsize; -} sfp_header_t; - -/** - * SFP Headers: - * The following functions are helper functions that handles the extra SFP - * information that needs to be appended to all data packets. - */ -static sfp_header_t * csp_sfp_header_add(csp_packet_t * packet) { - sfp_header_t * header = (sfp_header_t *) &packet->data[packet->length]; - packet->length += sizeof(sfp_header_t); - memset(header, 0, sizeof(sfp_header_t)); - return header; -} - -static sfp_header_t * csp_sfp_header_remove(csp_packet_t * packet) { - sfp_header_t * header = (sfp_header_t *) &packet->data[packet->length-sizeof(sfp_header_t)]; - packet->length -= sizeof(sfp_header_t); - return header; -} - -int csp_sfp_send_own_memcpy(csp_conn_t * conn, const void * data, int totalsize, int mtu, uint32_t timeout, void * (*memcpyfcn)(void *, const void *, size_t)) { - - int count = 0; - while(count < totalsize) { - - /* Allocate packet */ - csp_packet_t * packet = csp_buffer_get(mtu); - if (packet == NULL) - return -1; - - /* Calculate sending size */ - int size = totalsize - count; - if (size > mtu) - size = mtu; - - /* Print debug */ - csp_debug(CSP_PROTOCOL, "Sending SFP at %x size %u", data + count, size); - - /* Copy data */ - (*memcpyfcn)(packet->data, data + count, size); - packet->length = size; - - /* Set fragment flag */ - conn->idout.flags |= CSP_FFRAG; - - /* Add SFP header */ - sfp_header_t * sfp_header = csp_sfp_header_add(packet); - sfp_header->totalsize = csp_hton32(totalsize); - sfp_header->offset = csp_hton32(count); - - /* Send data */ - if (!csp_send(conn, packet, timeout)) { - csp_buffer_free(packet); - return -1; - } - - /* Increment count */ - count += size; - - } - - return 0; - -} - -int csp_sfp_send(csp_conn_t * conn, const void * data, int totalsize, int mtu, uint32_t timeout) { - return csp_sfp_send_own_memcpy(conn, data, totalsize, mtu, timeout, &memcpy); -} - -int csp_sfp_recv_fp(csp_conn_t * conn, void ** dataout, int * datasize, uint32_t timeout, csp_packet_t * first_packet) { - - unsigned int last_byte = 0; - - *dataout = NULL; /* Allow caller to assume csp_free() can always be called when dataout is non-NULL */ - - /* Get first packet from user, or from connection */ - csp_packet_t * packet = NULL; - if (first_packet == NULL) { - packet = csp_read(conn, timeout); - if (packet == NULL) - return -1; - } else { - packet = first_packet; - } - - do { - - /* Check that SFP header is present */ - if ((packet->id.flags & CSP_FFRAG) == 0) { - csp_debug(CSP_ERROR, "Missing SFP header"); - csp_buffer_free(packet); - return -1; - } - - /* Read SFP header */ - sfp_header_t * sfp_header = csp_sfp_header_remove(packet); - sfp_header->offset = csp_ntoh32(sfp_header->offset); - sfp_header->totalsize = csp_ntoh32(sfp_header->totalsize); - - csp_debug(CSP_PROTOCOL, "SFP fragment %u/%u", sfp_header->offset + packet->length, sfp_header->totalsize); - - if (sfp_header->offset > last_byte + 1) { - csp_debug(CSP_ERROR, "SFP missing %u bytes", sfp_header->offset - last_byte); - csp_buffer_free(packet); - return -1; - } else { - last_byte = sfp_header->offset + packet->length; - } - - /* Allocate memory */ - if (*dataout == NULL) - *dataout = csp_malloc(sfp_header->totalsize); - if (*dataout == NULL) { - csp_debug(CSP_ERROR, "No dyn-memory for SFP fragment"); - csp_buffer_free(packet); - return -1; - } - - /* Copy data to output */ - *datasize = sfp_header->totalsize; - memcpy(*dataout + sfp_header->offset, packet->data, packet->length); - - if (sfp_header->offset + packet->length >= sfp_header->totalsize) { - csp_debug(CSP_PROTOCOL, "SFP complete"); - csp_buffer_free(packet); - return 0; - } else { - csp_buffer_free(packet); - } - - } while((packet = csp_read(conn, timeout)) != NULL); - - return -1; - -} - -int csp_sfp_recv(csp_conn_t * conn, void ** dataout, int * datasize, uint32_t timeout) { - return csp_sfp_recv_fp(conn, dataout, datasize, timeout, NULL); -} - diff --git a/libcsp/src/drivers/CMakeLists.txt b/libcsp/src/drivers/CMakeLists.txt deleted file mode 100644 index e2dd440b..00000000 --- a/libcsp/src/drivers/CMakeLists.txt +++ /dev/null @@ -1 +0,0 @@ -add_subdirectory(can) diff --git a/libcsp/src/drivers/can/CMakeLists.txt b/libcsp/src/drivers/can/CMakeLists.txt deleted file mode 100644 index d291fccc..00000000 --- a/libcsp/src/drivers/can/CMakeLists.txt +++ /dev/null @@ -1,3 +0,0 @@ -target_sources(${LIB_CSP_NAME} PRIVATE - can_socketcan.c -) diff --git a/libcsp/src/drivers/can/can_socketcan.c b/libcsp/src/drivers/can/can_socketcan.c deleted file mode 100644 index 94c6bdde..00000000 --- a/libcsp/src/drivers/can/can_socketcan.c +++ /dev/null @@ -1,201 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -/* SocketCAN driver */ -#include - -#include -#include - -#include -#include -#include -#include -#include - -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include - -#include -#include -#include - -#include -#include - -#ifdef CSP_HAVE_LIBSOCKETCAN -#include -#endif - -static struct can_socketcan_s { - int socket; - csp_iface_t interface; -} socketcan[1] = { - { - .interface = { - .name = "CAN", - .nexthop = csp_can_tx, - .mtu = CSP_CAN_MTU, - .driver = &socketcan[0], - }, - }, -}; - -static void * socketcan_rx_thread(void * parameters) -{ - struct can_frame frame; - int nbytes; - - while (1) { - /* Read CAN frame */ - nbytes = read(socketcan[0].socket, &frame, sizeof(frame)); - if (nbytes < 0) { - csp_log_error("read: %s", strerror(errno)); - continue; - } - - if (nbytes != sizeof(frame)) { - csp_log_warn("Read incomplete CAN frame"); - continue; - } - - /* Frame type */ - if (frame.can_id & (CAN_ERR_FLAG | CAN_RTR_FLAG) || !(frame.can_id & CAN_EFF_FLAG)) { - /* Drop error and remote frames */ - csp_log_warn("Discarding ERR/RTR/SFF frame"); - continue; - } - - /* Strip flags */ - frame.can_id &= CAN_EFF_MASK; - - /* Call RX callbacsp_can_rx_frameck */ - csp_can_rx(&socketcan[0].interface, frame.can_id, frame.data, frame.can_dlc, NULL); - } - - /* We should never reach this point */ - pthread_exit(NULL); -} - - -int csp_can_tx_frame(csp_iface_t *interface, uint32_t id, const uint8_t * data, uint8_t dlc) -{ - struct can_frame frame; - int i, tries = 0; - memset(&frame, 0, sizeof(frame)); - if (dlc > 8) - return -1; - - /* Copy identifier */ - frame.can_id = id | CAN_EFF_FLAG; - - /* Copy data to frame */ - for (i = 0; i < dlc; i++) - frame.data[i] = data[i]; - - /* Set DLC */ - frame.can_dlc = dlc; - - /* Send frame */ - while (write(socketcan[0].socket, &frame, sizeof(frame)) != sizeof(frame)) { - if (++tries < 1000 && errno == ENOBUFS) { - /* Wait 10 ms and try again */ - usleep(10000); - } else { - csp_log_error("write: %s", strerror(errno)); - break; - } - } - - return 0; -} - -csp_iface_t * csp_can_socketcan_init(const char * ifc, int bitrate, int promisc) -{ - struct ifreq ifr; - struct sockaddr_can addr; - pthread_t rx_thread; - - printf("-I-: Initiating CAN interface %s\n", ifc); - -#ifdef CSP_HAVE_LIBSOCKETCAN - /* Set interface up */ - if (bitrate > 0) { - can_do_stop(ifc); - can_set_bitrate(ifc, bitrate); - can_set_restart_ms(ifc, 100); - can_do_start(ifc); - } -#endif - - /* Create socket */ - if ((socketcan[0].socket = socket(PF_CAN, SOCK_RAW, CAN_RAW)) < 0) { - csp_log_error("socket: %s", strerror(errno)); - return NULL; - } - - /* Locate interface */ - strncpy(ifr.ifr_name, ifc, IFNAMSIZ - 1); - if (ioctl(socketcan[0].socket, SIOCGIFINDEX, &ifr) < 0) { - csp_log_error("ioctl: %s", strerror(errno)); - return NULL; - } - memset(&addr, 0, sizeof(addr)); - /* Bind the socket to CAN interface */ - addr.can_family = AF_CAN; - addr.can_ifindex = ifr.ifr_ifindex; - if (bind(socketcan[0].socket, (struct sockaddr *)&addr, sizeof(addr)) < 0) { - csp_log_error("bind: %s", strerror(errno)); - return NULL; - } - - /* Set filter mode */ - if (promisc == 0) { - - struct can_filter filter; - filter.can_id = CFP_MAKE_DST(csp_get_address()); - filter.can_mask = CFP_MAKE_DST((1 << CFP_HOST_SIZE) - 1); - - if (setsockopt(socketcan[0].socket, SOL_CAN_RAW, CAN_RAW_FILTER, &filter, sizeof(filter)) < 0) { - csp_log_error("setsockopt: %s", strerror(errno)); - return NULL; - } - - } - - /* Create receive thread */ - if (pthread_create(&rx_thread, NULL, socketcan_rx_thread, NULL) != 0) { - csp_log_error("pthread_create: %s", strerror(errno)); - return NULL; - } - - csp_iflist_add(&socketcan[0].interface); - - return &socketcan[0].interface; -} diff --git a/libcsp/src/drivers/usart/usart_linux.c b/libcsp/src/drivers/usart/usart_linux.c deleted file mode 100644 index c4ceeb27..00000000 --- a/libcsp/src/drivers/usart/usart_linux.c +++ /dev/null @@ -1,254 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include -#include - -int fd; -usart_callback_t usart_callback = NULL; - -static void *serial_rx_thread(void *vptr_args); - -int getbaud(int ifd) { - struct termios termAttr; - int inputSpeed = -1; - speed_t baudRate; - tcgetattr(ifd, &termAttr); - /* Get the input speed. */ - baudRate = cfgetispeed(&termAttr); - switch (baudRate) { - case B0: - inputSpeed = 0; - break; - case B50: - inputSpeed = 50; - break; - case B110: - inputSpeed = 110; - break; - case B134: - inputSpeed = 134; - break; - case B150: - inputSpeed = 150; - break; - case B200: - inputSpeed = 200; - break; - case B300: - inputSpeed = 300; - break; - case B600: - inputSpeed = 600; - break; - case B1200: - inputSpeed = 1200; - break; - case B1800: - inputSpeed = 1800; - break; - case B2400: - inputSpeed = 2400; - break; - case B4800: - inputSpeed = 4800; - break; - case B9600: - inputSpeed = 9600; - break; - case B19200: - inputSpeed = 19200; - break; - case B38400: - inputSpeed = 38400; - break; - case B57600: - inputSpeed = 57600; - break; - case B115200: - inputSpeed = 115200; - break; - case B230400: - inputSpeed = 230400; - break; -#ifndef CSP_MACOSX - case B460800: - inputSpeed = 460800; - break; - case B500000: - inputSpeed = 500000; - break; - case B576000: - inputSpeed = 576000; - break; - case B921600: - inputSpeed = 921600; - break; - case B1000000: - inputSpeed = 1000000; - break; - case B1152000: - inputSpeed = 1152000; - break; - case B1500000: - inputSpeed = 1500000; - break; - case B2000000: - inputSpeed = 2000000; - break; - case B2500000: - inputSpeed = 2500000; - break; - case B3000000: - inputSpeed = 3000000; - break; - case B3500000: - inputSpeed = 3500000; - break; - case B4000000: - inputSpeed = 4000000; - break; -#endif - } - - return inputSpeed; - -} - -void usart_init(struct usart_conf * conf) { - - struct termios options; - pthread_t rx_thread; - - fd = open(conf->device, O_RDWR | O_NOCTTY | O_NONBLOCK); - - if (fd < 0) { - printf("Failed to open %s: %s\r\n", conf->device, strerror(errno)); - return; - } - - int brate = 0; - switch(conf->baudrate) { - case 4800: brate=B4800; break; - case 9600: brate=B9600; break; - case 19200: brate=B19200; break; - case 38400: brate=B38400; break; - case 57600: brate=B57600; break; - case 115200: brate=B115200; break; - case 230400: brate=B230400; break; -#ifndef CSP_MACOSX - case 460800: brate=B460800; break; - case 500000: brate=B500000; break; - case 576000: brate=B576000; break; - case 921600: brate=B921600; break; - case 1000000: brate=B1000000; break; - case 1152000: brate=B1152000; break; - case 1500000: brate=B1500000; break; - case 2000000: brate=B2000000; break; - case 2500000: brate=B2500000; break; - case 3000000: brate=B3000000; break; - case 3500000: brate=B3500000; break; - case 4000000: brate=B4000000; break; -#endif - default: - printf("Unsupported baudrate requested, defaulting to 500000, requested baudrate=%u\n", conf->baudrate); - brate=B500000; - break; - } - - tcgetattr(fd, &options); - cfsetispeed(&options, brate); - cfsetospeed(&options, brate); - options.c_cflag |= (CLOCAL | CREAD); - options.c_cflag &= ~PARENB; - options.c_cflag &= ~CSTOPB; - options.c_cflag &= ~CSIZE; - options.c_cflag |= CS8; - options.c_lflag &= ~(ECHO | ECHONL | ICANON | IEXTEN | ISIG); - options.c_iflag &= ~(IGNBRK | BRKINT | ICRNL | INLCR | PARMRK | INPCK | ISTRIP | IXON); - options.c_oflag &= ~(OCRNL | ONLCR | ONLRET | ONOCR | OFILL | OPOST); - options.c_cc[VTIME] = 0; - options.c_cc[VMIN] = 1; - tcsetattr(fd, TCSANOW, &options); - if (tcgetattr(fd, &options) == -1) - perror("error setting options"); - fcntl(fd, F_SETFL, 0); - - /* Flush old transmissions */ - if (tcflush(fd, TCIOFLUSH) == -1) - printf("Error flushing serial port - %s(%d).\n", strerror(errno), errno); - - if (pthread_create(&rx_thread, NULL, serial_rx_thread, NULL) != 0) - return; - -} - -void usart_set_callback(usart_callback_t callback) { - usart_callback = callback; -} - -void usart_insert(char c, void * pxTaskWoken) { - printf("%c", c); -} - -void usart_putstr(char * buf, int len) { - if (write(fd, buf, len) != len) - return; -} - -void usart_putc(char c) { - if (write(fd, &c, 1) != 1) - return; -} - -char usart_getc(void) { - char c; - if (read(fd, &c, 1) != 1) return 0; - return c; -} - -static void *serial_rx_thread(void *vptr_args) { - unsigned int length; - uint8_t * cbuf = malloc(100000); - - // Receive loop - while (1) { - length = read(fd, cbuf, 300); - if (length <= 0) { - perror("Error: "); - exit(1); - } - if (usart_callback) - usart_callback(cbuf, length, NULL); - } - return NULL; -} diff --git a/libcsp/src/drivers/usart/usart_windows.c b/libcsp/src/drivers/usart/usart_windows.c deleted file mode 100644 index 91ffe87d..00000000 --- a/libcsp/src/drivers/usart/usart_windows.c +++ /dev/null @@ -1,230 +0,0 @@ -#include -#include -#include - -#include -#include - -static HANDLE portHandle = INVALID_HANDLE_VALUE; -static HANDLE rxThread = INVALID_HANDLE_VALUE; -static CRITICAL_SECTION txSection; -static LONG isListening = 0; -static usart_callback_t usart_callback = NULL; - -static void prvSendData(char *buf, int bufsz); -static int prvTryOpenPort(const char* intf); -static int prvTryConfigurePort(const struct usart_conf*); -static int prvTrySetPortTimeouts(void); -static const char* prvParityToStr(BYTE paritySetting); - -#ifdef CSP_DEBUG -static void prvPrintError(void) { - char *messageBuffer = NULL; - DWORD errorCode = GetLastError(); - DWORD formatMessageRet; - formatMessageRet = FormatMessageA( - FORMAT_MESSAGE_ALLOCATE_BUFFER | - FORMAT_MESSAGE_FROM_SYSTEM, - NULL, - errorCode, - MAKELANGID(LANG_NEUTRAL, SUBLANG_DEFAULT), - (char*)&messageBuffer, - 0, - NULL); - - if( !formatMessageRet ) { - csp_log_error("FormatMessage error, code: %lu", GetLastError()); - return; - } - csp_log_error("%s", messageBuffer); - LocalFree(messageBuffer); -} -#endif - -#ifdef CSP_DEBUG -#define printError() prvPrintError() -#else -#define printError() do {} while(0) -#endif - -static int prvTryOpenPort(const char *intf) { - portHandle = CreateFileA( - intf, - GENERIC_READ|GENERIC_WRITE, - 0, - NULL, - OPEN_EXISTING, - 0, - NULL); - - if( portHandle == INVALID_HANDLE_VALUE ) { - DWORD errorCode = GetLastError(); - if( errorCode == ERROR_FILE_NOT_FOUND ) { - csp_log_error("Could not open serial port, because it didn't exist!"); - } - else - csp_log_error("Failure opening serial port! Code: %lu", errorCode); - return 1; - } - return 0; -} - -static int prvTryConfigurePort(const struct usart_conf * conf) { - DCB portSettings = {0}; - portSettings.DCBlength = sizeof(DCB); - if(!GetCommState(portHandle, &portSettings) ) { - csp_log_error("Could not get default settings for open COM port! Code: %lu", GetLastError()); - return -1; - } - portSettings.BaudRate = conf->baudrate; - portSettings.Parity = conf->paritysetting; - portSettings.StopBits = conf->stopbits; - portSettings.fParity = conf->checkparity; - portSettings.fBinary = TRUE; - portSettings.ByteSize = conf->databits; - if( !SetCommState(portHandle, &portSettings) ) { - csp_log_error("Error when setting COM port settings! Code:%lu", GetLastError()); - return 1; - } - - GetCommState(portHandle, &portSettings); - - csp_log_info("Port: %s, Baudrate: %lu, Data bits: %d, Stop bits: %d, Parity: %s", - conf->device, conf->baudrate, conf->databits, conf->stopbits, prvParityToStr(conf->paritysetting)); - return 0; -} - -static const char* prvParityToStr(BYTE paritySetting) { - static const char *parityStr[] = { - "None", - "Odd", - "Even", - "N/A" - }; - char const *resultStr = NULL; - - switch(paritySetting) { - case NOPARITY: - resultStr = parityStr[0]; - break; - case ODDPARITY: - resultStr = parityStr[1]; - break; - case EVENPARITY: - resultStr = parityStr[2]; - break; - default: - resultStr = parityStr[3]; - }; - return resultStr; -} - -static int prvTrySetPortTimeouts(void) { - COMMTIMEOUTS timeouts = {0}; - - if( !GetCommTimeouts(portHandle, &timeouts) ) { - csp_log_error("Error gettings current timeout settings"); - return 1; - } - - timeouts.ReadIntervalTimeout = 5; - timeouts.ReadTotalTimeoutMultiplier = 1; - timeouts.ReadTotalTimeoutConstant = 5; - timeouts.WriteTotalTimeoutMultiplier = 1; - timeouts.WriteTotalTimeoutConstant = 5; - - if(!SetCommTimeouts(portHandle, &timeouts)) { - csp_log_error("Error setting timeouts!"); - return 1; - } - - return 0; -} - -unsigned WINAPI prvRxTask(void* params) { - DWORD bytesRead; - DWORD eventStatus; - uint8_t recvBuffer[24]; - SetCommMask(portHandle, EV_RXCHAR); - - while(isListening) { - WaitCommEvent(portHandle, &eventStatus, NULL); - if( !(eventStatus & EV_RXCHAR) ) { - continue; - } - if( !ReadFile(portHandle, recvBuffer, 24, &bytesRead, NULL)) { - csp_log_warn("Error receiving data! Code: %lu", GetLastError()); - continue; - } - if( usart_callback != NULL ) - usart_callback(recvBuffer, (size_t)bytesRead, NULL); - } - return 0; -} - -static void prvSendData(char *buf, int bufsz) { - DWORD bytesTotal = 0; - DWORD bytesActual; - if( !WriteFile(portHandle, buf, bufsz-bytesTotal, &bytesActual, NULL) ) { - csp_log_error("Could not write data. Code: %lu", GetLastError()); - return; - } - if( !FlushFileBuffers(portHandle) ) { - csp_log_warn("Could not flush write buffer. Code: %lu", GetLastError()); - } -} - -void usart_shutdown(void) { - InterlockedExchange(&isListening, 0); - CloseHandle(portHandle); - portHandle = INVALID_HANDLE_VALUE; - if( rxThread != INVALID_HANDLE_VALUE ) { - WaitForSingleObject(rxThread, INFINITE); - rxThread = INVALID_HANDLE_VALUE; - } - DeleteCriticalSection(&txSection); -} - -void usart_listen(void) { - InterlockedExchange(&isListening, 1); - rxThread = (HANDLE)_beginthreadex(NULL, 0, &prvRxTask, NULL, 0, NULL); -} - -void usart_putstr(char* buf, int bufsz) { - EnterCriticalSection(&txSection); - prvSendData(buf, bufsz); - LeaveCriticalSection(&txSection); -} - -void usart_insert(char c, void *pxTaskWoken) { - /* redirect debug output to stdout */ - printf("%c", c); -} - -void usart_set_callback(usart_callback_t callback) { - usart_callback = callback; -} - -void usart_init(struct usart_conf * conf) { - if( prvTryOpenPort(conf->device) ) { - printError(); - return; - } - - if( prvTryConfigurePort(conf) ) { - printError(); - return; - } - - if( prvTrySetPortTimeouts() ) { - printError(); - return; - } - - InitializeCriticalSection(&txSection); - - /* Start receiver thread */ - usart_listen(); -} - - diff --git a/libcsp/src/interfaces/CMakeLists.txt b/libcsp/src/interfaces/CMakeLists.txt deleted file mode 100644 index 33f779e3..00000000 --- a/libcsp/src/interfaces/CMakeLists.txt +++ /dev/null @@ -1,7 +0,0 @@ -target_sources(${LIB_CSP_NAME} PRIVATE - csp_if_can_pbuf.c - csp_if_can.c - csp_if_i2c.c - csp_if_kiss.c - csp_if_lo.c -) diff --git a/libcsp/src/interfaces/csp_if_can.c b/libcsp/src/interfaces/csp_if_can.c deleted file mode 100644 index 5add8334..00000000 --- a/libcsp/src/interfaces/csp_if_can.c +++ /dev/null @@ -1,279 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -/* CAN frames contains at most 8 bytes of data, so in order to transmit CSP - * packets larger than this, a fragmentation protocol is required. The CAN - * Fragmentation Protocol (CFP) header is designed to match the 29 bit CAN - * identifier. - * - * The CAN identifier is divided in these fields: - * src: 5 bits - * dst: 5 bits - * type: 1 bit - * remain: 8 bits - * identifier: 10 bits - * - * Source and Destination addresses must match the CSP packet. The type field - * is used to distinguish the first and subsequent frames in a fragmented CSP - * packet. Type is BEGIN (0) for the first fragment and MORE (1) for all other - * fragments. Remain indicates number of remaining fragments, and must be - * decremented by one for each fragment sent. The identifier field serves the - * same purpose as in the Internet Protocol, and should be an auto incrementing - * integer to uniquely separate sessions. - */ - -#include -#include -#include -#include -#include - -#include -#include -#include -#include - -#include -#include -#include -#include - -#include "csp_if_can_pbuf.h" - -/* CFP Frame Types */ -enum cfp_frame_t { - CFP_BEGIN = 0, - CFP_MORE = 1 -}; - -int csp_can_rx(csp_iface_t *interface, uint32_t id, const uint8_t *data, uint8_t dlc, CSP_BASE_TYPE *task_woken) -{ - csp_can_pbuf_element_t *buf; - uint8_t offset; - - /* Random packet loss */ -#if 0 - int random = rand(); - if (random < RAND_MAX * 0.00005) { - csp_log_warn("Dropping frame"); - return; - } -#endif - - /* Bind incoming frame to a packet buffer */ - buf = csp_can_pbuf_find(id, CFP_ID_CONN_MASK); - - /* Check returned buffer */ - if (buf == NULL) { - if (CFP_TYPE(id) == CFP_BEGIN) { - buf = csp_can_pbuf_new(id, task_woken); - if (buf == NULL) { - //csp_log_warn("No available packet buffer for CAN"); - interface->rx_error++; - return CSP_ERR_NOMEM; - } - } else { - //csp_log_warn("Out of order id 0x%X remain %u", CFP_ID(id), CFP_REMAIN(id)); - interface->frame++; - return CSP_ERR_INVAL; - } - } - - /* Reset frame data offset */ - offset = 0; - - switch (CFP_TYPE(id)) { - - case CFP_BEGIN: - - /* Discard packet if DLC is less than CSP id + CSP length fields */ - if (dlc < sizeof(csp_id_t) + sizeof(uint16_t)) { - //csp_log_warn("Short BEGIN frame received"); - interface->frame++; - csp_can_pbuf_free(buf, task_woken); - break; - } - - /* Check for incomplete frame */ - if (buf->packet != NULL) { - /* Reuse the buffer */ - //csp_log_warn("Incomplete frame"); - interface->frame++; - } else { - /* Allocate memory for frame */ - if (task_woken == NULL) { - buf->packet = csp_buffer_get(interface->mtu); - } else { - buf->packet = csp_buffer_get_isr(interface->mtu); - } - if (buf->packet == NULL) { - //csp_log_error("Failed to get buffer for CSP_BEGIN packet"); - interface->frame++; - csp_can_pbuf_free(buf, task_woken); - break; - } - } - - /* Copy CSP identifier and length*/ - memcpy(&(buf->packet->id), data, sizeof(csp_id_t)); - buf->packet->id.ext = csp_ntoh32(buf->packet->id.ext); - memcpy(&(buf->packet->length), data + sizeof(csp_id_t), sizeof(uint16_t)); - buf->packet->length = csp_ntoh16(buf->packet->length); - - /* Reset RX count */ - buf->rx_count = 0; - - /* Set offset to prevent CSP header from being copied to CSP data */ - offset = sizeof(csp_id_t) + sizeof(uint16_t); - - /* Set remain field - increment to include begin packet */ - buf->remain = CFP_REMAIN(id) + 1; - - /* FALLTHROUGH */ - - case CFP_MORE: - - /* Check 'remain' field match */ - if (CFP_REMAIN(id) != buf->remain - 1) { - //csp_log_error("CAN frame lost in CSP packet"); - csp_can_pbuf_free(buf, task_woken); - interface->frame++; - break; - } - - /* Decrement remaining frames */ - buf->remain--; - - /* Check for overflow */ - if ((buf->rx_count + dlc - offset) > buf->packet->length) { - //csp_log_error("RX buffer overflow"); - interface->frame++; - csp_can_pbuf_free(buf, task_woken); - break; - } - - /* Copy dlc bytes into buffer */ - memcpy(&buf->packet->data[buf->rx_count], data + offset, dlc - offset); - buf->rx_count += dlc - offset; - - /* Check if more data is expected */ - if (buf->rx_count != buf->packet->length) - break; - - /* Data is available */ - csp_qfifo_write(buf->packet, interface, task_woken); - - /* Drop packet buffer reference */ - buf->packet = NULL; - - /* Free packet buffer */ - csp_can_pbuf_free(buf, task_woken); - - break; - - default: - //csp_log_warn("Received unknown CFP message type"); - csp_can_pbuf_free(buf, task_woken); - break; - - } - - return CSP_ERR_NONE; -} - -int csp_can_tx(csp_iface_t *interface, csp_packet_t *packet, uint32_t timeout) -{ - - /* CFP Identification number */ - static volatile int csp_can_frame_id = 0; - - /* Get local copy of the static frameid */ - int ident = csp_can_frame_id++; - - uint16_t tx_count; - uint8_t bytes, overhead, avail, dest; - uint8_t frame_buf[8]; - - /* Calculate overhead */ - overhead = sizeof(csp_id_t) + sizeof(uint16_t); - - /* Insert destination node mac address into the CFP destination field */ - dest = csp_rtable_find_mac(packet->id.dst); - if (dest == CSP_NODE_MAC) - dest = packet->id.dst; - - /* Create CAN identifier */ - uint32_t id = 0; - id |= CFP_MAKE_SRC(packet->id.src); - id |= CFP_MAKE_DST(dest); - id |= CFP_MAKE_ID(ident); - id |= CFP_MAKE_TYPE(CFP_BEGIN); - id |= CFP_MAKE_REMAIN((packet->length + overhead - 1) / 8); - - /* Calculate first frame data bytes */ - avail = 8 - overhead; - bytes = (packet->length <= avail) ? packet->length : avail; - - /* Copy CSP headers and data */ - uint32_t csp_id_be = csp_hton32(packet->id.ext); - uint16_t csp_length_be = csp_hton16(packet->length); - - memcpy(frame_buf, &csp_id_be, sizeof(csp_id_be)); - memcpy(frame_buf + sizeof(csp_id_be), &csp_length_be, sizeof(csp_length_be)); - memcpy(frame_buf + overhead, packet->data, bytes); - - /* Increment tx counter */ - tx_count = bytes; - - /* Send first frame */ - if (csp_can_tx_frame(interface, id, frame_buf, overhead + bytes)) { - //csp_log_warn("Failed to send CAN frame in csp_tx_can"); - interface->tx_error++; - return CSP_ERR_DRIVER; - } - - /* Send next frames if not complete */ - while (tx_count < packet->length) { - /* Calculate frame data bytes */ - bytes = (packet->length - tx_count >= 8) ? 8 : packet->length - tx_count; - - /* Prepare identifier */ - id = 0; - id |= CFP_MAKE_SRC(packet->id.src); - id |= CFP_MAKE_DST(dest); - id |= CFP_MAKE_ID(ident); - id |= CFP_MAKE_TYPE(CFP_MORE); - id |= CFP_MAKE_REMAIN((packet->length - tx_count - bytes + 7) / 8); - - /* Increment tx counter */ - tx_count += bytes; - - /* Send frame */ - if (csp_can_tx_frame(interface, id, packet->data + tx_count - bytes, bytes)) { - //csp_log_warn("Failed to send CAN frame in Tx callback"); - interface->tx_error++; - return CSP_ERR_DRIVER; - } - } - - csp_buffer_free(packet); - - return CSP_ERR_NONE; -} diff --git a/libcsp/src/interfaces/csp_if_can_pbuf.c b/libcsp/src/interfaces/csp_if_can_pbuf.c deleted file mode 100644 index 65f18de9..00000000 --- a/libcsp/src/interfaces/csp_if_can_pbuf.c +++ /dev/null @@ -1,77 +0,0 @@ -/* - * csp_if_can_pbuf.c - * - * Created on: Feb 3, 2017 - * Author: johan - */ - -#include -#include "csp_if_can_pbuf.h" - -/* Number of packet buffer elements */ -#define PBUF_ELEMENTS CSP_CONN_MAX - -/* Buffer element timeout in ms */ -#define PBUF_TIMEOUT_MS 1000 - -static csp_can_pbuf_element_t csp_can_pbuf[PBUF_ELEMENTS] = {}; - -int csp_can_pbuf_free(csp_can_pbuf_element_t *buf, CSP_BASE_TYPE *task_woken) -{ - /* Free CSP packet */ - if (buf->packet != NULL) { - if (task_woken == NULL) { - csp_buffer_free(buf->packet); - } else { - csp_buffer_free_isr(buf->packet); - } - } - - /* Mark buffer element free */ - buf->packet = NULL; - buf->rx_count = 0; - buf->cfpid = 0; - buf->last_used = 0; - buf->remain = 0; - buf->state = BUF_FREE; - - return CSP_ERR_NONE; -} - -csp_can_pbuf_element_t *csp_can_pbuf_new(uint32_t id, CSP_BASE_TYPE *task_woken) -{ - uint32_t now = csp_get_ms(); - - for (int i = 0; i < PBUF_ELEMENTS; i++) { - - /* Perform cleanup in used pbufs */ - if (csp_can_pbuf[i].state == BUF_USED) { - if (now - csp_can_pbuf[i].last_used > PBUF_TIMEOUT_MS) - csp_can_pbuf_free(&csp_can_pbuf[i], task_woken); - } - - if (csp_can_pbuf[i].state == BUF_FREE) { - csp_can_pbuf[i].state = BUF_USED; - csp_can_pbuf[i].cfpid = id; - csp_can_pbuf[i].remain = 0; - csp_can_pbuf[i].last_used = now; - return &csp_can_pbuf[i]; - } - - } - - return NULL; - -} - -csp_can_pbuf_element_t *csp_can_pbuf_find(uint32_t id, uint32_t mask) -{ - for (int i = 0; i < PBUF_ELEMENTS; i++) { - if ((csp_can_pbuf[i].state == BUF_USED) && ((csp_can_pbuf[i].cfpid & mask) == (id & mask))) { - csp_can_pbuf[i].last_used = csp_get_ms(); - return &csp_can_pbuf[i]; - } - } - return NULL; -} - diff --git a/libcsp/src/interfaces/csp_if_can_pbuf.h b/libcsp/src/interfaces/csp_if_can_pbuf.h deleted file mode 100644 index 3e71c26c..00000000 --- a/libcsp/src/interfaces/csp_if_can_pbuf.h +++ /dev/null @@ -1,31 +0,0 @@ -/* - * csp_if_can_pbuf.h - * - * Created on: Feb 3, 2017 - * Author: johan - */ - -#ifndef LIB_CSP_SRC_INTERFACES_CSP_IF_CAN_PBUF_H_ -#define LIB_CSP_SRC_INTERFACES_CSP_IF_CAN_PBUF_H_ - -/* Packet buffers */ -typedef enum { - BUF_FREE = 0, /* Buffer element free */ - BUF_USED = 1, /* Buffer element used */ -} csp_can_pbuf_state_t; - -typedef struct { - uint16_t rx_count; /* Received bytes */ - uint32_t remain; /* Remaining packets */ - uint32_t cfpid; /* Connection CFP identification number */ - csp_packet_t *packet; /* Pointer to packet buffer */ - csp_can_pbuf_state_t state; /* Element state */ - uint32_t last_used; /* Timestamp in ms for last use of buffer */ -} csp_can_pbuf_element_t; - -int csp_can_pbuf_free(csp_can_pbuf_element_t *buf, CSP_BASE_TYPE *task_woken); -csp_can_pbuf_element_t *csp_can_pbuf_new(uint32_t id, CSP_BASE_TYPE *task_woken); -csp_can_pbuf_element_t *csp_can_pbuf_find(uint32_t id, uint32_t mask); -void csp_can_pbuf_cleanup(CSP_BASE_TYPE *task_woken); - -#endif /* LIB_CSP_SRC_INTERFACES_CSP_IF_CAN_PBUF_H_ */ diff --git a/libcsp/src/interfaces/csp_if_i2c.c b/libcsp/src/interfaces/csp_if_i2c.c deleted file mode 100644 index c5d105df..00000000 --- a/libcsp/src/interfaces/csp_if_i2c.c +++ /dev/null @@ -1,116 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include -#include - -#include -#include -#include -#include -#include -#include - -static int csp_i2c_handle = 0; - -int csp_i2c_tx(csp_iface_t * interface, csp_packet_t * packet, uint32_t timeout) { - - /* Cast the CSP packet buffer into an i2c frame */ - i2c_frame_t * frame = (i2c_frame_t *) packet; - - /* Insert destination node into the i2c destination field */ - if (csp_rtable_find_mac(packet->id.dst) == CSP_NODE_MAC) { - frame->dest = packet->id.dst; - } else { - frame->dest = csp_rtable_find_mac(packet->id.dst); - } - - /* Save the outgoing id in the buffer */ - packet->id.ext = csp_hton32(packet->id.ext); - - /* Add the CSP header to the I2C length field */ - frame->len += sizeof(packet->id); - frame->len_rx = 0; - - /* Some I2C drivers support X number of retries - * CSP don't care about this. If it doesn't work the first - * time, don'y use time on it. - */ - frame->retries = 0; - - /* enqueue the frame */ - if (i2c_send(csp_i2c_handle, frame, timeout) != E_NO_ERR) - return CSP_ERR_DRIVER; - - return CSP_ERR_NONE; - -} - -/** - * When a frame is received, cast it to a csp_packet - * and send it directly to the CSP new packet function. - * Context: ISR only - * @param frame - */ -void csp_i2c_rx(i2c_frame_t * frame, void * pxTaskWoken) { - - static csp_packet_t * packet; - - /* Validate input */ - if (frame == NULL) - return; - - if ((frame->len < 4) || (frame->len > I2C_MTU)) { - csp_if_i2c.frame++; - csp_buffer_free_isr(frame); - return; - } - - /* Strip the CSP header off the length field before converting to CSP packet */ - frame->len -= sizeof(csp_id_t); - - /* Convert the packet from network to host order */ - packet = (csp_packet_t *) frame; - packet->id.ext = csp_ntoh32(packet->id.ext); - - /* Receive the packet in CSP */ - csp_qfifo_write(packet, &csp_if_i2c, pxTaskWoken); - -} - -int csp_i2c_init(uint8_t addr, int handle, int speed) { - - /* Create i2c_handle */ - csp_i2c_handle = handle; - if (i2c_init(csp_i2c_handle, I2C_MASTER, addr, speed, 10, 10, csp_i2c_rx) != E_NO_ERR) - return CSP_ERR_DRIVER; - - /* Register interface */ - csp_iflist_add(&csp_if_i2c); - - return CSP_ERR_NONE; - -} - -/** Interface definition */ -csp_iface_t csp_if_i2c = { - .name = "I2C", - .nexthop = csp_i2c_tx, -}; diff --git a/libcsp/src/interfaces/csp_if_kiss.c b/libcsp/src/interfaces/csp_if_kiss.c deleted file mode 100644 index fe5707f6..00000000 --- a/libcsp/src/interfaces/csp_if_kiss.c +++ /dev/null @@ -1,260 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include - -#define KISS_MTU 256 - -#define FEND 0xC0 -#define FESC 0xDB -#define TFEND 0xDC -#define TFESC 0xDD - -#define TNC_DATA 0x00 -#define TNC_SET_HARDWARE 0x06 -#define TNC_RETURN 0xFF - -static int kiss_lock_init = 0; -static csp_bin_sem_handle_t kiss_lock; - -/* Send a CSP packet over the KISS RS232 protocol */ -static int csp_kiss_tx(csp_iface_t * interface, csp_packet_t * packet, uint32_t timeout) { - - if (interface == NULL || interface->driver == NULL) - return CSP_ERR_DRIVER; - - /* Add CRC32 checksum */ - csp_crc32_append(packet, false); - - /* Save the outgoing id in the buffer */ - packet->id.ext = csp_hton32(packet->id.ext); - packet->length += sizeof(packet->id.ext); - - /* Lock */ - csp_bin_sem_wait(&kiss_lock, 1000); - - /* Transmit data */ - csp_kiss_handle_t * driver = interface->driver; - driver->kiss_putc(FEND); - driver->kiss_putc(TNC_DATA); - for (unsigned int i = 0; i < packet->length; i++) { - if (((unsigned char *) &packet->id.ext)[i] == FEND) { - ((unsigned char *) &packet->id.ext)[i] = TFEND; - driver->kiss_putc(FESC); - } else if (((unsigned char *) &packet->id.ext)[i] == FESC) { - ((unsigned char *) &packet->id.ext)[i] = TFESC; - driver->kiss_putc(FESC); - } - driver->kiss_putc(((unsigned char *) &packet->id.ext)[i]); - } - driver->kiss_putc(FEND); - - /* Free data */ - csp_buffer_free(packet); - - /* Unlock */ - csp_bin_sem_post(&kiss_lock); - - return CSP_ERR_NONE; -} - -/** - * When a frame is received, decode the kiss-stuff - * and eventually send it directly to the CSP new packet function. - */ -void csp_kiss_rx(csp_iface_t * interface, uint8_t * buf, int len, void * pxTaskWoken) { - - /* Driver handle */ - csp_kiss_handle_t * driver = interface->driver; - - while (len--) { - - /* Input */ - unsigned char inputbyte = *buf++; - - /* If packet was too long */ - if (driver->rx_length > interface->mtu) { - //csp_log_warn("KISS RX overflow"); - interface->rx_error++; - driver->rx_mode = KISS_MODE_NOT_STARTED; - driver->rx_length = 0; - } - - switch (driver->rx_mode) { - - case KISS_MODE_NOT_STARTED: - - /* Send normal chars back to usart driver */ - if (inputbyte != FEND) { - if (driver->kiss_discard != NULL) - driver->kiss_discard(inputbyte, pxTaskWoken); - break; - } - - /* Try to allocate new buffer */ - if (driver->rx_packet == NULL) { - if (pxTaskWoken == NULL) { - driver->rx_packet = csp_buffer_get(interface->mtu); - } else { - driver->rx_packet = csp_buffer_get_isr(interface->mtu); - } - } - - /* If no more memory, skip frame */ - if (driver->rx_packet == NULL) { - driver->rx_mode = KISS_MODE_SKIP_FRAME; - break; - } - - /* Start transfer */ - driver->rx_length = 0; - driver->rx_mode = KISS_MODE_STARTED; - driver->rx_first = 1; - break; - - case KISS_MODE_STARTED: - - /* Escape char */ - if (inputbyte == FESC) { - driver->rx_mode = KISS_MODE_ESCAPED; - break; - } - - /* End Char */ - if (inputbyte == FEND) { - - /* Accept message */ - if (driver->rx_length > 0) { - - /* Check for valid length */ - if (driver->rx_length < CSP_HEADER_LENGTH + sizeof(uint32_t)) { - //csp_log_warn("KISS short frame skipped, len: %u", driver->rx_length); - interface->rx_error++; - driver->rx_mode = KISS_MODE_NOT_STARTED; - break; - } - - /* Count received frame */ - interface->frame++; - - /* The CSP packet length is without the header */ - driver->rx_packet->length = driver->rx_length - CSP_HEADER_LENGTH; - - /* Convert the packet from network to host order */ - driver->rx_packet->id.ext = csp_ntoh32(driver->rx_packet->id.ext); - - /* Validate CRC */ - if (csp_crc32_verify(driver->rx_packet, false) != CSP_ERR_NONE) { - //csp_log_warn("KISS invalid crc frame skipped, len: %u", driver->rx_packet->length); - interface->rx_error++; - driver->rx_mode = KISS_MODE_NOT_STARTED; - break; - } - - /* Send back into CSP, notice calling from task so last argument must be NULL! */ - csp_qfifo_write(driver->rx_packet, interface, pxTaskWoken); - driver->rx_packet = NULL; - driver->rx_mode = KISS_MODE_NOT_STARTED; - break; - - } - - /* Break after the end char */ - break; - } - - /* Skip the first char after FEND which is TNC_DATA (0x00) */ - if (driver->rx_first) { - driver->rx_first = 0; - break; - } - - /* Valid data char */ - ((char *) &driver->rx_packet->id.ext)[driver->rx_length++] = inputbyte; - - break; - - case KISS_MODE_ESCAPED: - - /* Escaped escape char */ - if (inputbyte == TFESC) - ((char *) &driver->rx_packet->id.ext)[driver->rx_length++] = FESC; - - /* Escaped fend char */ - if (inputbyte == TFEND) - ((char *) &driver->rx_packet->id.ext)[driver->rx_length++] = FEND; - - /* Go back to started mode */ - driver->rx_mode = KISS_MODE_STARTED; - break; - - case KISS_MODE_SKIP_FRAME: - - /* Just wait for end char */ - if (inputbyte == FEND) - driver->rx_mode = KISS_MODE_NOT_STARTED; - - break; - - } - - } - -} - -void csp_kiss_init(csp_iface_t * csp_iface, csp_kiss_handle_t * csp_kiss_handle, csp_kiss_putc_f kiss_putc_f, csp_kiss_discard_f kiss_discard_f, const char * name) { - - /* Init lock only once */ - if (kiss_lock_init == 0) { - csp_bin_sem_create(&kiss_lock); - kiss_lock_init = 1; - } - - /* Register device handle as member of interface */ - csp_iface->driver = csp_kiss_handle; - csp_kiss_handle->kiss_discard = kiss_discard_f; - csp_kiss_handle->kiss_putc = kiss_putc_f; - csp_kiss_handle->rx_packet = NULL; - csp_kiss_handle->rx_mode = KISS_MODE_NOT_STARTED; - - /* Set default MTU if not given */ - if (csp_iface->mtu == 0) { - csp_iface->mtu = KISS_MTU; - } - - /* Setup other mandatories */ - csp_iface->nexthop = csp_kiss_tx; - csp_iface->name = name; - - /* Regsiter interface */ - csp_iflist_add(csp_iface); - -} diff --git a/libcsp/src/interfaces/csp_if_lo.c b/libcsp/src/interfaces/csp_if_lo.c deleted file mode 100644 index f3e81b15..00000000 --- a/libcsp/src/interfaces/csp_if_lo.c +++ /dev/null @@ -1,61 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -/* CSP includes */ -#include -#include -#include -#include - -#include -#include - -#include "../csp_route.h" - -/** - * Loopback interface transmit function - * @param packet Packet to transmit - * @param timeout Timout in ms - * @return 1 if packet was successfully transmitted, 0 on error - */ -static int csp_lo_tx(csp_iface_t * interface, csp_packet_t * packet, uint32_t timeout) { - - /* Drop packet silently if not destined for us. This allows - * blackhole routing addresses by setting their nexthop to - * the loopback interface. - */ - if (packet->id.dst != csp_get_address()) { - /* Consume and drop packet */ - csp_buffer_free(packet); - return CSP_ERR_NONE; - } - - /* Send back into CSP, notice calling from task so last argument must be NULL! */ - csp_qfifo_write(packet, &csp_if_lo, NULL); - - return CSP_ERR_NONE; - -} - -/* Interface definition */ -csp_iface_t csp_if_lo = { - .name = "LOOP", - .nexthop = csp_lo_tx, -}; diff --git a/libcsp/src/rtable/CMakeLists.txt b/libcsp/src/rtable/CMakeLists.txt deleted file mode 100644 index 101f4fb9..00000000 --- a/libcsp/src/rtable/CMakeLists.txt +++ /dev/null @@ -1,3 +0,0 @@ -target_sources(${LIB_CSP_NAME} PRIVATE - csp_rtable_cidr.c -) diff --git a/libcsp/src/rtable/csp_rtable_cidr.c b/libcsp/src/rtable/csp_rtable_cidr.c deleted file mode 100644 index 5758dc3c..00000000 --- a/libcsp/src/rtable/csp_rtable_cidr.c +++ /dev/null @@ -1,233 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include -#include -#include -#include -#include -#include - -/* Local typedef for routing table */ -typedef struct __attribute__((__packed__)) csp_rtable_s { - uint8_t address; - uint8_t netmask; - uint8_t mac; - csp_iface_t * interface; - struct csp_rtable_s * next; -} csp_rtable_t; - -/* Routing entries are stored in a linked list*/ -static csp_rtable_t * rtable = NULL; - -static csp_rtable_t * csp_rtable_find(uint8_t addr, uint8_t netmask, uint8_t exact) { - - /* Remember best result */ - csp_rtable_t * best_result = NULL; - uint8_t best_result_mask = 0; - - /* Start search */ - csp_rtable_t * i = rtable; - while(i) { - - /* Look for exact match */ - if (i->address == addr && i->netmask == netmask) { - best_result = i; - break; - } - - /* Try a CIDR netmask match */ - if (!exact) { - uint8_t hostbits = (1 << (CSP_ID_HOST_SIZE - i->netmask)) - 1; - uint8_t netbits = ~hostbits; - //printf("Netbits %x Hostbits %x\r\n", netbits, hostbits); - - /* Match network addresses */ - uint8_t net_a = i->address & netbits; - uint8_t net_b = addr & netbits; - //printf("A: %hhx, B: %hhx\r\n", net_a, net_b); - - /* We have a match */ - if (net_a == net_b) { - if (i->netmask >= best_result_mask) { - //printf("Match best result %u %u\r\n", best_result_mask, i->netmask); - best_result = i; - best_result_mask = i->netmask; - } - } - - } - - i = i->next; - - } - -#if 0 - if (best_result) - csp_debug(CSP_PACKET, "Using routing entry: %u/%u dev %s m:%u\r\n", best_result->address, best_result->netmask, best_result->interface->name, best_result->mac); -#endif - - return best_result; - -} - -void csp_rtable_clear(void) { - for (csp_rtable_t * i = rtable; (i);) { - void * freeme = i; - i = i->next; - csp_free(freeme); - } - rtable = NULL; - - /* Set loopback up again */ - csp_rtable_set(csp_get_address(), CSP_ID_HOST_SIZE, &csp_if_lo, CSP_NODE_MAC); - -} - -static int csp_rtable_parse(const char * buffer, int dry_run) { - - int valid_entries = 0; - - /* Copy string before running strtok */ - char * str = alloca(strlen(buffer) + 1); - memcpy(str, buffer, strlen(buffer) + 1); - - /* Get first token */ - str = strtok(str, ","); - - while ((str) && (strlen(str) > 1)) { - int address = 0, netmask = 0, mac = 255; - char name[10] = {}; - if (sscanf(str, "%u/%u %s %u", &address, &netmask, name, &mac) != 4) { - if (sscanf(str, "%u/%u %s", &address, &netmask, name) != 3) { - csp_log_error("Parse error %s", str); - return -1; - } - } - //printf("Parsed %u/%u %u %s\r\n", address, netmask, mac, name); - csp_iface_t * ifc = csp_iflist_get_by_name(name); - if (ifc) { - if (dry_run == 0) - csp_rtable_set(address, netmask, ifc, mac); - } else { - csp_log_error("Unknown interface %s", name); - return -1; - } - valid_entries++; - str = strtok(NULL, ","); - } - - return valid_entries; -} - -void csp_rtable_load(const char * buffer) { - csp_rtable_parse(buffer, 0); -} - -int csp_rtable_check(const char * buffer) { - return csp_rtable_parse(buffer, 1); -} - -int csp_rtable_save(char * buffer, int maxlen) { - int len = 0; - for (csp_rtable_t * i = rtable; (i); i = i->next) { - if (i->mac != CSP_NODE_MAC) { - len += snprintf(buffer + len, maxlen - len, "%u/%u %s %u, ", i->address, i->netmask, i->interface->name, i->mac); - } else { - len += snprintf(buffer + len, maxlen - len, "%u/%u %s, ", i->address, i->netmask, i->interface->name); - } - } - return len; -} - -csp_iface_t * csp_rtable_find_iface(uint8_t id) { - csp_rtable_t * entry = csp_rtable_find(id, CSP_ID_HOST_SIZE, 0); - if (entry == NULL) - return NULL; - return entry->interface; -} - -uint8_t csp_rtable_find_mac(uint8_t id) { - csp_rtable_t * entry = csp_rtable_find(id, CSP_ID_HOST_SIZE, 0); - if (entry == NULL) - return 255; - return entry->mac; -} - -int csp_rtable_set(uint8_t _address, uint8_t _netmask, csp_iface_t *ifc, uint8_t mac) { - - if (ifc == NULL) - return CSP_ERR_INVAL; - - /* Set default route in the old way */ - int address, netmask; - if (_address == CSP_DEFAULT_ROUTE) { - netmask = 0; - address = 0; - } else { - netmask = _netmask; - address = _address; - } - - /* Fist see if the entry exists */ - csp_rtable_t * entry = csp_rtable_find(address, netmask, 1); - - /* If not, create a new one */ - if (!entry) { - entry = csp_malloc(sizeof(csp_rtable_t)); - if (entry == NULL) - return CSP_ERR_NOMEM; - - entry->next = NULL; - /* Add entry to linked-list */ - if (rtable == NULL) { - /* This is the first interface to be added */ - rtable = entry; - } else { - /* One or more interfaces were already added */ - csp_rtable_t * i = rtable; - while (i->next) - i = i->next; - i->next = entry; - } - } - - /* Fill in the data */ - entry->address = address; - entry->netmask = netmask; - entry->interface = ifc; - entry->mac = mac; - - return CSP_ERR_NONE; -} - -#ifdef CSP_DEBUG -void csp_rtable_print(void) { - - for (csp_rtable_t * i = rtable; (i); i = i->next) { - if (i->mac == 255) { - printf("%u/%u %s\r\n", i->address, i->netmask, i->interface->name); - } else { - printf("%u/%u %s %u\r\n", i->address, i->netmask, i->interface->name, i->mac); - } - } - -} -#endif diff --git a/libcsp/src/rtable/csp_rtable_static.c b/libcsp/src/rtable/csp_rtable_static.c deleted file mode 100644 index ea993027..00000000 --- a/libcsp/src/rtable/csp_rtable_static.c +++ /dev/null @@ -1,128 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include -#include -#include - -/* Local typedef for routing table */ -typedef struct __attribute__((__packed__)) csp_rtable_s { - csp_iface_t * interface; - uint8_t mac; -} csp_rtable_t; - -/* Static storage context for routing table */ -static csp_rtable_t routes[CSP_ROUTE_COUNT] = {}; - -/** - * Find entry in static routing table - * This is done by table lookup with fallback to the default route - * The reason why the csp_rtable_t struct is not returned directly - * is that we wish to hide the storage format, mainly because of - * the alternative routing table storage (cidr). - * @param id Node - * @return pointer to found routing entry - */ -static csp_rtable_t * csp_rtable_find(uint8_t id) { - - if (routes[id].interface != NULL) { - return &routes[id]; - } else if (routes[CSP_DEFAULT_ROUTE].interface != NULL) { - return &routes[CSP_DEFAULT_ROUTE]; - } - return NULL; - -} - -csp_iface_t * csp_rtable_find_iface(uint8_t id) { - csp_rtable_t * route = csp_rtable_find(id); - if (route == NULL) - return NULL; - return route->interface; -} - -uint8_t csp_rtable_find_mac(uint8_t id) { - csp_rtable_t * route = csp_rtable_find(id); - if (route == NULL) - return 255; - return route->mac; -} - -void csp_rtable_clear(void) { - memset(routes, 0, sizeof(routes[0]) * CSP_ROUTE_COUNT); -} - -void csp_route_table_load(uint8_t route_table_in[CSP_ROUTE_TABLE_SIZE]) { - memcpy(routes, route_table_in, sizeof(routes[0]) * CSP_ROUTE_COUNT); -} - -void csp_route_table_save(uint8_t route_table_out[CSP_ROUTE_TABLE_SIZE]) { - memcpy(route_table_out, routes, sizeof(routes[0]) * CSP_ROUTE_COUNT); -} - -int csp_rtable_set(uint8_t node, uint8_t mask, csp_iface_t *ifc, uint8_t mac) { - - /* Don't add nothing */ - if (ifc == NULL) - return CSP_ERR_INVAL; - - /** - * Check if the interface has been added. - * - * NOTE: For future implementations, interfaces should call - * csp_route_add_if in its csp_if__init function, instead - * of registering at first route_set, in order to make the interface - * available to network based (CMP) route configuration. - */ - csp_iflist_add(ifc); - - /* Set route */ - if (node <= CSP_DEFAULT_ROUTE) { - routes[node].interface = ifc; - routes[node].mac = mac; - } else { - csp_log_error("Failed to set route: invalid node id %u", node); - return CSP_ERR_INVAL; - } - - return CSP_ERR_NONE; - -} - -void csp_rtable_load(const char * buffer) { -} - -int csp_rtable_check(const char * buffer) { - return -1; -} - -#ifdef CSP_DEBUG -void csp_rtable_print(void) { - int i; - printf("Node Interface Address\r\n"); - for (i = 0; i < CSP_DEFAULT_ROUTE; i++) - if (routes[i].interface != NULL) - printf("%4u %-9s %u\r\n", i, - routes[i].interface->name, - routes[i].mac == CSP_NODE_MAC ? i : routes[i].mac); - printf(" * %-9s %u\r\n", routes[CSP_DEFAULT_ROUTE].interface->name, routes[CSP_DEFAULT_ROUTE].mac); - -} -#endif diff --git a/libcsp/src/transport/CMakeLists.txt b/libcsp/src/transport/CMakeLists.txt deleted file mode 100644 index c509b755..00000000 --- a/libcsp/src/transport/CMakeLists.txt +++ /dev/null @@ -1,4 +0,0 @@ -target_sources(${LIB_CSP_NAME} PRIVATE - csp_rdp.c - csp_udp.c -) diff --git a/libcsp/src/transport/csp_rdp.c b/libcsp/src/transport/csp_rdp.c deleted file mode 100644 index e19968e2..00000000 --- a/libcsp/src/transport/csp_rdp.c +++ /dev/null @@ -1,1102 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -/* - * This is a implementation of the seq/ack handling taken from the Reliable Datagram Protocol (RDP) - * For more information read RFC 908/1151. The implementation has been extended to include support for - * delayed acknowledgments, to improve performance over half-duplex links. - */ - -#include -#include -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include "../csp_port.h" -#include "../csp_conn.h" -#include "../csp_io.h" -#include "csp_transport.h" - -#ifdef CSP_USE_RDP - -#define RDP_SYN 0x01 -#define RDP_ACK 0x02 -#define RDP_EAK 0x04 -#define RDP_RST 0x08 - -static uint32_t csp_rdp_window_size = 4; -static uint32_t csp_rdp_conn_timeout = 10000; -static uint32_t csp_rdp_packet_timeout = 1000; -static uint32_t csp_rdp_delayed_acks = 1; -static uint32_t csp_rdp_ack_timeout = 1000 / 4; -static uint32_t csp_rdp_ack_delay_count = 4 / 2; - -/* Used for queue calls */ -static CSP_BASE_TYPE pdTrue = 1; - -typedef struct __attribute__((__packed__)) { - /* The timestamp is placed in the padding bytes */ - uint8_t padding[CSP_PADDING_BYTES - 2 * sizeof(uint32_t)]; - uint32_t quarantine; // EACK quarantine period - uint32_t timestamp; // Time the message was sent - uint16_t length; // Length field must be just before CSP ID - csp_id_t id; // CSP id must be just before data - uint8_t data[]; // This just points to the rest of the buffer, without a size indication. -} rdp_packet_t; - -typedef struct __attribute__((__packed__)) { - union __attribute__((__packed__)) { - uint8_t flags; - struct __attribute__((__packed__)) { -#if defined(CSP_BIG_ENDIAN) && !defined(CSP_LITTLE_ENDIAN) - unsigned int res : 4; - unsigned int syn : 1; - unsigned int ack : 1; - unsigned int eak : 1; - unsigned int rst : 1; -#elif defined(CSP_LITTLE_ENDIAN) && !defined(CSP_BIG_ENDIAN) - unsigned int rst : 1; - unsigned int eak : 1; - unsigned int ack : 1; - unsigned int syn : 1; - unsigned int res : 4; -#else - #error "Must define one of CSP_BIG_ENDIAN or CSP_LITTLE_ENDIAN in csp_platform.h" -#endif - }; - }; - uint16_t seq_nr; - uint16_t ack_nr; -} rdp_header_t; - -/** - * RDP Headers: - * The following functions are helper functions that handles the extra RDP - * information that needs to be appended to all data packets. - */ -static rdp_header_t * csp_rdp_header_add(csp_packet_t * packet) { - rdp_header_t * header = (rdp_header_t *) &packet->data[packet->length]; - packet->length += sizeof(rdp_header_t); - memset(header, 0, sizeof(rdp_header_t)); - return header; -} - -static rdp_header_t * csp_rdp_header_remove(csp_packet_t * packet) { - rdp_header_t * header = (rdp_header_t *) &packet->data[packet->length-sizeof(rdp_header_t)]; - packet->length -= sizeof(rdp_header_t); - return header; -} - -static rdp_header_t * csp_rdp_header_ref(csp_packet_t * packet) { - rdp_header_t * header = (rdp_header_t *) &packet->data[packet->length-sizeof(rdp_header_t)]; - return header; -} - -/* Functions for comparing wrapping sequence numbers and timestamps */ - -/* Return 1 if seq is between start and end (both inclusive) */ -static inline int csp_rdp_seq_between(uint16_t seq, uint16_t start, uint16_t end) { - return (uint16_t)(end - start) >= (uint16_t)(seq - start); -} - -/* Return 1 if seq is before cmp */ -static inline int csp_rdp_seq_before(uint16_t seq, uint16_t cmp) { - return (int16_t)(seq - cmp) < 0; -} - -/* Return 1 if seq is after cmp */ -static inline int csp_rdp_seq_after(uint16_t seq, uint16_t cmp) { - return csp_rdp_seq_before(cmp, seq); -} - -/* Return 1 if time is between start and end (both inclusive) */ -static inline int csp_rdp_time_between(uint32_t time, uint32_t start, uint32_t end) { - return (uint32_t)(end - start) >= (uint32_t)(time - start); -} - -/* Return 1 if time is before cmp */ -static inline int csp_rdp_time_before(uint32_t time, uint32_t cmp) { - return (int32_t)(time - cmp) < 0; -} - -/* Return 1 if time is after cmp */ -static inline int csp_rdp_time_after(uint32_t time, uint32_t cmp) { - return csp_rdp_time_before(cmp, time); -} - -/** - * CONTROL MESSAGES - * The following function is used to send empty messages, - * with ACK, SYN or RST flag. - */ -static int csp_rdp_send_cmp(csp_conn_t * conn, csp_packet_t * packet, int flags, int seq_nr, int ack_nr) { - - csp_id_t idout; - - /* Generate message */ - if (!packet) { - packet = csp_buffer_get(20); - if (!packet) - return CSP_ERR_NOMEM; - packet->length = 0; - } - - /* Add RDP header */ - rdp_header_t * header = csp_rdp_header_add(packet); - header->seq_nr = csp_hton16(seq_nr); - header->ack_nr = csp_hton16(ack_nr); - header->ack = (flags & RDP_ACK) ? 1 : 0; - header->eak = (flags & RDP_EAK) ? 1 : 0; - header->syn = (flags & RDP_SYN) ? 1 : 0; - header->rst = (flags & RDP_RST) ? 1 : 0; - - /* Send copy to tx_queue, before sending packet to IF */ - if (flags & RDP_SYN) { - rdp_packet_t * rdp_packet = csp_buffer_clone(packet); - if (rdp_packet == NULL) return CSP_ERR_NOMEM; - rdp_packet->timestamp = csp_get_ms(); - if (csp_queue_enqueue(conn->rdp.tx_queue, &rdp_packet, 0) != CSP_QUEUE_OK) - csp_buffer_free(rdp_packet); - } - - /* Send control messages with high priority */ - idout = conn->idout; - idout.pri = conn->idout.pri < CSP_PRIO_HIGH ? conn->idout.pri : CSP_PRIO_HIGH; - - /* Send packet to IF */ - csp_iface_t * ifout = csp_rtable_find_iface(idout.dst); - if (csp_send_direct(idout, packet, ifout, 0) != CSP_ERR_NONE) { - csp_log_error("INTERFACE ERROR: not possible to send"); - csp_buffer_free(packet); - return CSP_ERR_BUSY; - } - - /* Update last ACK time stamp */ - if (flags & RDP_ACK) { - conn->rdp.rcv_lsa = ack_nr; - conn->rdp.ack_timestamp = csp_get_ms(); - } - - return CSP_ERR_NONE; - -} - -/** - * EXTENDED ACKNOWLEDGEMENTS - * The following function sends an extended ACK packet - */ -static int csp_rdp_send_eack(csp_conn_t * conn) { - - /* Allocate message */ - csp_packet_t * packet_eack = csp_buffer_get(100); - if (packet_eack == NULL) return CSP_ERR_NOMEM; - packet_eack->length = 0; - - /* Loop through RX queue */ - int i, count; - csp_packet_t * packet; - count = csp_queue_size(conn->rdp.rx_queue); - for (i = 0; i < count; i++) { - - if (csp_queue_dequeue_isr(conn->rdp.rx_queue, &packet, &pdTrue) != CSP_QUEUE_OK) { - csp_log_error("Cannot dequeue from rx_queue in queue deliver"); - break; - } - - /* Add seq nr to EACK packet */ - rdp_header_t * header = csp_rdp_header_ref(packet); - packet_eack->data16[packet_eack->length/sizeof(uint16_t)] = csp_hton16(header->seq_nr); - packet_eack->length += sizeof(uint16_t); - csp_log_protocol("Added EACK nr %u", header->seq_nr); - - /* Requeue */ - csp_queue_enqueue_isr(conn->rdp.rx_queue, &packet, &pdTrue); - - } - - return csp_rdp_send_cmp(conn, packet_eack, RDP_ACK | RDP_EAK, conn->rdp.snd_nxt, conn->rdp.rcv_cur); - -} - - -/** - * SYN Packet - * The following function sends a SYN packet - */ -static int csp_rdp_send_syn(csp_conn_t * conn) { - - /* Allocate message */ - csp_packet_t * packet = csp_buffer_get(100); - if (packet == NULL) return CSP_ERR_NOMEM; - - /* Generate contents */ - packet->data32[0] = csp_hton32(csp_rdp_window_size); - packet->data32[1] = csp_hton32(csp_rdp_conn_timeout); - packet->data32[2] = csp_hton32(csp_rdp_packet_timeout); - packet->data32[3] = csp_hton32(csp_rdp_delayed_acks); - packet->data32[4] = csp_hton32(csp_rdp_ack_timeout); - packet->data32[5] = csp_hton32(csp_rdp_ack_delay_count); - packet->length = 6 * sizeof(uint32_t); - - return csp_rdp_send_cmp(conn, packet, RDP_SYN, conn->rdp.snd_iss, 0); - -} - -static inline int csp_rdp_receive_data(csp_conn_t * conn, csp_packet_t * packet) { - - /* Remove RDP header before passing to userspace */ - csp_rdp_header_remove(packet); - - /* Enqueue data */ - if (csp_conn_enqueue_packet(conn, packet) < 0) { - csp_log_warn("Conn RX buffer full"); - return CSP_ERR_NOBUFS; - } - - return CSP_ERR_NONE; - -} - -static inline void csp_rdp_rx_queue_flush(csp_conn_t * conn) { - - /* Loop through RX queue */ - int i, count; - csp_packet_t * packet; - -front: - count = csp_queue_size(conn->rdp.rx_queue); - for (i = 0; i < count; i++) { - - if (csp_queue_dequeue_isr(conn->rdp.rx_queue, &packet, &pdTrue) != CSP_QUEUE_OK) { - csp_log_error("Cannot dequeue from rx_queue in queue deliver"); - break; - } - - rdp_header_t * header = csp_rdp_header_ref(packet); - csp_log_protocol("RX Queue deliver matching Element, seq %u", header->seq_nr); - - /* If the matching packet was found: */ - if (header->seq_nr == (uint16_t)(conn->rdp.rcv_cur + 1)) { - csp_log_protocol("Deliver seq %u", header->seq_nr); - csp_rdp_receive_data(conn, packet); - conn->rdp.rcv_cur++; - /* Loop from first element again */ - goto front; - - /* Otherwise, requeue */ - } else { - csp_queue_enqueue_isr(conn->rdp.rx_queue, &packet, &pdTrue); - } - - } - -} - -static inline bool csp_rdp_seq_in_rx_queue(csp_conn_t * conn, uint16_t seq_nr) { - - /* Loop through RX queue */ - int i, count; - rdp_packet_t * packet; - count = csp_queue_size(conn->rdp.rx_queue); - for (i = 0; i < count; i++) { - - if (csp_queue_dequeue_isr(conn->rdp.rx_queue, &packet, &pdTrue) != CSP_QUEUE_OK) { - csp_log_error("Cannot dequeue from rx_queue in queue exists"); - break; - } - - csp_queue_enqueue_isr(conn->rdp.rx_queue, &packet, &pdTrue); - - rdp_header_t * header = csp_rdp_header_ref((csp_packet_t *) packet); - csp_log_protocol("RX Queue exists matching Element, seq %u", header->seq_nr); - - /* If the matching packet was found, deliver */ - if (header->seq_nr == seq_nr) { - csp_log_protocol("We have a match"); - return true; - } - - } - - return false; - -} - -static inline int csp_rdp_rx_queue_add(csp_conn_t * conn, csp_packet_t * packet, uint16_t seq_nr) { - - if (csp_rdp_seq_in_rx_queue(conn, seq_nr)) - return CSP_QUEUE_ERROR; - return csp_queue_enqueue_isr(conn->rdp.rx_queue, &packet, &pdTrue); - -} - -static void csp_rdp_flush_eack(csp_conn_t * conn, csp_packet_t * eack_packet) { - - /* Loop through TX queue */ - int i, j, count; - rdp_packet_t * packet; - count = csp_queue_size(conn->rdp.tx_queue); - for (i = 0; i < count; i++) { - - if (csp_queue_dequeue(conn->rdp.tx_queue, &packet, 0) != CSP_QUEUE_OK) { - csp_log_error("Cannot dequeue from tx_queue in flush EACK"); - break; - } - - rdp_header_t * header = csp_rdp_header_ref((csp_packet_t *) packet); - csp_log_protocol("EACK compare element, time %u, seq %u", packet->timestamp, csp_ntoh16(header->seq_nr)); - - /* Look for this element in EACKs */ - int match = 0; - for (j = 0; j < (int)((eack_packet->length - sizeof(rdp_header_t)) / sizeof(uint16_t)); j++) { - if (csp_ntoh16(eack_packet->data16[j]) == csp_ntoh16(header->seq_nr)) - match = 1; - - /* Enable this if you want EACK's to trigger retransmission */ - if (csp_ntoh16(eack_packet->data16[j]) > csp_ntoh16(header->seq_nr)) { - uint32_t time_now = csp_get_ms(); - if (csp_rdp_time_after(time_now, packet->quarantine)) { - packet->timestamp = time_now - conn->rdp.packet_timeout - 1; - packet->quarantine = time_now + conn->rdp.packet_timeout / 2; - } - } - } - - if (match == 0) { - /* If not found, put back on tx queue */ - csp_queue_enqueue(conn->rdp.tx_queue, &packet, 0); - } else { - /* Found, free */ - csp_log_protocol("TX Element %u freed", csp_ntoh16(header->seq_nr)); - csp_buffer_free(packet); - } - - } - -} - -static inline bool csp_rdp_should_ack(csp_conn_t * conn) { - - /* If delayed ACKs are not used, always ACK */ - if (!conn->rdp.delayed_acks) { - return true; - } - - /* ACK if time since last ACK is greater than ACK timeout */ - uint32_t time_now = csp_get_ms(); - if (csp_rdp_time_after(time_now, conn->rdp.ack_timestamp + conn->rdp.ack_timeout)) - return true; - - /* ACK if number of unacknowledged packets is greater than delay count */ - if (csp_rdp_seq_after(conn->rdp.rcv_cur, conn->rdp.rcv_lsa + conn->rdp.ack_delay_count)) - return true; - - return false; - -} - -void csp_rdp_flush_all(csp_conn_t * conn) { - - if ((conn == NULL) || conn->rdp.tx_queue == NULL) { - csp_log_error("Null pointer passed to rdp flush all"); - return; - } - - rdp_packet_t * packet; - - /* Empty TX queue */ - while (csp_queue_dequeue_isr(conn->rdp.tx_queue, &packet, &pdTrue) == CSP_QUEUE_OK) { - if (packet != NULL) { - csp_log_protocol("RDP %p: Flush TX Element, time %u, seq %u", conn, packet->timestamp, csp_ntoh16(csp_rdp_header_ref((csp_packet_t *) packet)->seq_nr)); - csp_buffer_free(packet); - } - } - - /* Empty RX queue */ - while (csp_queue_dequeue_isr(conn->rdp.rx_queue, &packet, &pdTrue) == CSP_QUEUE_OK) { - if (packet != NULL) { - csp_log_protocol("RDP %p: Flush RX Element, time %u, seq %u", conn, packet->timestamp, csp_ntoh16(csp_rdp_header_ref((csp_packet_t *) packet)->seq_nr)); - csp_buffer_free(packet); - } - } - -} - - -int csp_rdp_check_ack(csp_conn_t * conn) { - - /* Check all RX queues for spare capacity */ - int prio, avail = 1; - for (prio = 0; prio < CSP_RX_QUEUES; prio++) { - if (CSP_RX_QUEUE_LENGTH - csp_queue_size(conn->rx_queue[prio]) <= 2 * (int32_t)conn->rdp.window_size) { - avail = 0; - break; - } - } - - /* If more space available, only send after ack timeout or immediately if delay_acks is zero */ - if (avail && csp_rdp_should_ack(conn)) - csp_rdp_send_cmp(conn, NULL, RDP_ACK, conn->rdp.snd_nxt, conn->rdp.rcv_cur); - - return CSP_ERR_NONE; - -} - -static inline bool csp_rdp_is_conn_ready_for_tx(csp_conn_t * conn) -{ - // Check Tx window (messages waiting for acks) - if (csp_rdp_seq_after(conn->rdp.snd_nxt, conn->rdp.snd_una + conn->rdp.window_size - 1)) { - return false; - } - return true; -} - -/** - * This function must be called with regular intervals for the - * RDP protocol to work as expected. This takes care of closing - * stale connections and retransmitting traffic. A good place to - * call this function is from the CSP router task. - */ -void csp_rdp_check_timeouts(csp_conn_t * conn) { - - rdp_packet_t * packet; - - /** - * CONNECTION TIMEOUT: - * Check that connection has not timed out inside the network stack - * */ - uint32_t time_now = csp_get_ms(); - if (conn->socket != NULL) { - if (csp_rdp_time_after(time_now, conn->timestamp + conn->rdp.conn_timeout)) { - csp_log_warn("RDP %p: Found a lost connection (now: %u, ts: %u, to: %u), closing now", - conn, time_now, conn->timestamp, conn->rdp.conn_timeout); - csp_close(conn); - return; - } - } - - /** - * CLOSE-WAIT TIMEOUT: - * After waiting a while in CLOSE-WAIT, the connection should be closed. - */ - if (conn->rdp.state == RDP_CLOSE_WAIT) { - if (csp_rdp_time_after(time_now, conn->timestamp + conn->rdp.conn_timeout)) { - csp_log_protocol("RDP %p: CLOSE_WAIT timeout", conn); - csp_close(conn); - } - return; - } - - /** - * MESSAGE TIMEOUT: - * Check each outgoing message for TX timeout - */ - int i, count; - count = csp_queue_size(conn->rdp.tx_queue); - for (i = 0; i < count; i++) { - - if ((csp_queue_dequeue_isr(conn->rdp.tx_queue, &packet, &pdTrue) != CSP_QUEUE_OK) || packet == NULL) { - csp_log_warn("Cannot dequeue from tx_queue in check timeout"); - break; - } - - /* Get header */ - rdp_header_t * header = csp_rdp_header_ref((csp_packet_t *) packet); - - /* If acked, do not retransmit */ - if (csp_rdp_seq_before(csp_ntoh16(header->seq_nr), conn->rdp.snd_una)) { - csp_log_protocol("TX Element Free, time %u, seq %u, una %u", packet->timestamp, csp_ntoh16(header->seq_nr), conn->rdp.snd_una); - csp_buffer_free(packet); - continue; - } - - /* Check timestamp and retransmit if needed */ - if (csp_rdp_time_after(time_now, packet->timestamp + conn->rdp.packet_timeout)) { - csp_log_protocol("TX Element timed out, retransmitting seq %u", csp_ntoh16(header->seq_nr)); - - /* Update to latest outgoing ACK */ - header->ack_nr = csp_hton16(conn->rdp.rcv_cur); - - /* Send copy to tx_queue */ - packet->timestamp = csp_get_ms(); - csp_packet_t * new_packet = csp_buffer_clone(packet); - csp_iface_t * ifout = csp_rtable_find_iface(conn->idout.dst); - if (csp_send_direct(conn->idout, new_packet, ifout, 0) != CSP_ERR_NONE) { - csp_log_warn("Retransmission failed"); - csp_buffer_free(new_packet); - } - - } - - /* Requeue the TX element */ - csp_queue_enqueue_isr(conn->rdp.tx_queue, &packet, &pdTrue); - - } - - /** - * ACK TIMEOUT: - * Check ACK timeouts, if we have unacknowledged segments - */ - if (conn->rdp.delayed_acks) { - csp_rdp_check_ack(conn); - } - - /* Wake user task if connection is open and additional Tx can be done */ - if ((conn->rdp.state == RDP_OPEN) && csp_rdp_is_conn_ready_for_tx(conn)) { - csp_log_protocol("RDP %p: Wake Tx task (check timeouts)", conn); - csp_bin_sem_post(&conn->rdp.tx_wait); - } -} - -void csp_rdp_new_packet(csp_conn_t * conn, csp_packet_t * packet) { - - /* Get RX header and convert to host byte-order */ - rdp_header_t * rx_header = csp_rdp_header_ref(packet); - rx_header->ack_nr = csp_ntoh16(rx_header->ack_nr); - rx_header->seq_nr = csp_ntoh16(rx_header->seq_nr); - - csp_log_protocol("RDP %p: Received in S %u: syn %u, ack %u, eack %u, " - "rst %u, seq_nr %5u, ack_nr %5u, packet_len %u (%u)", - conn, conn->rdp.state, rx_header->syn, rx_header->ack, rx_header->eak, - rx_header->rst, rx_header->seq_nr, rx_header->ack_nr, - packet->length, packet->length - sizeof(rdp_header_t)); - - /* If a RESET was received. */ - if (rx_header->rst) { - - if (rx_header->ack) { - /* Store current ack'ed sequence number */ - conn->rdp.snd_una = rx_header->ack_nr + 1; - } - - if (conn->rdp.state == RDP_CLOSE_WAIT || conn->rdp.state == RDP_CLOSED) { - csp_log_protocol("RDP %p: RST received in CLOSE_WAIT or CLOSED. Now closing connection", conn); - goto discard_close; - } else { - csp_log_protocol("RDP %p: Got RESET in state %u", conn, conn->rdp.state); - - if (rx_header->seq_nr == (uint16_t)(conn->rdp.rcv_cur + 1)) { - csp_log_protocol("RDP %p: RESET in sequence, no more data incoming, reply with RESET", conn); - conn->rdp.state = RDP_CLOSE_WAIT; - conn->timestamp = csp_get_ms(); - csp_rdp_send_cmp(conn, NULL, RDP_ACK | RDP_RST, conn->rdp.snd_nxt, conn->rdp.rcv_cur); - goto discard_close; - } else { - csp_log_protocol("RDP %p: RESET out of sequence, keep connection open", conn); - goto discard_open; - } - } - } - - /* The BIG FAT switch (state-machine) */ - switch(conn->rdp.state) { - - /** - * STATE == CLOSED - */ - case RDP_CLOSED: { - - /* No SYN flag set while in closed. Inform by sending back RST */ - if (!rx_header->syn) { - csp_log_protocol("Not SYN received in CLOSED state. Discarding packet"); - csp_rdp_send_cmp(conn, NULL, RDP_RST, conn->rdp.snd_nxt, conn->rdp.rcv_cur); - goto discard_close; - } - - csp_log_protocol("RDP: SYN-Received"); - - /* Setup TX seq. */ - conn->rdp.snd_iss = (uint16_t)rand(); - conn->rdp.snd_nxt = conn->rdp.snd_iss + 1; - conn->rdp.snd_una = conn->rdp.snd_iss; - - /* Store RX seq. */ - conn->rdp.rcv_cur = rx_header->seq_nr; - conn->rdp.rcv_irs = rx_header->seq_nr; - conn->rdp.rcv_lsa = rx_header->seq_nr; - - /* Store RDP options */ - conn->rdp.window_size = csp_ntoh32(packet->data32[0]); - conn->rdp.conn_timeout = csp_ntoh32(packet->data32[1]); - conn->rdp.packet_timeout = csp_ntoh32(packet->data32[2]); - conn->rdp.delayed_acks = csp_ntoh32(packet->data32[3]); - conn->rdp.ack_timeout = csp_ntoh32(packet->data32[4]); - conn->rdp.ack_delay_count = csp_ntoh32(packet->data32[5]); - csp_log_protocol("RDP: Window Size %u, conn timeout %u, packet timeout %u", - conn->rdp.window_size, conn->rdp.conn_timeout, conn->rdp.packet_timeout); - csp_log_protocol("RDP: Delayed acks: %u, ack timeout %u, ack each %u packet", - conn->rdp.delayed_acks, conn->rdp.ack_timeout, conn->rdp.ack_delay_count); - - /* Connection accepted */ - conn->rdp.state = RDP_SYN_RCVD; - - /* Send SYN/ACK */ - csp_rdp_send_cmp(conn, NULL, RDP_ACK | RDP_SYN, conn->rdp.snd_iss, conn->rdp.rcv_irs); - - goto discard_open; - - } - break; - - /** - * STATE == SYN-SENT - */ - case RDP_SYN_SENT: { - - /* First check SYN/ACK */ - if (rx_header->syn && rx_header->ack) { - - conn->rdp.rcv_cur = rx_header->seq_nr; - conn->rdp.rcv_irs = rx_header->seq_nr; - conn->rdp.rcv_lsa = rx_header->seq_nr - 1; - conn->rdp.snd_una = rx_header->ack_nr + 1; - conn->rdp.ack_timestamp = csp_get_ms(); - conn->rdp.state = RDP_OPEN; - - csp_log_protocol("RDP: NP: Connection OPEN"); - - /* Send ACK */ - csp_rdp_send_cmp(conn, NULL, RDP_ACK, conn->rdp.snd_nxt, conn->rdp.rcv_cur); - - /* Wake TX task */ - csp_log_protocol("RDP %p: Wake Tx task (ack)", conn); - csp_bin_sem_post(&conn->rdp.tx_wait); - - goto discard_open; - } - - /* If there was no SYN in the reply, our SYN message hit an already open connection - * This is handled by sending a RST. - * Normally this would be followed up by a new connection attempt, however - * we don't have a method for signaling this to the user space. - */ - if (rx_header->ack) { - csp_log_error("Half-open connection found, sending RST"); - csp_rdp_send_cmp(conn, NULL, RDP_RST, conn->rdp.snd_nxt, conn->rdp.rcv_cur); - csp_log_protocol("RDP %p: Wake Tx task (rst)", conn); - csp_bin_sem_post(&conn->rdp.tx_wait); - - goto discard_open; - } - - /* Otherwise we have an invalid command, such as a SYN reply to a SYN command, - * indicating simultaneous connections, which is not possible in the way CSP - * reserves some ports for server and some for clients. - */ - csp_log_error("Invalid reply to SYN request"); - goto discard_close; - - } - break; - - /** - * STATE == OPEN - */ - case RDP_SYN_RCVD: - case RDP_OPEN: - { - - /* SYN or !ACK is invalid */ - if (rx_header->syn || !rx_header->ack) { - if (rx_header->seq_nr != conn->rdp.rcv_irs) { - csp_log_error("Invalid SYN or no ACK, resetting!"); - goto discard_close; - } else { - csp_log_protocol("Ignoring duplicate SYN packet!"); - goto discard_open; - } - } - - /* Check sequence number */ - if (!csp_rdp_seq_between(rx_header->seq_nr, conn->rdp.rcv_cur + 1, conn->rdp.rcv_cur + conn->rdp.window_size * 2)) { - csp_log_protocol("Invalid sequence number! %"PRIu16" not between %"PRIu16" and %"PRIu16, - rx_header->seq_nr, conn->rdp.rcv_cur + 1, conn->rdp.rcv_cur + 1 + conn->rdp.window_size * 2); - /* If duplicate SYN received, send another SYN/ACK */ - if (conn->rdp.state == RDP_SYN_RCVD) - csp_rdp_send_cmp(conn, NULL, RDP_ACK | RDP_SYN, conn->rdp.snd_iss, conn->rdp.rcv_irs); - /* If duplicate data packet received, send EACK back */ - if (conn->rdp.state == RDP_OPEN) - csp_rdp_send_eack(conn); - - goto discard_open; - } - - /* Check ACK number */ - if (!csp_rdp_seq_between(rx_header->ack_nr, conn->rdp.snd_una - 1 - (conn->rdp.window_size * 2), conn->rdp.snd_nxt - 1)) { - csp_log_error("Invalid ACK number! %u not between %u and %u", - rx_header->ack_nr, conn->rdp.snd_una - 1 - (conn->rdp.window_size * 2), conn->rdp.snd_nxt - 1); - goto discard_open; - } - - /* Check SYN_RCVD ACK */ - if (conn->rdp.state == RDP_SYN_RCVD) { - if (rx_header->ack_nr != conn->rdp.snd_iss) { - csp_log_error("SYN-RCVD: Wrong ACK number"); - goto discard_close; - } - csp_log_protocol("RDP: NC: Connection OPEN"); - conn->rdp.state = RDP_OPEN; - - /* If a socket is set, this message is the first in a new connection - * so the connection must be queued to the socket. */ - if (conn->socket != NULL) { - - /* Try queueing */ - if (csp_queue_enqueue(conn->socket, &conn, 0) == CSP_QUEUE_FULL) { - csp_log_error("ERROR socket cannot accept more connections"); - goto discard_close; - } - - /* Ensure that this connection will not be posted to this socket again - * and remember that the connection handle has been passed to userspace - * by setting the socket = NULL */ - conn->socket = NULL; - } - - } - - /* Store current ack'ed sequence number */ - conn->rdp.snd_una = rx_header->ack_nr + 1; - - /* We have an EACK */ - if (rx_header->eak) { - if (packet->length > sizeof(rdp_header_t)) - csp_rdp_flush_eack(conn, packet); - goto discard_open; - } - - /* If no data, return here */ - if (packet->length <= sizeof(rdp_header_t)) - goto discard_open; - - /* If message is not in sequence, send EACK and store packet */ - if (rx_header->seq_nr != (uint16_t)(conn->rdp.rcv_cur + 1)) { - if (csp_rdp_rx_queue_add(conn, packet, rx_header->seq_nr) != CSP_QUEUE_OK) { - csp_log_protocol("Duplicate sequence number"); - csp_rdp_check_ack(conn); - goto discard_open; - } - csp_rdp_send_eack(conn); - goto accepted_open; - } - - /* Store sequence number before stripping RDP header */ - uint16_t seq_nr = rx_header->seq_nr; - - /* Receive data */ - if (csp_rdp_receive_data(conn, packet) != CSP_ERR_NONE) - goto discard_open; - - /* Update last received packet */ - conn->rdp.rcv_cur = seq_nr; - - /* Only ACK the message if there is room for a full window in the RX buffer. - * Unacknowledged segments are ACKed by csp_rdp_check_timeouts when the buffer is - * no longer full. */ - csp_rdp_check_ack(conn); - - /* Flush RX queue */ - csp_rdp_rx_queue_flush(conn); - - goto accepted_open; - - } - break; - - case RDP_CLOSE_WAIT: - - /* Ignore SYN or !ACK */ - if (rx_header->syn || !rx_header->ack) { - csp_log_protocol("Invalid SYN or no ACK in CLOSE-WAIT"); - goto discard_open; - } - - /* Check ACK number */ - if (!csp_rdp_seq_between(rx_header->ack_nr, conn->rdp.snd_una - 1 - (conn->rdp.window_size * 2), conn->rdp.snd_nxt - 1)) { - csp_log_error("Invalid ACK number! %u not between %u and %u", - rx_header->ack_nr, conn->rdp.snd_una - 1 - (conn->rdp.window_size * 2), conn->rdp.snd_nxt - 1); - goto discard_open; - } - - /* Store current ack'ed sequence number */ - conn->rdp.snd_una = rx_header->ack_nr + 1; - - /* Send back a reset */ - csp_rdp_send_cmp(conn, NULL, RDP_ACK | RDP_RST, conn->rdp.snd_nxt, conn->rdp.rcv_cur); - - goto discard_open; - - default: - csp_log_error("RDP: ERROR default state!"); - goto discard_close; - } - -discard_close: - /* If user-space has received the connection handle, wake it up, - * by sending a NULL pointer, user-space should close connection */ - if (conn->socket == NULL) { - csp_log_protocol("RDP %p: Waiting for userspace to close", conn); - csp_conn_enqueue_packet(conn, NULL); - } else { - csp_close(conn); - } - -discard_open: - csp_buffer_free(packet); -accepted_open: - return; - -} - -int csp_rdp_connect(csp_conn_t * conn, uint32_t timeout) { - - int retry = 1; - - conn->rdp.window_size = csp_rdp_window_size; - conn->rdp.conn_timeout = csp_rdp_conn_timeout; - conn->rdp.packet_timeout = csp_rdp_packet_timeout; - conn->rdp.delayed_acks = csp_rdp_delayed_acks; - conn->rdp.ack_timeout = csp_rdp_ack_timeout; - conn->rdp.ack_delay_count = csp_rdp_ack_delay_count; - conn->rdp.ack_timestamp = csp_get_ms(); - -retry: - csp_log_protocol("RDP %p: Active connect, conn state %u", conn, conn->rdp.state); - - if (conn->rdp.state == RDP_OPEN) { - csp_log_error("RDP %p: Connection already open", conn); - return CSP_ERR_ALREADY; - } - - /* Randomize ISS */ - conn->rdp.snd_iss = (uint16_t)rand(); - - conn->rdp.snd_nxt = conn->rdp.snd_iss + 1; - conn->rdp.snd_una = conn->rdp.snd_iss; - - csp_log_protocol("RDP %p: AC: Sending SYN", conn); - - /* Ensure semaphore is busy, so router task can release it */ - csp_bin_sem_wait(&conn->rdp.tx_wait, 0); - - /* Send SYN message */ - conn->rdp.state = RDP_SYN_SENT; - if (csp_rdp_send_syn(conn) != CSP_ERR_NONE) - goto error; - - /* Wait for router task to release semaphore */ - csp_log_protocol("RDP %p: AC: Waiting for SYN/ACK reply...", conn); - int result = csp_bin_sem_wait(&conn->rdp.tx_wait, conn->rdp.conn_timeout); - - if (result == CSP_SEMAPHORE_OK) { - if (conn->rdp.state == RDP_OPEN) { - csp_log_protocol("RDP %p: AC: Connection OPEN", conn); - return CSP_ERR_NONE; - } else if(conn->rdp.state == RDP_SYN_SENT) { - if (retry) { - csp_log_warn("RDP %p: Half-open connection detected, RST sent, now retrying", conn); - csp_rdp_flush_all(conn); - retry = 0; - goto retry; - } else { - csp_log_error("RDP %p: Connection stayed half-open, even after RST and retry!", conn); - goto error; - } - } - } else { - csp_log_protocol("RDP %p: AC: Connection Failed", conn); - goto error; - } - -error: - conn->rdp.state = RDP_CLOSE_WAIT; - return CSP_ERR_TIMEDOUT; - -} - -int csp_rdp_send(csp_conn_t * conn, csp_packet_t * packet, uint32_t timeout) { - - if (conn->rdp.state != RDP_OPEN) { - csp_log_error("RDP: ERROR cannot send, connection reset"); - return CSP_ERR_RESET; - } - - while ((conn->rdp.state == RDP_OPEN) && (csp_rdp_is_conn_ready_for_tx(conn) == false)) { - csp_log_protocol("RDP %p: Waiting for window update before sending seq %u", conn, conn->rdp.snd_nxt); - if ((csp_bin_sem_wait(&conn->rdp.tx_wait, conn->rdp.conn_timeout)) != CSP_SEMAPHORE_OK) { - csp_log_error("RDP %p: Timeout during send", conn); - return CSP_ERR_TIMEDOUT; - } - } - - if (conn->rdp.state != RDP_OPEN) { - csp_log_error("RDP: ERROR cannot send, connection reset"); - return CSP_ERR_RESET; - } - - /* Add RDP header */ - rdp_header_t * tx_header = csp_rdp_header_add(packet); - tx_header->ack_nr = csp_hton16(conn->rdp.rcv_cur); - tx_header->seq_nr = csp_hton16(conn->rdp.snd_nxt); - tx_header->ack = 1; - - /* Send copy to tx_queue */ - rdp_packet_t * rdp_packet = csp_buffer_clone(packet); - if (rdp_packet == NULL) { - csp_log_error("Failed to allocate packet buffer"); - return CSP_ERR_NOMEM; - } - - rdp_packet->timestamp = csp_get_ms(); - rdp_packet->quarantine = 0; - if (csp_queue_enqueue(conn->rdp.tx_queue, &rdp_packet, 0) != CSP_QUEUE_OK) { - csp_log_error("No more space in RDP retransmit queue"); - csp_buffer_free(rdp_packet); - return CSP_ERR_NOBUFS; - } - - csp_log_protocol("RDP: Sending in S %u: syn %u, ack %u, eack %u, " - "rst %u, seq_nr %5u, ack_nr %5u, packet_len %u (%u)", - conn->rdp.state, tx_header->syn, tx_header->ack, tx_header->eak, - tx_header->rst, csp_ntoh16(tx_header->seq_nr), csp_ntoh16(tx_header->ack_nr), - packet->length, packet->length - sizeof(rdp_header_t)); - - conn->rdp.snd_nxt++; - return CSP_ERR_NONE; - -} - -int csp_rdp_allocate(csp_conn_t * conn) { - - csp_log_protocol("RDP: Creating RDP queues for conn %p", conn); - - /* Set initial state */ - conn->rdp.state = RDP_CLOSED; - conn->rdp.conn_timeout = csp_rdp_conn_timeout; - conn->rdp.packet_timeout = csp_rdp_packet_timeout; - - /* Create a binary semaphore to wait on for tasks */ - if (csp_bin_sem_create(&conn->rdp.tx_wait) != CSP_SEMAPHORE_OK) { - csp_log_error("Failed to initialize semaphore"); - return CSP_ERR_NOMEM; - } - - /* Create TX queue */ - conn->rdp.tx_queue = csp_queue_create(CSP_RDP_MAX_WINDOW, sizeof(csp_packet_t *)); - if (conn->rdp.tx_queue == NULL) { - csp_log_error("Failed to create TX queue for conn"); - csp_bin_sem_remove(&conn->rdp.tx_wait); - return CSP_ERR_NOMEM; - } - - /* Create RX queue */ - conn->rdp.rx_queue = csp_queue_create(CSP_RDP_MAX_WINDOW * 2, sizeof(csp_packet_t *)); - if (conn->rdp.rx_queue == NULL) { - csp_log_error("Failed to create RX queue for conn"); - csp_bin_sem_remove(&conn->rdp.tx_wait); - csp_queue_remove(conn->rdp.tx_queue); - return CSP_ERR_NOMEM; - } - - return CSP_ERR_NONE; - -} - -/** - * @note This function may only be called from csp_close, and is therefore - * without any checks for null pointers. - */ -int csp_rdp_close(csp_conn_t * conn) { - - if (conn->rdp.state == RDP_CLOSED) - return CSP_ERR_NONE; - - /* If message is open, send reset */ - if (conn->rdp.state != RDP_CLOSE_WAIT) { - conn->rdp.state = RDP_CLOSE_WAIT; - conn->timestamp = csp_get_ms(); - csp_rdp_send_cmp(conn, NULL, RDP_ACK | RDP_RST, conn->rdp.snd_nxt, conn->rdp.rcv_cur); - csp_log_protocol("RDP %p: Close, sent RST", conn); - csp_bin_sem_post(&conn->rdp.tx_wait); // wake up any pendng Tx - return CSP_ERR_AGAIN; - } - - csp_log_protocol("RDP %p: Close in CLOSE_WAIT, now closing", conn); - conn->rdp.state = RDP_CLOSED; - return CSP_ERR_NONE; - -} - -/** - * RDP Set socket options - * Controls important parameters of the RDP protocol. - * These settings will be applied to all new outgoing connections. - * The settings are global, so be sure no other task are conflicting with your settings. - */ -void csp_rdp_set_opt(unsigned int window_size, unsigned int conn_timeout_ms, - unsigned int packet_timeout_ms, unsigned int delayed_acks, - unsigned int ack_timeout, unsigned int ack_delay_count) { - csp_rdp_window_size = window_size; - csp_rdp_conn_timeout = conn_timeout_ms; - csp_rdp_packet_timeout = packet_timeout_ms; - csp_rdp_delayed_acks = delayed_acks; - csp_rdp_ack_timeout = ack_timeout; - csp_rdp_ack_delay_count = ack_delay_count; -} - -void csp_rdp_get_opt(unsigned int * window_size, unsigned int * conn_timeout_ms, - unsigned int * packet_timeout_ms, unsigned int * delayed_acks, - unsigned int * ack_timeout, unsigned int * ack_delay_count) { - - if (window_size) - *window_size = csp_rdp_window_size; - if (conn_timeout_ms) - *conn_timeout_ms = csp_rdp_conn_timeout; - if (packet_timeout_ms) - *packet_timeout_ms = csp_rdp_packet_timeout; - if (delayed_acks) - *delayed_acks = csp_rdp_delayed_acks; - if (ack_timeout) - *ack_timeout = csp_rdp_ack_timeout; - if (ack_delay_count) - *ack_delay_count = csp_rdp_ack_delay_count; -} - -#ifdef CSP_DEBUG -void csp_rdp_conn_print(csp_conn_t * conn) { - - if (conn == NULL) - return; - - printf("\tRDP: State %"PRIu16", rcv %"PRIu16", snd %"PRIu16", win %"PRIu32"\r\n", - conn->rdp.state, conn->rdp.rcv_cur, conn->rdp.snd_una, conn->rdp.window_size); - -} -#endif - -#endif diff --git a/libcsp/src/transport/csp_transport.h b/libcsp/src/transport/csp_transport.h deleted file mode 100644 index 7fcda3dc..00000000 --- a/libcsp/src/transport/csp_transport.h +++ /dev/null @@ -1,46 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#ifndef _CSP_TRANSPORT_H_ -#define _CSP_TRANSPORT_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -/** ARRIVING SEGMENT */ -void csp_udp_new_packet(csp_conn_t * conn, csp_packet_t * packet); -void csp_rdp_new_packet(csp_conn_t * conn, csp_packet_t * packet); - -/** RDP: USER REQUESTS */ -int csp_rdp_connect(csp_conn_t * conn, uint32_t timeout); -int csp_rdp_allocate(csp_conn_t * conn); -int csp_rdp_close(csp_conn_t * conn); -void csp_rdp_conn_print(csp_conn_t * conn); -int csp_rdp_send(csp_conn_t * conn, csp_packet_t * packet, uint32_t timeout); -int csp_rdp_check_ack(csp_conn_t * conn); -void csp_rdp_check_timeouts(csp_conn_t * conn); -void csp_rdp_flush_all(csp_conn_t * conn); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif /* _CSP_TRANSPORT_H_ */ diff --git a/libcsp/src/transport/csp_udp.c b/libcsp/src/transport/csp_udp.c deleted file mode 100644 index 61732703..00000000 --- a/libcsp/src/transport/csp_udp.c +++ /dev/null @@ -1,49 +0,0 @@ -/* -Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) - -This library is free software; you can redistribute it and/or -modify it under the terms of the GNU Lesser General Public -License as published by the Free Software Foundation; either -version 2.1 of the License, or (at your option) any later version. - -This library is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -Lesser General Public License for more details. - -You should have received a copy of the GNU Lesser General Public -License along with this library; if not, write to the Free Software -Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include -#include -#include "../csp_port.h" -#include "../csp_conn.h" -#include "csp_transport.h" - -void csp_udp_new_packet(csp_conn_t * conn, csp_packet_t * packet) { - - /* Enqueue */ - if (csp_conn_enqueue_packet(conn, packet) < 0) { - csp_log_error("Connection buffer queue full!"); - csp_buffer_free(packet); - return; - } - - /* Try to queue up the new connection pointer */ - if (conn->socket != NULL) { - if (csp_queue_enqueue(conn->socket, &conn, 0) != CSP_QUEUE_OK) { - csp_log_warn("Warning socket connection queue full"); - csp_close(conn); - return; - } - - /* Ensure that this connection will not be posted to this socket again */ - conn->socket = NULL; - } - -} - diff --git a/libcsp/utils/cfpsplit.py b/libcsp/utils/cfpsplit.py deleted file mode 100644 index 9a350e3e..00000000 --- a/libcsp/utils/cfpsplit.py +++ /dev/null @@ -1,52 +0,0 @@ -#!/usr/bin/env python - -# Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -# Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -# Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) -# -# This library is free software; you can redistribute it and/or -# modify it under the terms of the GNU Lesser General Public -# License as published by the Free Software Foundation; either -# version 2.1 of the License, or (at your option) any later version. -# -# This library is distributed in the hope that it will be useful, -# but WITHOUT ANY WARRANTY; without even the implied warranty of -# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -# Lesser General Public License for more details. -# -# You should have received a copy of the GNU Lesser General Public -# License along with this library; if not, write to the Free Software -# Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA - -# Split CFP header in protocol fields - -import sys - -def usage(): - print("usage: cfpsplit.py HEADER") - -def main(): - try: - hdr = sys.argv[1] - except: - usage() - sys.exit(-1) - - try: - hdrhex = int(hdr, 16) - except: - print("HEADER must be in hexadecimal format") - sys.exit(-1) - - if hdrhex > 0x1fffffff: - print("HEADER is not a valid CFP header") - sys.exit(-1) - - print("Source: {0}".format((hdrhex >> 24) & 0x1f)) - print("Destination: {0}".format((hdrhex >> 19) & 0x1f)) - print("Type: {0}".format("MORE" if ((hdrhex >> 18) & 0x01) else "BEGIN")) - print("Remain: {0}".format((hdrhex >> 10) & 0xff)) - print("Identifier: {0}".format((hdrhex >> 0) & 0x3ff)) - -if __name__ == "__main__": - main() diff --git a/libcsp/utils/cspsplit.py b/libcsp/utils/cspsplit.py deleted file mode 100644 index f4ed942f..00000000 --- a/libcsp/utils/cspsplit.py +++ /dev/null @@ -1,52 +0,0 @@ -#!/usr/bin/env python - -# Cubesat Space Protocol - A small network-layer protocol designed for Cubesats -# Copyright (C) 2012 GomSpace ApS (http://www.gomspace.com) -# Copyright (C) 2012 AAUSAT3 Project (http://aausat3.space.aau.dk) -# -# This library is free software; you can redistribute it and/or -# modify it under the terms of the GNU Lesser General Public -# License as published by the Free Software Foundation; either -# version 2.1 of the License, or (at your option) any later version. -# -# This library is distributed in the hope that it will be useful, -# but WITHOUT ANY WARRANTY; without even the implied warranty of -# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -# Lesser General Public License for more details. -# -# You should have received a copy of the GNU Lesser General Public -# License along with this library; if not, write to the Free Software -# Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA - -# Split CSP header in protocol fields - -import sys - -def usage(): - print("usage: cspsplit.py HEADER") - -def main(): - try: - hdr = sys.argv[1] - except: - usage() - sys.exit(-1) - - try: - hdrhex = int(hdr, 16) - except: - print("HEADER must be in hexadecimal format") - sys.exit(-1) - - print("Priotity: {0}".format((hdrhex >> 30) & 0x03)) - print("Source: {0}".format((hdrhex >> 25) & 0x1f)) - print("Destination: {0}".format((hdrhex >> 20) & 0x1f)) - print("Destination port: {0}".format((hdrhex >> 14) & 0x3f)) - print("Source port: {0}".format((hdrhex >> 8) & 0x3f)) - print("HMAC: {0}".format("Yes" if ((hdrhex >> 3) & 0x01) else "No")) - print("XTEA: {0}".format("Yes" if ((hdrhex >> 2) & 0x01) else "No")) - print("RDP: {0}".format("Yes" if ((hdrhex >> 1) & 0x01) else "No")) - print("CRC32: {0}".format("Yes" if ((hdrhex >> 0) & 0x01) else "No")) - -if __name__ == "__main__": - main() diff --git a/linux/CMakeLists.txt b/linux/CMakeLists.txt index da75446a..ebb3b6d6 100644 --- a/linux/CMakeLists.txt +++ b/linux/CMakeLists.txt @@ -3,4 +3,6 @@ add_subdirectory(i2c) add_subdirectory(csp) add_subdirectory(spi) add_subdirectory(uart) +add_subdirectory(utility) +add_subdirectory(boardtest) diff --git a/linux/csp/CspComIF.h b/linux/csp/CspComIF.h index 4855fbf8..4b8d323b 100644 --- a/linux/csp/CspComIF.h +++ b/linux/csp/CspComIF.h @@ -1,5 +1,5 @@ -#ifndef BSP_LINUX_COMIF_COOKIES_CSPCOMIF_H_ -#define BSP_LINUX_COMIF_COOKIES_CSPCOMIF_H_ +#ifndef LINUX_CSP_CSPCOMIF_H_ +#define LINUX_CSP_CSPCOMIF_H_ #include #include @@ -86,4 +86,4 @@ private: void initiatePingRequest(uint8_t cspAddress, uint16_t querySize); }; -#endif /* BSP_LINUX_COMIF_COOKIES_CSPCOMIF_H_ */ +#endif /* LINUX_CSP_CSPCOMIF_H_ */ diff --git a/linux/gpio/LinuxLibgpioIF.cpp b/linux/gpio/LinuxLibgpioIF.cpp index 04148467..cdf22a45 100644 --- a/linux/gpio/LinuxLibgpioIF.cpp +++ b/linux/gpio/LinuxLibgpioIF.cpp @@ -1,142 +1,191 @@ #include "LinuxLibgpioIF.h" +#include "GpioCookie.h" + #include +#include #include #include #include + LinuxLibgpioIF::LinuxLibgpioIF(object_id_t objectId) : SystemObject(objectId) { } LinuxLibgpioIF::~LinuxLibgpioIF() { } -ReturnValue_t LinuxLibgpioIF::initialize(CookieIF * cookie){ +ReturnValue_t LinuxLibgpioIF::addGpios(GpioCookie* gpioCookie) { ReturnValue_t result; - GpioMap mapToAdd; - - if(cookie == nullptr) { + if(gpioCookie == nullptr) { sif::error << "LinuxLibgpioIF::initialize: Invalid cookie" << std::endl; return RETURN_FAILED; } - GpioCookie* gpioCookie = dynamic_cast(cookie); - if(gpioCookie == nullptr) { - sif::error << "LinuxLibgpioIF: Invalid Gpio Cookie!" - << std::endl; - return RETURN_FAILED; - } - mapToAdd = gpioCookie->getGpioMap(); + GpioMap mapToAdd = gpioCookie->getGpioMap(); + /* Check whether this ID already exists in the map and remove duplicates */ result = checkForConflicts(mapToAdd); if (result != RETURN_OK){ return result; } - result = configureGpios(&mapToAdd); + result = configureGpios(mapToAdd); if (result != RETURN_OK) { return RETURN_FAILED; } - /* Register new GPIOs in gpioMap*/ + /* Register new GPIOs in gpioMap */ gpioMap.insert(mapToAdd.begin(), mapToAdd.end()); return RETURN_OK; } -ReturnValue_t LinuxLibgpioIF::configureGpios(GpioMap* mapToAdd) { - GpioMapIter mapToAddIter; +ReturnValue_t LinuxLibgpioIF::configureGpios(GpioMap& mapToAdd) { + for(auto& gpioConfig: mapToAdd) { + switch(gpioConfig.second->gpioType) { + case(gpio::GpioTypes::NONE): { + return GPIO_INVALID_INSTANCE; + } + case(gpio::GpioTypes::GPIOD_REGULAR): { + GpiodRegular* regularGpio = dynamic_cast(gpioConfig.second); + if(regularGpio == nullptr) { + return GPIO_INVALID_INSTANCE; + } + configureRegularGpio(gpioConfig.first, regularGpio); + break; + } + case(gpio::GpioTypes::CALLBACK): { + auto gpioCallback = dynamic_cast(gpioMapIter->second); + if(gpioCallback->callback == nullptr) { + return GPIO_INVALID_INSTANCE; + } + gpioCallback->callback(gpioMapIter->first, gpio::GpioOperation::READ, + gpioCallback->initValue, gpioCallback->callbackArgs); + } + } + } + return RETURN_OK; +} + +ReturnValue_t LinuxLibgpioIF::configureRegularGpio(gpioId_t gpioId, GpiodRegular *regularGpio) { std::string chipname; unsigned int lineNum; struct gpiod_chip *chip; gpio::Direction direction; std::string consumer; struct gpiod_line *lineHandle; - int result; + int result = 0; - mapToAddIter = mapToAdd->begin(); - for (; mapToAddIter != mapToAdd->end(); mapToAddIter++) { - - chipname = mapToAddIter->second.chipname; - chip = gpiod_chip_open_by_name(chipname.c_str()); - if (!chip) { - sif::error << "LinuxLibgpioIF::configureGpios: Failed to open chip " - << chipname << ". Gpio ID: " << mapToAddIter->first << std::endl; - return RETURN_FAILED; - } - - lineNum = mapToAddIter->second.lineNum; - lineHandle = gpiod_chip_get_line(chip, lineNum); - if (!lineHandle) { - sif::error << "LinuxLibgpioIF::configureGpios: Failed to open line for GPIO with id " - << mapToAddIter->first << std::endl; - gpiod_chip_close(chip); - return RETURN_FAILED; - } - - direction = mapToAddIter->second.direction; - consumer = mapToAddIter->second.consumer; - /* Configure direction and add a description to the GPIO */ - switch (direction) { - case gpio::OUT: - result = gpiod_line_request_output(lineHandle, consumer.c_str(), - mapToAddIter->second.initValue); - if (result < 0) { - sif::error << "LinuxLibgpioIF::configureGpios: Failed to request line " - << lineNum << " from GPIO instance with ID: " << mapToAddIter->first - << std::endl; - gpiod_line_release(lineHandle); - return RETURN_FAILED; - } - break; - case gpio::IN: - result = gpiod_line_request_input(lineHandle, consumer.c_str()); - if (result < 0) { - sif::error << "LinuxLibgpioIF::configureGpios: Failed to request line " - << lineNum << " from GPIO instance with ID: " << mapToAddIter->first - << std::endl; - gpiod_line_release(lineHandle); - return RETURN_FAILED; - } - break; - default: - sif::error << "LinuxLibgpioIF::configureGpios: Invalid direction specified" - << std::endl; - return RETURN_FAILED; - } - /** - * Write line handle to GPIO configuration instance so it can later be used to set or - * read states of GPIOs. - */ - mapToAddIter->second.lineHandle = lineHandle; - } - return RETURN_OK; -} - -ReturnValue_t LinuxLibgpioIF::pullHigh(gpioId_t gpioId){ - return driveGpio(gpioId, 1); -} - -ReturnValue_t LinuxLibgpioIF::pullLow(gpioId_t gpioId){ - return driveGpio(gpioId, 0); -} - -ReturnValue_t LinuxLibgpioIF::driveGpio(gpioId_t gpioId, - unsigned int logiclevel) { - int result; - struct gpiod_line *lineHandle; - - gpioMapIter = gpioMap.find(gpioId); - if (gpioMapIter == gpioMap.end()){ - sif::debug << "LinuxLibgpioIF::driveGpio: Unknown gpio id " << gpioId << std::endl; + chipname = regularGpio->chipname; + chip = gpiod_chip_open_by_name(chipname.c_str()); + if (!chip) { + sif::error << "LinuxLibgpioIF::configureGpios: Failed to open chip " + << chipname << ". Gpio ID: " << gpioId << std::endl; return RETURN_FAILED; } - lineHandle = gpioMapIter->second.lineHandle; - result = gpiod_line_set_value(lineHandle, logiclevel); + lineNum = regularGpio->lineNum; + lineHandle = gpiod_chip_get_line(chip, lineNum); + if (!lineHandle) { + sif::error << "LinuxLibgpioIF::configureGpios: Failed to open line for GPIO with id " + << gpioId << std::endl; + gpiod_chip_close(chip); + return RETURN_FAILED; + } + + direction = regularGpio->direction; + consumer = regularGpio->consumer; + /* Configure direction and add a description to the GPIO */ + switch (direction) { + case(gpio::OUT): { + result = gpiod_line_request_output(lineHandle, consumer.c_str(), + regularGpio->initValue); + if (result < 0) { + sif::error << "LinuxLibgpioIF::configureGpios: Failed to request line " << lineNum << + " from GPIO instance with ID: " << gpioId << std::endl; + gpiod_line_release(lineHandle); + return RETURN_FAILED; + } + break; + } + case(gpio::IN): { + result = gpiod_line_request_input(lineHandle, consumer.c_str()); + if (result < 0) { + sif::error << "LinuxLibgpioIF::configureGpios: Failed to request line " + << lineNum << " from GPIO instance with ID: " << gpioId << std::endl; + gpiod_line_release(lineHandle); + return RETURN_FAILED; + } + break; + } + default: { + sif::error << "LinuxLibgpioIF::configureGpios: Invalid direction specified" + << std::endl; + return GPIO_INVALID_INSTANCE; + } + + } + /** + * Write line handle to GPIO configuration instance so it can later be used to set or + * read states of GPIOs. + */ + regularGpio->lineHandle = lineHandle; + return RETURN_OK; +} + +ReturnValue_t LinuxLibgpioIF::pullHigh(gpioId_t gpioId) { + gpioMapIter = gpioMap.find(gpioId); + if (gpioMapIter == gpioMap.end()) { + sif::warning << "LinuxLibgpioIF::driveGpio: Unknown GPIOD ID " << gpioId << std::endl; + return UNKNOWN_GPIO_ID; + } + + if(gpioMapIter->second->gpioType == gpio::GpioTypes::GPIOD_REGULAR) { + return driveGpio(gpioId, dynamic_cast(gpioMapIter->second), 1); + } + else { + auto gpioCallback = dynamic_cast(gpioMapIter->second); + if(gpioCallback->callback == nullptr) { + return GPIO_INVALID_INSTANCE; + } + gpioCallback->callback(gpioMapIter->first, gpio::GpioOperation::WRITE, + 1, gpioCallback->callbackArgs); + } + return GPIO_TYPE_FAILURE; +} + +ReturnValue_t LinuxLibgpioIF::pullLow(gpioId_t gpioId) { + gpioMapIter = gpioMap.find(gpioId); + if (gpioMapIter == gpioMap.end()) { + sif::warning << "LinuxLibgpioIF::driveGpio: Unknown GPIOD ID " << gpioId << std::endl; + return UNKNOWN_GPIO_ID; + } + + if(gpioMapIter->second->gpioType == gpio::GpioTypes::GPIOD_REGULAR) { + return driveGpio(gpioId, dynamic_cast(gpioMapIter->second), 0); + } + else { + auto gpioCallback = dynamic_cast(gpioMapIter->second); + if(gpioCallback->callback == nullptr) { + return GPIO_INVALID_INSTANCE; + } + gpioCallback->callback(gpioMapIter->first, gpio::GpioOperation::WRITE, + 0, gpioCallback->callbackArgs); + } + return GPIO_TYPE_FAILURE; +} + +ReturnValue_t LinuxLibgpioIF::driveGpio(gpioId_t gpioId, + GpiodRegular* regularGpio, unsigned int logicLevel) { + if(regularGpio == nullptr) { + return GPIO_TYPE_FAILURE; + } + + int result = gpiod_line_set_value(regularGpio->lineHandle, logicLevel); if (result < 0) { - sif::error << "LinuxLibgpioIF::driveGpio: Failed to pull GPIO with ID " - << gpioId << " to logic level " << logiclevel << std::endl; + sif::warning << "LinuxLibgpioIF::driveGpio: Failed to pull GPIO with ID " << gpioId << + " to logic level " << logicLevel << std::endl; return DRIVE_GPIO_FAILURE; } @@ -144,38 +193,107 @@ ReturnValue_t LinuxLibgpioIF::driveGpio(gpioId_t gpioId, } ReturnValue_t LinuxLibgpioIF::readGpio(gpioId_t gpioId, int* gpioState) { - struct gpiod_line *lineHandle; - gpioMapIter = gpioMap.find(gpioId); if (gpioMapIter == gpioMap.end()){ - sif::debug << "LinuxLibgpioIF::readGpio: Unknown gpio id " << gpioId << std::endl; - return RETURN_FAILED; + sif::warning << "LinuxLibgpioIF::readGpio: Unknown GPIOD ID " << gpioId << std::endl; + return UNKNOWN_GPIO_ID; + } + + if(gpioMapIter->second->gpioType == gpio::GpioTypes::GPIOD_REGULAR) { + GpiodRegular* regularGpio = dynamic_cast(gpioMapIter->second); + if(regularGpio == nullptr) { + return GPIO_TYPE_FAILURE; + } + *gpioState = gpiod_line_get_value(regularGpio->lineHandle); + } + else { + } - lineHandle = gpioMapIter->second.lineHandle; - *gpioState = gpiod_line_get_value(lineHandle); return RETURN_OK; } -ReturnValue_t LinuxLibgpioIF::checkForConflicts(GpioMap mapToAdd){ - gpioId_t gpioId; - GpioMapIter mapToAddIter = mapToAdd.begin(); - for(; mapToAddIter != mapToAdd.end(); mapToAddIter++){ - gpioId = mapToAddIter->first; - gpioMapIter = gpioMap.find(gpioId); - if(gpioMapIter != mapToAdd.end()){ - /* An entry for this GPIO already exists. Check if configuration - * of direction is equivalent */ - if (mapToAddIter->second.direction != gpioMapIter->second.direction){ - sif::error << "LinuxLibgpioIF::checkForConflicts: Detected conflict " - << "for GPIO " << mapToAddIter->first << std::endl; - return RETURN_OK; +ReturnValue_t LinuxLibgpioIF::checkForConflicts(GpioMap& mapToAdd){ + ReturnValue_t status = HasReturnvaluesIF::RETURN_OK; + ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + for(auto& gpioConfig: mapToAdd) { + switch(gpioConfig.second->gpioType) { + case(gpio::GpioTypes::GPIOD_REGULAR): { + auto regularGpio = dynamic_cast(gpioConfig.second); + if(regularGpio == nullptr) { + return GPIO_TYPE_FAILURE; } - /* Remove element from map to add because a entry for this GPIO - * already exists */ - mapToAdd.erase(mapToAddIter); + /* Check for conflicts and remove duplicates if necessary */ + result = checkForConflictsRegularGpio(gpioConfig.first, regularGpio, mapToAdd); + if(result != HasReturnvaluesIF::RETURN_OK) { + status = result; + } + break; + } + case(gpio::GpioTypes::CALLBACK): { + auto callbackGpio = dynamic_cast(gpioConfig.second); + if(callbackGpio == nullptr) { + return GPIO_TYPE_FAILURE; + } + /* Check for conflicts and remove duplicates if necessary */ + result = checkForConflictsCallbackGpio(gpioConfig.first, callbackGpio, mapToAdd); + if(result != HasReturnvaluesIF::RETURN_OK) { + status = result; + } + break; + } + default: { + + } } } - return RETURN_OK; + return status; +} + + +ReturnValue_t LinuxLibgpioIF::checkForConflictsRegularGpio(gpioId_t gpioIdToCheck, + GpiodRegular* gpioToCheck, GpioMap& mapToAdd) { + /* Cross check with private map */ + gpioMapIter = gpioMap.find(gpioIdToCheck); + if(gpioMapIter != gpioMap.end()) { + if(gpioMapIter->second->gpioType != gpio::GpioTypes::GPIOD_REGULAR) { + sif::warning << "LinuxLibgpioIF::checkForConflicts: ID already exists for different " + "GPIO type" << gpioIdToCheck << ". Removing duplicate." << std::endl; + mapToAdd.erase(gpioIdToCheck); + return HasReturnvaluesIF::RETURN_OK; + } + auto ownRegularGpio = dynamic_cast(gpioMapIter->second); + if(ownRegularGpio == nullptr) { + return GPIO_TYPE_FAILURE; + } + + /* Remove element from map to add because a entry for this GPIO + already exists */ + sif::warning << "LinuxLibgpioIF::checkForConflictsRegularGpio: Duplicate GPIO definition" + << " detected. Duplicate will be removed from map to add." << std::endl; + mapToAdd.erase(gpioIdToCheck); + } + return HasReturnvaluesIF::RETURN_OK; +} + +ReturnValue_t LinuxLibgpioIF::checkForConflictsCallbackGpio(gpioId_t gpioIdToCheck, + GpioCallback *callbackGpio, GpioMap& mapToAdd) { + /* Cross check with private map */ + gpioMapIter = gpioMap.find(gpioIdToCheck); + if(gpioMapIter != gpioMap.end()) { + if(gpioMapIter->second->gpioType != gpio::GpioTypes::CALLBACK) { + sif::warning << "LinuxLibgpioIF::checkForConflicts: ID already exists for different " + "GPIO type" << gpioIdToCheck << ". Removing duplicate." << std::endl; + mapToAdd.erase(gpioIdToCheck); + return HasReturnvaluesIF::RETURN_OK; + } + + /* Remove element from map to add because a entry for this GPIO + already exists */ + sif::warning << "LinuxLibgpioIF::checkForConflictsRegularGpio: Duplicate GPIO definition" + << " detected. Duplicate will be removed from map to add." << std::endl; + mapToAdd.erase(gpioIdToCheck); + } + return HasReturnvaluesIF::RETURN_OK; } diff --git a/linux/i2c/I2cComIF.cpp b/linux/i2c/I2cComIF.cpp index 5b11f231..ed50293d 100644 --- a/linux/i2c/I2cComIF.cpp +++ b/linux/i2c/I2cComIF.cpp @@ -1,12 +1,13 @@ #include "I2cComIF.h" #include - #include #include #include #include #include -#include +#include + +#include I2cComIF::I2cComIF(object_id_t objectId): SystemObject(objectId){ @@ -14,186 +15,182 @@ I2cComIF::I2cComIF(object_id_t objectId): SystemObject(objectId){ I2cComIF::~I2cComIF() {} -ReturnValue_t I2cComIF::initializeInterface(CookieIF * cookie) { +ReturnValue_t I2cComIF::initializeInterface(CookieIF* cookie) { - address_t i2cAddress; - std::string deviceFile; + address_t i2cAddress; + std::string deviceFile; - if(cookie == nullptr) { - return NULLPOINTER; - } - I2cCookie* i2cCookie = dynamic_cast(cookie); - if(i2cCookie == nullptr) { - sif::error << "I2cComIF: Invalid I2C Cookie!" - << std::endl; - return NULLPOINTER; - } + if(cookie == nullptr) { + sif::error << "I2cComIF::initializeInterface: Invalid cookie!" << std::endl; + return NULLPOINTER; + } + I2cCookie* i2cCookie = dynamic_cast(cookie); + if(i2cCookie == nullptr) { + sif::error << "I2cComIF::initializeInterface: Invalid I2C cookie!" << std::endl; + return NULLPOINTER; + } - i2cAddress = i2cCookie->getAddress(); + i2cAddress = i2cCookie->getAddress(); - i2cDeviceMapIter = i2cDeviceMap.find(i2cAddress); - if(i2cDeviceMapIter == i2cDeviceMap.end()) { - size_t maxReplyLen = i2cCookie->getMaxReplyLen(); - I2cInstance_t i2cInstance = {std::vector(maxReplyLen), 0}; - std::pair status = i2cDeviceMap.emplace(i2cAddress, i2cInstance); - if (status.second == false) { - sif::error << "I2cComIF::initializeInterface: Failed to insert " - << "device with address " << i2cAddress << "to I2C device " - << "map" << std::endl; - return HasReturnvaluesIF::RETURN_FAILED; - } - } - else { - sif::error << "I2cComIF: Device with address " << i2cAddress - << "already in use" << std::endl; - } + i2cDeviceMapIter = i2cDeviceMap.find(i2cAddress); + if(i2cDeviceMapIter == i2cDeviceMap.end()) { + size_t maxReplyLen = i2cCookie->getMaxReplyLen(); + I2cInstance_t i2cInstance = {std::vector(maxReplyLen), 0}; + auto statusPair = i2cDeviceMap.emplace(i2cAddress, i2cInstance); + if (not statusPair.second) { + sif::error << "I2cComIF::initializeInterface: Failed to insert device with address " << + i2cAddress << "to I2C device " << "map" << std::endl; + return HasReturnvaluesIF::RETURN_FAILED; + } + return HasReturnvaluesIF::RETURN_OK; + } - return HasReturnvaluesIF::RETURN_OK; + sif::error << "I2cComIF::initializeInterface: Device with address " << i2cAddress << + "already in use" << std::endl; + return HasReturnvaluesIF::RETURN_FAILED; } ReturnValue_t I2cComIF::sendMessage(CookieIF *cookie, const uint8_t *sendData, size_t sendLen) { - ReturnValue_t result; - int fd; - std::string deviceFile; + ReturnValue_t result; + int fd; + std::string deviceFile; - if(sendData == nullptr) { - sif::error << "I2cComIF::sendMessage: Send Data is nullptr" - << std::endl; - return HasReturnvaluesIF::RETURN_FAILED; - } + if(sendData == nullptr) { + sif::error << "I2cComIF::sendMessage: Send Data is nullptr" + << std::endl; + return HasReturnvaluesIF::RETURN_FAILED; + } - if(sendLen == 0) { - return HasReturnvaluesIF::RETURN_OK; - } + if(sendLen == 0) { + return HasReturnvaluesIF::RETURN_OK; + } - I2cCookie* i2cCookie = dynamic_cast(cookie); - if(i2cCookie == nullptr) { - sif::error << "I2cComIF::sendMessasge: Invalid I2C Cookie!" - << std::endl; - return NULLPOINTER; - } + I2cCookie* i2cCookie = dynamic_cast(cookie); + if(i2cCookie == nullptr) { + sif::error << "I2cComIF::sendMessage: Invalid I2C Cookie!" << std::endl; + return NULLPOINTER; + } - address_t i2cAddress = i2cCookie->getAddress(); - i2cDeviceMapIter = i2cDeviceMap.find(i2cAddress); - if (i2cDeviceMapIter == i2cDeviceMap.end()) { - sif::error << "I2cComIF::sendMessage: i2cAddress of Cookie not " - << "registered in i2cDeviceMap" << std::endl; - return HasReturnvaluesIF::RETURN_FAILED; - } + address_t i2cAddress = i2cCookie->getAddress(); + i2cDeviceMapIter = i2cDeviceMap.find(i2cAddress); + if (i2cDeviceMapIter == i2cDeviceMap.end()) { + sif::error << "I2cComIF::sendMessage: i2cAddress of Cookie not " + << "registered in i2cDeviceMap" << std::endl; + return HasReturnvaluesIF::RETURN_FAILED; + } - deviceFile = i2cCookie->getDeviceFile(); - result = openDevice(deviceFile, i2cAddress, &fd); - if (result != HasReturnvaluesIF::RETURN_OK){ - return result; - } + deviceFile = i2cCookie->getDeviceFile(); + utility::UnixFileHelper fileHelper(deviceFile, &fd, O_RDWR, "I2cComIF::sendMessage"); + if(fileHelper.getOpenResult() != HasReturnvaluesIF::RETURN_OK) { + return fileHelper.getOpenResult(); + } + result = openDevice(deviceFile, i2cAddress, &fd); + if (result != HasReturnvaluesIF::RETURN_OK){ + return result; + } - if (write(fd, sendData, sendLen) != (int)sendLen) { - sif::error << "I2cComIF::sendMessage: Failed to send data to I2C " - "device with error code " << errno << ". Error description: " - << strerror(errno) << std::endl; - close(fd); - return HasReturnvaluesIF::RETURN_FAILED; - } - close(fd); - return HasReturnvaluesIF::RETURN_OK; + if (write(fd, sendData, sendLen) != (int)sendLen) { + sif::error << "I2cComIF::sendMessage: Failed to send data to I2C " + "device with error code " << errno << ". Error description: " + << strerror(errno) << std::endl; + return HasReturnvaluesIF::RETURN_FAILED; + } + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t I2cComIF::getSendSuccess(CookieIF *cookie) { - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t I2cComIF::requestReceiveMessage(CookieIF *cookie, - size_t requestLen) { + size_t requestLen) { + ReturnValue_t result; + int fd; + std::string deviceFile; - ReturnValue_t result; - int fd; - std::string deviceFile; + if (requestLen == 0) { + return HasReturnvaluesIF::RETURN_OK; + } - if (requestLen == 0) { - return HasReturnvaluesIF::RETURN_OK; - } + I2cCookie* i2cCookie = dynamic_cast(cookie); + if(i2cCookie == nullptr) { + sif::error << "I2cComIF::requestReceiveMessage: Invalid I2C Cookie!" << std::endl; + i2cDeviceMapIter->second.replyLen = 0; + return NULLPOINTER; + } - I2cCookie* i2cCookie = dynamic_cast(cookie); - if(i2cCookie == nullptr) { - sif::error << "I2cComIF::requestReceiveMessage: Invalid I2C Cookie!" - << std::endl; - i2cDeviceMapIter->second.replyLen = 0; - return NULLPOINTER; - } + address_t i2cAddress = i2cCookie->getAddress(); + i2cDeviceMapIter = i2cDeviceMap.find(i2cAddress); + if (i2cDeviceMapIter == i2cDeviceMap.end()) { + sif::error << "I2cComIF::requestReceiveMessage: i2cAddress of Cookie not " + << "registered in i2cDeviceMap" << std::endl; + i2cDeviceMapIter->second.replyLen = 0; + return HasReturnvaluesIF::RETURN_FAILED; + } - address_t i2cAddress = i2cCookie->getAddress(); - i2cDeviceMapIter = i2cDeviceMap.find(i2cAddress); - if (i2cDeviceMapIter == i2cDeviceMap.end()) { - sif::error << "I2cComIF::requestReceiveMessage: i2cAddress of Cookie not " - << "registered in i2cDeviceMap" << std::endl; - i2cDeviceMapIter->second.replyLen = 0; - return HasReturnvaluesIF::RETURN_FAILED; - } + deviceFile = i2cCookie->getDeviceFile(); + utility::UnixFileHelper fileHelper(deviceFile, &fd, O_RDWR, "I2cComIF::requestReceiveMessage"); + if(fileHelper.getOpenResult() != HasReturnvaluesIF::RETURN_OK) { + return fileHelper.getOpenResult(); + } + result = openDevice(deviceFile, i2cAddress, &fd); + if (result != HasReturnvaluesIF::RETURN_OK){ + i2cDeviceMapIter->second.replyLen = 0; + return result; + } - deviceFile = i2cCookie->getDeviceFile(); - result = openDevice(deviceFile, i2cAddress, &fd); - if (result != HasReturnvaluesIF::RETURN_OK){ - i2cDeviceMapIter->second.replyLen = 0; - return result; - } + uint8_t* replyBuffer = i2cDeviceMapIter->second.replyBuffer.data(); - uint8_t* replyBuffer = i2cDeviceMapIter->second.replyBuffer.data(); + if (read(fd, replyBuffer, requestLen) != static_cast(requestLen)) { + sif::error << "I2cComIF::requestReceiveMessage: Reading from I2C " + << "device failed with error code " << errno <<". Description" + << " of error: " << strerror(errno) << std::endl; + i2cDeviceMapIter->second.replyLen = 0; + return HasReturnvaluesIF::RETURN_FAILED; + } - if (read(fd, replyBuffer, requestLen) != (int)requestLen) { - sif::error << "I2cComIF::requestReceiveMessage: Reading from I2C " - << "device failed with error code " << errno <<". Description" - << " of error: " << strerror(errno) << std::endl; - close(fd); - i2cDeviceMapIter->second.replyLen = 0; - return HasReturnvaluesIF::RETURN_FAILED; - } - - i2cDeviceMapIter->second.replyLen = requestLen; - - close(fd); - - return HasReturnvaluesIF::RETURN_OK; + i2cDeviceMapIter->second.replyLen = requestLen; + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t I2cComIF::readReceivedMessage(CookieIF *cookie, - uint8_t **buffer, size_t* size) { - I2cCookie* i2cCookie = dynamic_cast(cookie); - if(i2cCookie == nullptr) { - sif::error << "I2cComIF::readReceivedMessage: Invalid I2C Cookie!" - << std::endl; - return NULLPOINTER; - } + uint8_t **buffer, size_t* size) { + I2cCookie* i2cCookie = dynamic_cast(cookie); + if(i2cCookie == nullptr) { + sif::error << "I2cComIF::readReceivedMessage: Invalid I2C Cookie!" << std::endl; + return NULLPOINTER; + } - address_t i2cAddress = i2cCookie->getAddress(); - i2cDeviceMapIter = i2cDeviceMap.find(i2cAddress); - if (i2cDeviceMapIter == i2cDeviceMap.end()) { - sif::error << "I2cComIF::readReceivedMessage: i2cAddress of Cookie not " - << "found in i2cDeviceMap" << std::endl; - return HasReturnvaluesIF::RETURN_FAILED; - } - *buffer = i2cDeviceMapIter->second.replyBuffer.data(); - *size = i2cDeviceMapIter->second.replyLen; + address_t i2cAddress = i2cCookie->getAddress(); + i2cDeviceMapIter = i2cDeviceMap.find(i2cAddress); + if (i2cDeviceMapIter == i2cDeviceMap.end()) { + sif::error << "I2cComIF::readReceivedMessage: i2cAddress of Cookie not " + << "found in i2cDeviceMap" << std::endl; + return HasReturnvaluesIF::RETURN_FAILED; + } + *buffer = i2cDeviceMapIter->second.replyBuffer.data(); + *size = i2cDeviceMapIter->second.replyLen; - return HasReturnvaluesIF::RETURN_OK; + return HasReturnvaluesIF::RETURN_OK; } ReturnValue_t I2cComIF::openDevice(std::string deviceFile, - address_t i2cAddress, int* fileDescriptor) { - *fileDescriptor = open(deviceFile.c_str(), O_RDWR); - if (*fileDescriptor < 0) { - sif::error << "I2cComIF: Opening i2c device failed with error code " - << errno << ". Error description: " << strerror(errno) - << std::endl; - return HasReturnvaluesIF::RETURN_FAILED; - } + address_t i2cAddress, int* fileDescriptor) { - if (ioctl(*fileDescriptor, I2C_SLAVE, i2cAddress) < 0) { - sif::error << "I2cComIF: Specifying target device failed with error " - << "code " << errno << ". Error description " - << strerror(errno) << std::endl; - return HasReturnvaluesIF::RETURN_FAILED; - } - return HasReturnvaluesIF::RETURN_OK; + if (ioctl(*fileDescriptor, I2C_SLAVE, i2cAddress) < 0) { +#if FSFW_VERBOSE_LEVEL >= 1 +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::warning << "I2cComIF: Specifying target device failed with error code " << errno << "." + << std::endl; + sif::warning << "Error description " << strerror(errno) << std::endl; +#else + sif::printWarning("I2cComIF: Specifying target device failed with error code %d.\n"); + sif::printWarning("Error description: %s\n", strerror(errno)); +#endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ +#endif /* FSFW_VERBOSE_LEVEL >= 1 */ + return HasReturnvaluesIF::RETURN_FAILED; + } + return HasReturnvaluesIF::RETURN_OK; } diff --git a/linux/i2c/I2cCookie.h b/linux/i2c/I2cCookie.h index 483ed19c..888a2b12 100644 --- a/linux/i2c/I2cCookie.h +++ b/linux/i2c/I2cCookie.h @@ -1,5 +1,5 @@ -#ifndef SAM9G20_COMIF_COOKIES_I2C_COOKIE_H_ -#define SAM9G20_COMIF_COOKIES_I2C_COOKIE_H_ +#ifndef LINUX_I2C_I2CCOOKIE_H_ +#define LINUX_I2C_I2CCOOKIE_H_ #include #include @@ -35,4 +35,4 @@ private: std::string deviceFile; }; -#endif +#endif /* LINUX_I2C_I2CCOOKIE_H_ */ diff --git a/mission/devices/CMakeLists.txt b/mission/devices/CMakeLists.txt index a5093a8c..906b172b 100644 --- a/mission/devices/CMakeLists.txt +++ b/mission/devices/CMakeLists.txt @@ -10,8 +10,6 @@ target_sources(${TARGET_NAME} PUBLIC PDU1Handler.cpp PDU2Handler.cpp ACUHandler.cpp - HeaterHandler.cpp - SolarArrayDeploymentHandler.cpp SyrlinksHkHandler.cpp ) diff --git a/mission/devices/HeaterHandler.cpp b/mission/devices/HeaterHandler.cpp deleted file mode 100644 index a810e2a6..00000000 --- a/mission/devices/HeaterHandler.cpp +++ /dev/null @@ -1,355 +0,0 @@ -#include -#include -#include -#include - -HeaterHandler::HeaterHandler(object_id_t setObjectId_, object_id_t gpioDriverId_, - CookieIF * gpioCookie_, object_id_t mainLineSwitcherObjectId_, uint8_t mainLineSwitch_) : - SystemObject(setObjectId_), gpioDriverId(gpioDriverId_), gpioCookie(gpioCookie_), mainLineSwitcherObjectId( - mainLineSwitcherObjectId_), mainLineSwitch(mainLineSwitch_), actionHelper(this, - nullptr) { - commandQueue = QueueFactory::instance()->createMessageQueue(cmdQueueSize, - MessageQueueMessage::MAX_MESSAGE_SIZE); -} - -HeaterHandler::~HeaterHandler() { -} - -ReturnValue_t HeaterHandler::performOperation(uint8_t operationCode) { - - if (operationCode == DeviceHandlerIF::PERFORM_OPERATION) { - readCommandQueue(); - handleActiveCommands(); - return RETURN_OK; - } - return RETURN_OK; -} - -ReturnValue_t HeaterHandler::initialize() { - ReturnValue_t result = SystemObject::initialize(); - if (result != RETURN_OK) { - return ObjectManagerIF::CHILD_INIT_FAILED; - } - - result = initializeHeaterMap(); - if (result != RETURN_OK) { - return ObjectManagerIF::CHILD_INIT_FAILED; - } - - gpioInterface = objectManager->get(gpioDriverId); - if (gpioInterface == nullptr) { - sif::error << "HeaterHandler::initialize: Invalid Gpio interface." << std::endl; - return ObjectManagerIF::CHILD_INIT_FAILED; - } - - result = gpioInterface->initialize(gpioCookie); - if (result != RETURN_OK) { - sif::error << "HeaterHandler::initialize: Failed to initialize Gpio interface" << std::endl; - return ObjectManagerIF::CHILD_INIT_FAILED; - } - - IPCStore = objectManager->get(objects::IPC_STORE); - if (IPCStore == nullptr) { - sif::error << "HeaterHandler::initialize: IPC store not set up in factory." << std::endl; - return ObjectManagerIF::CHILD_INIT_FAILED; - } - - if(mainLineSwitcherObjectId != objects::NO_OBJECT) { - mainLineSwitcher = objectManager->get(mainLineSwitcherObjectId); - if (mainLineSwitcher == nullptr) { - sif::error << "HeaterHandler::initialize: Main line switcher failed to fetch object" - << "from object ID." << std::endl; - return ObjectManagerIF::CHILD_INIT_FAILED; - } - } - - result = actionHelper.initialize(commandQueue); - if (result != RETURN_OK) { - return ObjectManagerIF::CHILD_INIT_FAILED; - } - - return RETURN_OK; -} - -ReturnValue_t HeaterHandler::initializeHeaterMap(){ - HeaterCommandInfo_t heaterCommandInfo; - for(switchNr_t switchNr = 0; switchNr < heaterSwitches::NUMBER_OF_SWITCHES; switchNr++) { - std::pair status = heaterMap.emplace(switchNr, heaterCommandInfo); - if (status.second == false) { - sif::error << "HeaterHandler::initializeHeaterMap: Failed to initialize heater map" - << std::endl; - return RETURN_FAILED; - } - } - return RETURN_OK; -} - -void HeaterHandler::setInitialSwitchStates() { - for (switchNr_t switchNr = 0; switchNr < heaterSwitches::NUMBER_OF_SWITCHES; switchNr++) { - switchStates[switchNr] = OFF; - } -} - -void HeaterHandler::readCommandQueue() { - CommandMessage command; - ReturnValue_t result = commandQueue->receiveMessage(&command); - if (result != RETURN_OK) { - return; - } - - result = actionHelper.handleActionMessage(&command); - if (result == RETURN_OK) { - return; - } -} - -ReturnValue_t HeaterHandler::executeAction(ActionId_t actionId, - MessageQueueId_t commandedBy, const uint8_t* data, size_t size) { - ReturnValue_t result; - if (actionId != SWITCH_HEATER) { - result = COMMAND_NOT_SUPPORTED; - } else { - switchNr_t switchNr = *data; - HeaterMapIter heaterMapIter = heaterMap.find(switchNr); - if (heaterMapIter != heaterMap.end()) { - if (heaterMapIter->second.active) { - return COMMAND_ALREADY_WAITING; - } - heaterMapIter->second.action = *(data + 1); - heaterMapIter->second.active = true; - heaterMapIter->second.replyQueue = commandedBy; - } - else { - sif::error << "HeaterHandler::executeAction: Invalid switchNr" << std::endl; - return INVALID_SWITCH_NR; - } - result = RETURN_OK; - } - return result; -} - - -void HeaterHandler::sendSwitchCommand(uint8_t switchNr, - ReturnValue_t onOff) const { - - ReturnValue_t result; - store_address_t storeAddress; - uint8_t commandData[2]; - - switch(onOff) { - case PowerSwitchIF::SWITCH_ON: - commandData[0] = switchNr; - commandData[1] = SET_SWITCH_ON; - break; - case PowerSwitchIF::SWITCH_OFF: - commandData[0] = switchNr; - commandData[1] = SET_SWITCH_OFF; - break; - default: - sif::error << "HeaterHandler::sendSwitchCommand: Invalid switch request" - << std::endl; - break; - } - - result = IPCStore->addData(&storeAddress, commandData, sizeof(commandData)); - if (result == RETURN_OK) { - CommandMessage message; - ActionMessage::setCommand(&message, SWITCH_HEATER, storeAddress); - /* Send heater command to own command queue */ - result = commandQueue->sendMessage(commandQueue->getId(), &message, 0); - if (result != RETURN_OK) { - sif::debug << "HeaterHandler::sendSwitchCommand: Failed to send switch" - << "message" << std::endl; - } - } -} - -void HeaterHandler::handleActiveCommands(){ - - HeaterMapIter heaterMapIter = heaterMap.begin(); - for (; heaterMapIter != heaterMap.end(); heaterMapIter++) { - if (heaterMapIter->second.active) { - switch(heaterMapIter->second.action) { - case SET_SWITCH_ON: - handleSwitchOnCommand(heaterMapIter); - break; - case SET_SWITCH_OFF: - handleSwitchOffCommand(heaterMapIter); - break; - default: - sif::error << "HeaterHandler::handleActiveCommands: Invalid action commanded" - << std::endl; - break; - } - } - } -} - -void HeaterHandler::handleSwitchOnCommand(HeaterMapIter heaterMapIter) { - - ReturnValue_t result = RETURN_OK; - switchNr_t switchNr; - - /* Check if command waits for main switch being set on and whether the timeout has expired */ - if (heaterMapIter->second.waitMainSwitchOn - && heaterMapIter->second.mainSwitchCountdown.hasTimedOut()) { - //TODO - This requires the initiation of an FDIR procedure - triggerEvent(MAIN_SWITCH_TIMEOUT); - sif::error << "HeaterHandler::handleSwitchOnCommand: Main switch setting on timeout" - << std::endl; - heaterMapIter->second.active = false; - heaterMapIter->second.waitMainSwitchOn = false; - if (heaterMapIter->second.replyQueue != commandQueue->getId()) { - actionHelper.finish(heaterMapIter->second.replyQueue, heaterMapIter->second.action, - MAIN_SWITCH_SET_TIMEOUT ); - } - return; - } - - switchNr = heaterMapIter->first; - /* Check state of main line switch */ - ReturnValue_t mainSwitchState = mainLineSwitcher->getSwitchState(mainLineSwitch); - if (mainSwitchState == PowerSwitchIF::SWITCH_ON) { - if (!checkSwitchState(switchNr)) { - gpioId_t gpioId = getGpioIdFromSwitchNr(switchNr); - result = gpioInterface->pullHigh(gpioId); - if (result != RETURN_OK) { - sif::error << "HeaterHandler::handleSwitchOnCommand: Failed to pull gpio with id " - << gpioId << " high" << std::endl; - triggerEvent(GPIO_PULL_HIGH_FAILED, result); - } - else { - switchStates[switchNr] = ON; - } - } - else { - triggerEvent(SWITCH_ALREADY_ON, switchNr); - } - /* There is no need to send action finish replies if the sender was the - * HeaterHandler itself. */ - if (heaterMapIter->second.replyQueue != commandQueue->getId()) { - actionHelper.finish(heaterMapIter->second.replyQueue, - heaterMapIter->second.action, result); - } - heaterMapIter->second.active = false; - heaterMapIter->second.waitMainSwitchOn = false; - } - else if (mainSwitchState == PowerSwitchIF::SWITCH_OFF - && heaterMapIter->second.waitMainSwitchOn) { - /* Just waiting for the main switch being set on */ - return; - } - else if (mainSwitchState == PowerSwitchIF::SWITCH_OFF) { - mainLineSwitcher->sendSwitchCommand(mainLineSwitch, - PowerSwitchIF::SWITCH_ON); - heaterMapIter->second.mainSwitchCountdown.setTimeout(mainLineSwitcher->getSwitchDelayMs()); - heaterMapIter->second.waitMainSwitchOn = true; - } - else { - sif::debug << "HeaterHandler::handleActiveCommands: Failed to get state of" - << " main line switch" << std::endl; - if (heaterMapIter->second.replyQueue != commandQueue->getId()) { - actionHelper.finish(heaterMapIter->second.replyQueue, - heaterMapIter->second.action, mainSwitchState); - } - heaterMapIter->second.active = false; - } -} - -void HeaterHandler::handleSwitchOffCommand(HeaterMapIter heaterMapIter) { - ReturnValue_t result = RETURN_OK; - switchNr_t switchNr = heaterMapIter->first; - /* Check whether switch is already off */ - if (checkSwitchState(switchNr)) { - gpioId_t gpioId = getGpioIdFromSwitchNr(switchNr); - result = gpioInterface->pullLow(gpioId); - if (result != RETURN_OK) { - sif::error << "HeaterHandler::handleSwitchOffCommand: Failed to pull gpio with id" - << gpioId << " low" << std::endl; - triggerEvent(GPIO_PULL_LOW_FAILED, result); - } - else { - switchStates[switchNr] = OFF; - /* When all switches are off, also main line switch will be turned off */ - if (allSwitchesOff()) { - mainLineSwitcher->sendSwitchCommand(mainLineSwitch, PowerSwitchIF::SWITCH_OFF); - } - } - } - else { - sif::info << "HeaterHandler::handleSwitchOffCommand: Switch already off" << std::endl; - triggerEvent(SWITCH_ALREADY_OFF, switchNr); - } - if (heaterMapIter->second.replyQueue != NO_COMMANDER) { - actionHelper.finish(heaterMapIter->second.replyQueue, - heaterMapIter->second.action, result); - } - heaterMapIter->second.active = false; -} - -bool HeaterHandler::checkSwitchState(int switchNr) { - return switchStates[switchNr]; -} - -bool HeaterHandler::allSwitchesOff() { - bool allSwitchesOrd = false; - /* Or all switches. As soon one switch is on, allSwitchesOrd will be true */ - for (switchNr_t switchNr = 0; switchNr < heaterSwitches::NUMBER_OF_SWITCHES; switchNr++) { - allSwitchesOrd = allSwitchesOrd || switchStates[switchNr]; - } - return !allSwitchesOrd; -} - -gpioId_t HeaterHandler::getGpioIdFromSwitchNr(int switchNr) { - gpioId_t gpioId = 0xFFFF; - switch(switchNr) { - case heaterSwitches::HEATER_0: - gpioId = gpioIds::HEATER_0; - break; - case heaterSwitches::HEATER_1: - gpioId = gpioIds::HEATER_1; - break; - case heaterSwitches::HEATER_2: - gpioId = gpioIds::HEATER_2; - break; - case heaterSwitches::HEATER_3: - gpioId = gpioIds::HEATER_3; - break; - case heaterSwitches::HEATER_4: - gpioId = gpioIds::HEATER_4; - break; - case heaterSwitches::HEATER_5: - gpioId = gpioIds::HEATER_5; - break; - case heaterSwitches::HEATER_6: - gpioId = gpioIds::HEATER_6; - break; - case heaterSwitches::HEATER_7: - gpioId = gpioIds::HEATER_7; - break; - default: - sif::error << "HeaterHandler::getGpioIdFromSwitchNr: Unknown heater switch number" - << std::endl; - break; - } - return gpioId; -} - -MessageQueueId_t HeaterHandler::getCommandQueue() const { - return commandQueue->getId(); -} - -void HeaterHandler::sendFuseOnCommand(uint8_t fuseNr) const { -} - -ReturnValue_t HeaterHandler::getSwitchState( uint8_t switchNr ) const { - return 0; -} - -ReturnValue_t HeaterHandler::getFuseState( uint8_t fuseNr ) const { - return 0; -} - -uint32_t HeaterHandler::getSwitchDelayMs(void) const { - return 0; -} diff --git a/mission/devices/HeaterHandler.h b/mission/devices/HeaterHandler.h deleted file mode 100644 index 3c76e33b..00000000 --- a/mission/devices/HeaterHandler.h +++ /dev/null @@ -1,177 +0,0 @@ -#ifndef MISSION_DEVICES_HEATERHANDLER_H_ -#define MISSION_DEVICES_HEATERHANDLER_H_ - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -/** - * @brief This class intends the control of heaters. - * - * @author J. Meier - */ -class HeaterHandler: public ExecutableObjectIF, - public PowerSwitchIF, - public SystemObject, - public HasActionsIF { -public: - - /** Device command IDs */ - static const DeviceCommandId_t SWITCH_HEATER = 0x0; - - HeaterHandler(object_id_t setObjectId, object_id_t gpioDriverId, CookieIF * gpioCookie, - object_id_t mainLineSwitcherObjectId, uint8_t mainLineSwitch); - - virtual ~HeaterHandler(); - - virtual ReturnValue_t performOperation(uint8_t operationCode = 0) override; - - virtual void sendSwitchCommand(uint8_t switchNr, ReturnValue_t onOff) const override; - virtual void sendFuseOnCommand(uint8_t fuseNr) const override; - /** - * @brief This function will be called from the Heater object to check - * the current switch state. - */ - virtual ReturnValue_t getSwitchState( uint8_t switchNr ) const override; - virtual ReturnValue_t getFuseState( uint8_t fuseNr ) const override; - virtual uint32_t getSwitchDelayMs(void) const override; - - virtual MessageQueueId_t getCommandQueue() const override; - virtual ReturnValue_t executeAction(ActionId_t actionId, MessageQueueId_t commandedBy, - const uint8_t* data, size_t size) override; - virtual ReturnValue_t initialize() override; - -private: - - static const uint8_t INTERFACE_ID = CLASS_ID::HEATER_HANDLER; - - static const ReturnValue_t COMMAND_NOT_SUPPORTED = MAKE_RETURN_CODE(0xA1); - static const ReturnValue_t INIT_FAILED = MAKE_RETURN_CODE(0xA2); - static const ReturnValue_t INVALID_SWITCH_NR = MAKE_RETURN_CODE(0xA3); - static const ReturnValue_t MAIN_SWITCH_SET_TIMEOUT = MAKE_RETURN_CODE(0xA4); - static const ReturnValue_t COMMAND_ALREADY_WAITING = MAKE_RETURN_CODE(0xA5); - - static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::HEATER_HANDLER; - static const Event GPIO_PULL_HIGH_FAILED = MAKE_EVENT(0, severity::LOW); - static const Event GPIO_PULL_LOW_FAILED = MAKE_EVENT(1, severity::LOW); - static const Event SWITCH_ALREADY_ON = MAKE_EVENT(2, severity::LOW); - static const Event SWITCH_ALREADY_OFF = MAKE_EVENT(3, severity::LOW); - static const Event MAIN_SWITCH_TIMEOUT = MAKE_EVENT(4, severity::LOW); - - static const MessageQueueId_t NO_COMMANDER = 0; - - enum SwitchState : bool { - ON = true, - OFF = false - }; - - - /** - * @brief Struct holding information about a heater command to execute. - * - * @param action The action to perform. - * @param replyQueue The queue of the commander to which status replies - * will be sent. - * @param active True if command is waiting for execution, otherwise false. - * @param waitSwitchOn True if the command is waiting for the main switch being set on. - * @param mainSwitchCountdown Sets timeout to wait for main switch being set on. - */ - typedef struct HeaterCommandInfo { - uint8_t action; - MessageQueueId_t replyQueue; - bool active = false; - bool waitMainSwitchOn = false; - Countdown mainSwitchCountdown; - } HeaterCommandInfo_t; - - enum SwitchAction { - SET_SWITCH_OFF, - SET_SWITCH_ON - }; - - using switchNr_t = uint8_t; - using HeaterMap = std::unordered_map; - using HeaterMapIter = HeaterMap::iterator; - - HeaterMap heaterMap; - - bool switchStates[heaterSwitches::NUMBER_OF_SWITCHES]; - - /** Size of command queue */ - size_t cmdQueueSize = 20; - - /** - * The object ID of the GPIO driver which enables and disables the - * heaters. - */ - object_id_t gpioDriverId; - - CookieIF * gpioCookie; - - GpioIF* gpioInterface; - - /** Queue to receive messages from other objects. */ - MessageQueueIF* commandQueue = nullptr; - - object_id_t mainLineSwitcherObjectId; - - /** Switch number of the heater power supply switch */ - uint8_t mainLineSwitch; - - /** - * Power switcher object which controls the 8V main line of the heater - * logic on the TCS board. - */ - PowerSwitchIF *mainLineSwitcher = nullptr; - - ActionHelper actionHelper; - - StorageManagerIF *IPCStore = nullptr; - - void readCommandQueue(); - - /** - * @brief Returns the state of a switch (ON - true, or OFF - false). - * @param switchNr The number of the switch to check. - */ - bool checkSwitchState(int switchNr); - - /** - * @brief Returns the ID of the GPIO related to a heater identified by the switch number - * which is defined in the heaterSwitches list. - */ - gpioId_t getGpioIdFromSwitchNr(int switchNr); - - /** - * @brief This function runs commands waiting for execution. - */ - void handleActiveCommands(); - - ReturnValue_t initializeHeaterMap(); - - /** - * @brief Sets all switches to OFF. - */ - void setInitialSwitchStates(); - - void handleSwitchOnCommand(HeaterMapIter heaterMapIter); - - void handleSwitchOffCommand(HeaterMapIter heaterMapIter); - - /** - * @brief Checks if all switches are off. - * @return True if all switches are off, otherwise false. - */ - bool allSwitchesOff(); - -}; - -#endif /* MISSION_DEVICES_HEATERHANDLER_H_ */ diff --git a/mission/devices/Max31865PT1000Handler.cpp b/mission/devices/Max31865PT1000Handler.cpp new file mode 100644 index 00000000..ddf12d2f --- /dev/null +++ b/mission/devices/Max31865PT1000Handler.cpp @@ -0,0 +1,357 @@ +#include +#include +#include "Max31865PT100Handler.h" + +Max31865PT1000Handler::Max31865PT1000Handler(object_id_t objectId, + object_id_t comIF, CookieIF *comCookie, uint8_t switchId): + DeviceHandlerBase(objectId, comIF, comCookie), switchId(switchId), + sensorDataset(this), sensorDatasetSid(sensorDataset.getSid()) { +#if OBSW_VERBOSE_LEVEL >= 1 + debugDivider = new PeriodicOperationDivider(10); +#endif +} + +Max31865PT1000Handler::~Max31865PT1000Handler() { +} + +void Max31865PT1000Handler::doStartUp() { + if(internalState == InternalState::NONE) { + internalState = InternalState::WARMUP; + Clock::getUptime(&startTime); + } + + if(internalState == InternalState::WARMUP) { + dur_millis_t timeNow = 0; + Clock::getUptime(&timeNow); + if(timeNow - startTime >= 100) { + internalState = InternalState::CONFIGURE; + } + } + + if(internalState == InternalState::CONFIGURE) { + if(commandExecuted) { + internalState = InternalState::REQUEST_CONFIG; + commandExecuted = false; + } + } + + if(internalState == InternalState::REQUEST_CONFIG) { + if (commandExecuted) { + setMode(MODE_ON); + setMode(MODE_NORMAL); + commandExecuted = false; + internalState = InternalState::RUNNING; + } + } +} + +void Max31865PT1000Handler::doShutDown() { + commandExecuted = false; + setMode(MODE_OFF); +} + +ReturnValue_t Max31865PT1000Handler::buildNormalDeviceCommand( + DeviceCommandId_t *id) { + if(internalState == InternalState::RUNNING) { + *id = TSensorDefinitions::REQUEST_RTD; + return buildCommandFromCommand(*id, nullptr, 0); + } + else if(internalState == InternalState::REQUEST_FAULT_BYTE) { + *id = TSensorDefinitions::REQUEST_FAULT_BYTE; + return buildCommandFromCommand(*id, nullptr, 0); + } + else { + return DeviceHandlerBase::NOTHING_TO_SEND; + } +} + +ReturnValue_t Max31865PT1000Handler::buildTransitionDeviceCommand( + DeviceCommandId_t *id) { + switch(internalState) { + case(InternalState::NONE): + case(InternalState::WARMUP): + case(InternalState::RUNNING): + return DeviceHandlerBase::NOTHING_TO_SEND; + case(InternalState::CONFIGURE): { + *id = TSensorDefinitions::CONFIG_CMD; + uint8_t config[1] = {DEFAULT_CONFIG}; + return buildCommandFromCommand(*id, config, 1); + } + case(InternalState::REQUEST_CONFIG): { + *id = TSensorDefinitions::REQUEST_CONFIG; + return buildCommandFromCommand(*id, nullptr, 0); + } + + default: +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::error << "Max31865PT1000Handler: Invalid internal state" << std::endl; +#else + sif::printError("Max31865PT1000Handler: Invalid internal state\n"); +#endif + return HasReturnvaluesIF::RETURN_FAILED; + } +} + +ReturnValue_t Max31865PT1000Handler::buildCommandFromCommand( + DeviceCommandId_t deviceCommand, const uint8_t *commandData, + size_t commandDataLen) { + switch(deviceCommand) { + case(TSensorDefinitions::CONFIG_CMD) : { + commandBuffer[0] = static_cast(TSensorDefinitions::CONFIG_CMD); + if(commandDataLen == 1) { + commandBuffer[1] = commandData[0]; + DeviceHandlerBase::rawPacketLen = 2; + DeviceHandlerBase::rawPacket = commandBuffer.data(); + return HasReturnvaluesIF::RETURN_OK; + } + else { + return DeviceHandlerIF::NO_COMMAND_DATA; + } + } + case(TSensorDefinitions::REQUEST_CONFIG): { + commandBuffer[0] = 0x00; // dummy byte + commandBuffer[1] = static_cast( + TSensorDefinitions::REQUEST_CONFIG); + DeviceHandlerBase::rawPacketLen = 2; + DeviceHandlerBase::rawPacket = commandBuffer.data(); + return HasReturnvaluesIF::RETURN_OK; + } + case(TSensorDefinitions::REQUEST_RTD): { + commandBuffer[0] = static_cast( + TSensorDefinitions::REQUEST_RTD); + // two dummy bytes + commandBuffer[1] = 0x00; + commandBuffer[2] = 0x00; + DeviceHandlerBase::rawPacketLen = 3; + DeviceHandlerBase::rawPacket = commandBuffer.data(); + return HasReturnvaluesIF::RETURN_OK; + } + case(TSensorDefinitions::REQUEST_FAULT_BYTE): { + commandBuffer[0] = static_cast( + TSensorDefinitions::REQUEST_FAULT_BYTE); + commandBuffer[1] = 0x00; + DeviceHandlerBase::rawPacketLen = 2; + DeviceHandlerBase::rawPacket = commandBuffer.data(); + return HasReturnvaluesIF::RETURN_OK; + } + default: + //Unknown DeviceCommand + return DeviceHandlerIF::COMMAND_NOT_IMPLEMENTED; + } +} + +void Max31865PT1000Handler::fillCommandAndReplyMap() { + insertInCommandAndReplyMap(TSensorDefinitions::CONFIG_CMD, 3); + insertInCommandAndReplyMap(TSensorDefinitions::REQUEST_CONFIG, 3); + insertInCommandAndReplyMap(TSensorDefinitions::REQUEST_RTD, 3, + &sensorDataset); + insertInCommandAndReplyMap(TSensorDefinitions::REQUEST_FAULT_BYTE, 3); +} + +ReturnValue_t Max31865PT1000Handler::scanForReply(const uint8_t *start, + size_t remainingSize, DeviceCommandId_t *foundId, size_t *foundLen) { + size_t rtdReplySize = 3; + size_t configReplySize = 2; + + if(remainingSize == rtdReplySize and + internalState == InternalState::RUNNING) { + *foundId = TSensorDefinitions::REQUEST_RTD; + *foundLen = rtdReplySize; + } + + if(remainingSize == configReplySize) { + if(internalState == InternalState::CONFIGURE) { + commandExecuted = true; + *foundLen = configReplySize; + *foundId = TSensorDefinitions::CONFIG_CMD; + } + else if(internalState == InternalState::REQUEST_FAULT_BYTE) { + *foundId = TSensorDefinitions::REQUEST_FAULT_BYTE; + *foundLen = 2; + internalState = InternalState::RUNNING; + } + else { + *foundId = TSensorDefinitions::REQUEST_CONFIG; + *foundLen = configReplySize; + } + } + + return RETURN_OK; +} + +ReturnValue_t Max31865PT1000Handler::interpretDeviceReply( + DeviceCommandId_t id, const uint8_t *packet) { + switch(id) { + case(TSensorDefinitions::REQUEST_CONFIG): { + if(packet[1] != DEFAULT_CONFIG) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 + // it propably would be better if we at least try one restart.. + sif::error << "Max31865PT1000Handler: Invalid configuration reply!" << std::endl; +#else + sif::printError("Max31865PT1000Handler: Invalid configuration reply!\n"); +#endif + return HasReturnvaluesIF::RETURN_OK; + } + // set to true for invalid configs too for now. + if(internalState == InternalState::REQUEST_CONFIG) { + commandExecuted = true; + } + else if(internalState == InternalState::RUNNING) { + // we should propably generate a telemetry with the config byte + // as payload here. + } + break; + } + case(TSensorDefinitions::REQUEST_RTD): { + // first bit of LSB reply byte is the fault bit + uint8_t faultBit = packet[2] & 0b0000'0001; + if(faultBit == 1) { + // Maybe we should attempt to restart it? + if(faultByte == 0) { + internalState = InternalState::REQUEST_FAULT_BYTE; + } + } + + // RTD value consists of last seven bits of the LSB reply byte and + // the MSB reply byte + uint16_t adcCode = ((packet[1] << 8) | packet[2]) >> 1; + // do something with rtd value, will propably be stored in + // dataset. + float rtdValue = adcCode * RTD_RREF_PT1000 / INT16_MAX; + + // calculate approximation + float approxTemp = adcCode / 32.0 - 256.0; + +#if OBSW_VERBOSE_LEVEL >= 1 + if(debugDivider->checkAndIncrement()) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::info << "Max31865PT1000Handler::interpretDeviceReply: Measured " + << "resistance is " << rtdValue << " Ohms." << std::endl; + sif::info << "Approximated temperature is " << approxTemp << " °C" + << std::endl; +#else + sif::printInfo("Max31865PT1000Handler::interpretDeviceReply: Measured resistance is %f" + " Ohms.\n", rtdValue); + sif::printInfo("Approximated temperature is %f C\n", approxTemp); +#endif + sensorDataset.setChanged(true); + } +#endif + + ReturnValue_t result = sensorDataset.read(); + if(result != HasReturnvaluesIF::RETURN_OK) { + // Configuration error +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::debug << "Max31865PT1000Handler::interpretDeviceReply: Error reading dataset!" + << std::endl; +#else + sif::printDebug("Max31865PT1000Handler::interpretDeviceReply: Error reading dataset!\n"); +#endif + return result; + } + + if(not sensorDataset.isValid()) { + sensorDataset.temperatureCelcius.setValid(true); + } + + sensorDataset.temperatureCelcius = approxTemp; + + result = sensorDataset.commit(); + + if(result != HasReturnvaluesIF::RETURN_OK) { + // Configuration error +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::debug << "Max31865PT1000Handler::interpretDeviceReply: " + "Error commiting dataset!" << std::endl; +#else + sif::printDebug("Max31865PT1000Handler::interpretDeviceReply: " + "Error commiting dataset!\n"); +#endif + return result; + } + + break; + } + case(TSensorDefinitions::REQUEST_FAULT_BYTE): { + faultByte = packet[1]; +#if OBSW_VERBOSE_LEVEL >= 1 +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::info << "Max31865PT1000Handler::interpretDeviceReply: Fault byte" + " is: 0b" << std::bitset<8>(faultByte) << std::endl; +#else + sif::printInfo("Max31865PT1000Handler::interpretDeviceReply: Fault byte" + " is: 0b" BYTE_TO_BINARY_PATTERN "\n", BYTE_TO_BINARY(faultByte)); +#endif +#endif + ReturnValue_t result = sensorDataset.read(); + if(result != HasReturnvaluesIF::RETURN_OK) { + // Configuration error +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::debug << "Max31865PT1000Handler::interpretDeviceReply: " + "Error reading dataset!" << std::endl; +#else + sif::printDebug("Max31865PT1000Handler::interpretDeviceReply: " + "Error reading dataset!\n"); +#endif + return result; + } + sensorDataset.errorByte.setValid(true); + sensorDataset.errorByte = faultByte; + if(faultByte != 0) { + sensorDataset.temperatureCelcius.setValid(false); + } + + result = sensorDataset.commit(); + if(result != HasReturnvaluesIF::RETURN_OK) { + // Configuration error +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::debug << "Max31865PT1000Handler::interpretDeviceReply: " + "Error commiting dataset!" << std::endl; +#else + sif::printDebug("Max31865PT1000Handler::interpretDeviceReply: " + "Error commiting dataset!\n"); +#endif + return result; + } + + break; + } + default: + break; + } + return HasReturnvaluesIF::RETURN_OK; +} + +void Max31865PT1000Handler::debugInterface(uint8_t positionTracker, + object_id_t objectId, uint32_t parameter) { +} + +uint32_t Max31865PT1000Handler::getTransitionDelayMs( + Mode_t modeFrom, Mode_t modeTo) { + return 5000; +} + +ReturnValue_t Max31865PT1000Handler::getSwitches( + const uint8_t **switches, uint8_t *numberOfSwitches) { + return DeviceHandlerBase::NO_SWITCH; +} + +void Max31865PT1000Handler::doTransition(Mode_t modeFrom, + Submode_t subModeFrom) { + DeviceHandlerBase::doTransition(modeFrom, subModeFrom); +} + +ReturnValue_t Max31865PT1000Handler::initializeLocalDataPool(localpool::DataPool& localDataPoolMap, + LocalDataPoolManager& poolManager) { + localDataPoolMap.emplace(TSensorDefinitions::PoolIds::TEMPERATURE_C, + new PoolEntry({0}, 1, true)); + localDataPoolMap.emplace(TSensorDefinitions::PoolIds::FAULT_BYTE, + new PoolEntry({0})); + poolManager.subscribeForPeriodicPacket(sensorDatasetSid, + false, 4.0, false); + return HasReturnvaluesIF::RETURN_OK; +} + +void Max31865PT1000Handler::modeChanged() { + internalState = InternalState::NONE; +} diff --git a/mission/devices/Max31865PT100Handler.h b/mission/devices/Max31865PT100Handler.h new file mode 100644 index 00000000..9375eee9 --- /dev/null +++ b/mission/devices/Max31865PT100Handler.h @@ -0,0 +1,104 @@ +#ifndef MISSION_DEVICES_MAX31865PT100HANDLER_H_ +#define MISSION_DEVICES_MAX31865PT100HANDLER_H_ + +#include "devicedefinitions/ThermalSensorPacket.h" +#include + +#include +#include + +#include +#include + +/** + * @brief Device Handler for the thermal sensors + * @details + * Documentation of devices: + * MAX31865 RTD converter: + * https://datasheets.maximintegrated.com/en/ds/MAX31865.pdf + * Pt1000 platinum resistance thermometers OMEGA F2020-1000-1/3B: + * https://br.omega.com/omegaFiles/temperature/pdf/F1500_F2000_F4000.pdf + * + * The thermal sensor values are measured using the MAX31865 RTD converter IC + * which creates digital values from the measured resistance of the Pt1000 + * devices which can be read with the SPI interface. + * Refer to the SOURCE system schematic for the exact setup and number + * of devices. + * + * @author R. Mueller + * @ingroup devices + */ +class Max31865PT1000Handler: public DeviceHandlerBase { +public: + Max31865PT1000Handler(object_id_t objectId, object_id_t comIF, + CookieIF * comCookie, uint8_t switchId); + virtual~ Max31865PT1000Handler(); + + // Configuration in 8 digit code: + // 1. 1 for V_BIAS enabled, 0 for disabled + // 2. 1 for Auto-conversion, 0 for off + // 3. 1 for 1-shot enabled, 0 for disabled + // 4. 1 for 3-wire disabled, 0 for disabled + // 5./6. Fault detection: 00 for no action, 01 for automatic delay, 1 + // 0 for run fault detection with manual delay, + // 11 for finish fault detection with manual delay + // 7. Fault status: 1 for auto-clear, 0 for auto-clear off + // 8. 1 for 50 Hz filter, 0 for 60 Hz filter (noise rejection filter) + static constexpr uint8_t DEFAULT_CONFIG = 0b11000001; + + static constexpr float RTD_RREF_PT1000 = 4000.0; //!< Ohm + static constexpr float RTD_RESISTANCE0_PT1000 = 1000.0; //!< Ohm +protected: + /* DeviceHandlerBase abstract function implementation */ + void doStartUp() override; + void doShutDown() override; + ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t * id) override; + ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t * id) override; + ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, + const uint8_t * commandData, size_t commandDataLen) override; + void fillCommandAndReplyMap() override; + ReturnValue_t scanForReply(const uint8_t *start, size_t remainingSize, + DeviceCommandId_t *foundId, size_t *foundLen) override; + ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, + const uint8_t *packet) override; + uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override; + ReturnValue_t getSwitches(const uint8_t **switches, + uint8_t *numberOfSwitches) override; + + void doTransition(Mode_t modeFrom, Submode_t subModeFrom) override; + + void debugInterface(uint8_t positionTracker = 0, + object_id_t objectId = 0, uint32_t parameter = 0) override; + ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap, + LocalDataPoolManager& poolManager) override; + void modeChanged() override; + +private: + const uint8_t switchId; + + enum class InternalState { + NONE, + WARMUP, + CONFIGURE, + REQUEST_CONFIG, + RUNNING, + REQUEST_FAULT_BYTE + }; + + InternalState internalState = InternalState::NONE; + bool commandExecuted = false; + + dur_millis_t startTime = 0; + uint8_t faultByte = 0; + std::array commandBuffer { 0 }; + + TSensorDefinitions::ThermalSensorDataset sensorDataset; + sid_t sensorDatasetSid; + +#if OBSW_VERBOSE_LEVEL >= 1 + PeriodicOperationDivider* debugDivider; +#endif +}; + +#endif /* MISSION_DEVICES_MAX31865PT100HANDLER_H_ */ + diff --git a/mission/devices/PDU1Handler.cpp b/mission/devices/PDU1Handler.cpp index 559ce94d..5a6d62cb 100644 --- a/mission/devices/PDU1Handler.cpp +++ b/mission/devices/PDU1Handler.cpp @@ -1,6 +1,6 @@ #include "PDU1Handler.h" #include -#include +#include PDU1Handler::PDU1Handler(object_id_t objectId, object_id_t comIF, CookieIF * comCookie) : GomspaceDeviceHandler(objectId, comIF, comCookie, PDU::MAX_CONFIGTABLE_ADDRESS, diff --git a/mission/devices/SolarArrayDeploymentHandler.cpp b/mission/devices/SolarArrayDeploymentHandler.cpp deleted file mode 100644 index 45521800..00000000 --- a/mission/devices/SolarArrayDeploymentHandler.cpp +++ /dev/null @@ -1,197 +0,0 @@ -#include -#include -#include -#include - -SolarArrayDeploymentHandler::SolarArrayDeploymentHandler(object_id_t setObjectId_, - object_id_t gpioDriverId_, CookieIF * gpioCookie_, object_id_t mainLineSwitcherObjectId_, - uint8_t mainLineSwitch_, gpioId_t deplSA1, gpioId_t deplSA2, uint32_t burnTimeMs) : - SystemObject(setObjectId_), gpioDriverId(gpioDriverId_), gpioCookie(gpioCookie_), mainLineSwitcherObjectId( - mainLineSwitcherObjectId_), mainLineSwitch(mainLineSwitch_), deplSA1(deplSA1), deplSA2( - deplSA2), burnTimeMs(burnTimeMs), actionHelper(this, nullptr) { - commandQueue = QueueFactory::instance()->createMessageQueue(cmdQueueSize, - MessageQueueMessage::MAX_MESSAGE_SIZE); -} - -SolarArrayDeploymentHandler::~SolarArrayDeploymentHandler() { -} - -ReturnValue_t SolarArrayDeploymentHandler::performOperation(uint8_t operationCode) { - - if (operationCode == DeviceHandlerIF::PERFORM_OPERATION) { - handleStateMachine(); - return RETURN_OK; - } - return RETURN_OK; -} - -ReturnValue_t SolarArrayDeploymentHandler::initialize() { - ReturnValue_t result = SystemObject::initialize(); - if (result != RETURN_OK) { - return ObjectManagerIF::CHILD_INIT_FAILED; - } - - gpioInterface = objectManager->get(gpioDriverId); - if (gpioInterface == nullptr) { - sif::error << "SolarArrayDeploymentHandler::initialize: Invalid Gpio interface." - << std::endl; - return ObjectManagerIF::CHILD_INIT_FAILED; - } - - result = gpioInterface->initialize(gpioCookie); - if (result != RETURN_OK) { - sif::error << "SolarArrayDeploymentHandler::initialize: Failed to initialize Gpio interface" - << std::endl; - return ObjectManagerIF::CHILD_INIT_FAILED; - } - - if (mainLineSwitcherObjectId != objects::NO_OBJECT) { - mainLineSwitcher = objectManager->get(mainLineSwitcherObjectId); - if (mainLineSwitcher == nullptr) { - sif::error - << "SolarArrayDeploymentHandler::initialize: Main line switcher failed to fetch object" - << "from object ID." << std::endl; - return ObjectManagerIF::CHILD_INIT_FAILED; - } - } - - result = actionHelper.initialize(commandQueue); - if (result != RETURN_OK) { - return ObjectManagerIF::CHILD_INIT_FAILED; - } - - return RETURN_OK; -} - -void SolarArrayDeploymentHandler::handleStateMachine() { - switch (stateMachine) { - case WAIT_ON_DELOYMENT_COMMAND: - readCommandQueue(); - break; - case SWITCH_8V_ON: - mainLineSwitcher->sendSwitchCommand(mainLineSwitch, PowerSwitchIF::SWITCH_ON); - mainSwitchCountdown.setTimeout(mainLineSwitcher->getSwitchDelayMs()); - stateMachine = WAIT_ON_8V_SWITCH; - break; - case WAIT_ON_8V_SWITCH: - performWaitOn8VActions(); - break; - case SWITCH_DEPL_GPIOS: - switchDeploymentTransistors(); - break; - case WAIT_ON_DEPLOYMENT_FINISH: - handleDeploymentFinish(); - break; - case WAIT_FOR_MAIN_SWITCH_OFF: - if (mainLineSwitcher->getSwitchState(mainLineSwitch) == PowerSwitchIF::SWITCH_OFF) { - stateMachine = WAIT_ON_DELOYMENT_COMMAND; - } else if (mainSwitchCountdown.hasTimedOut()) { - triggerEvent(MAIN_SWITCH_OFF_TIMEOUT); - sif::error << "SolarArrayDeploymentHandler::handleStateMachine: Failed to switch main" - << " switch off" << std::endl; - stateMachine = WAIT_ON_DELOYMENT_COMMAND; - } - break; - default: - sif::debug << "SolarArrayDeploymentHandler::handleStateMachine: Invalid state" << std::endl; - break; - } -} - -void SolarArrayDeploymentHandler::performWaitOn8VActions() { - if (mainLineSwitcher->getSwitchState(mainLineSwitch) == PowerSwitchIF::SWITCH_ON) { - stateMachine = SWITCH_DEPL_GPIOS; - } else { - if (mainSwitchCountdown.hasTimedOut()) { - triggerEvent(MAIN_SWITCH_ON_TIMEOUT); - actionHelper.finish(rememberCommanderId, DEPLOY_SOLAR_ARRAYS, - MAIN_SWITCH_TIMEOUT_FAILURE); - stateMachine = WAIT_ON_DELOYMENT_COMMAND; - } - } -} - -void SolarArrayDeploymentHandler::switchDeploymentTransistors() { - ReturnValue_t result = RETURN_OK; - result = gpioInterface->pullHigh(deplSA1); - if (result != RETURN_OK) { - sif::debug << "SolarArrayDeploymentHandler::handleStateMachine: Failed to pull solar" - " array deployment switch 1 high " << std::endl; - /* If gpio switch high failed, state machine is reset to wait for a command reinitiating - * the deployment sequence. */ - stateMachine = WAIT_ON_DELOYMENT_COMMAND; - triggerEvent(DEPL_SA1_GPIO_SWTICH_ON_FAILED); - actionHelper.finish(rememberCommanderId, DEPLOY_SOLAR_ARRAYS, - SWITCHING_DEPL_SA2_FAILED); - mainLineSwitcher->sendSwitchCommand(mainLineSwitch, PowerSwitchIF::SWITCH_OFF); - } - result = gpioInterface->pullHigh(deplSA2); - if (result != RETURN_OK) { - sif::debug << "SolarArrayDeploymentHandler::handleStateMachine: Failed to pull solar" - " array deployment switch 2 high " << std::endl; - stateMachine = WAIT_ON_DELOYMENT_COMMAND; - triggerEvent(DEPL_SA2_GPIO_SWTICH_ON_FAILED); - actionHelper.finish(rememberCommanderId, DEPLOY_SOLAR_ARRAYS, - SWITCHING_DEPL_SA2_FAILED); - mainLineSwitcher->sendSwitchCommand(mainLineSwitch, PowerSwitchIF::SWITCH_OFF); - } - deploymentCountdown.setTimeout(burnTimeMs); - stateMachine = WAIT_ON_DEPLOYMENT_FINISH; -} - -void SolarArrayDeploymentHandler::handleDeploymentFinish() { - ReturnValue_t result = RETURN_OK; - if (deploymentCountdown.hasTimedOut()) { - actionHelper.finish(rememberCommanderId, DEPLOY_SOLAR_ARRAYS, RETURN_OK); - result = gpioInterface->pullLow(deplSA1); - if (result != RETURN_OK) { - sif::debug << "SolarArrayDeploymentHandler::handleStateMachine: Failed to pull solar" - " array deployment switch 1 low " << std::endl; - } - result = gpioInterface->pullLow(deplSA2); - if (result != RETURN_OK) { - sif::debug << "SolarArrayDeploymentHandler::handleStateMachine: Failed to pull solar" - " array deployment switch 2 low " << std::endl; - } - mainLineSwitcher->sendSwitchCommand(mainLineSwitch, PowerSwitchIF::SWITCH_OFF); - mainSwitchCountdown.setTimeout(mainLineSwitcher->getSwitchDelayMs()); - stateMachine = WAIT_FOR_MAIN_SWITCH_OFF; - } -} - -void SolarArrayDeploymentHandler::readCommandQueue() { - CommandMessage command; - ReturnValue_t result = commandQueue->receiveMessage(&command); - if (result != RETURN_OK) { - return; - } - - result = actionHelper.handleActionMessage(&command); - if (result == RETURN_OK) { - return; - } -} - -ReturnValue_t SolarArrayDeploymentHandler::executeAction(ActionId_t actionId, - MessageQueueId_t commandedBy, const uint8_t* data, size_t size) { - ReturnValue_t result; - if (stateMachine != WAIT_ON_DELOYMENT_COMMAND) { - sif::error << "SolarArrayDeploymentHandler::executeAction: Received command while not in" - << "waiting-on-command-state" << std::endl; - return DEPLOYMENT_ALREADY_EXECUTING; - } - if (actionId != DEPLOY_SOLAR_ARRAYS) { - sif::error << "SolarArrayDeploymentHandler::executeAction: Received invalid command" - << std::endl; - result = COMMAND_NOT_SUPPORTED; - } else { - stateMachine = SWITCH_8V_ON; - rememberCommanderId = commandedBy; - result = RETURN_OK; - } - return result; -} - -MessageQueueId_t SolarArrayDeploymentHandler::getCommandQueue() const { - return commandQueue->getId(); -} diff --git a/mission/devices/SolarArrayDeploymentHandler.h b/mission/devices/SolarArrayDeploymentHandler.h deleted file mode 100644 index 279ae5da..00000000 --- a/mission/devices/SolarArrayDeploymentHandler.h +++ /dev/null @@ -1,158 +0,0 @@ -#ifndef MISSION_DEVICES_SOLARARRAYDEPLOYMENT_H_ -#define MISSION_DEVICES_SOLARARRAYDEPLOYMENT_H_ - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -/** - * @brief This class is used to control the solar array deployment. - * - * @author J. Meier - */ -class SolarArrayDeploymentHandler: public ExecutableObjectIF, - public SystemObject, - public HasReturnvaluesIF, - public HasActionsIF { -public: - - static const DeviceCommandId_t DEPLOY_SOLAR_ARRAYS = 0x5; - - /** - * @brief constructor - * - * @param setObjectId The object id of the SolarArrayDeploymentHandler. - * @param gpioDriverId The id of the gpio com if. - * @param gpioCookie GpioCookie holding information about the gpios used to switch the - * transistors. - * @param mainLineSwitcherObjectId The object id of the object responsible for switching - * the 8V power source. This is normally the PCDU. - * @param mainLineSwitch The id of the main line switch. This is defined in - * powerSwitcherList.h. - * @param deplSA1 gpioId of the GPIO controlling the deployment 1 transistor. - * @param deplSA2 gpioId of the GPIO controlling the deployment 2 transistor. - * @param burnTimeMs Time duration the power will be applied to the burn wires. - */ - SolarArrayDeploymentHandler(object_id_t setObjectId, object_id_t gpioDriverId, - CookieIF * gpioCookie, object_id_t mainLineSwitcherObjectId, uint8_t mainLineSwitch, - gpioId_t deplSA1, gpioId_t deplSA2, uint32_t burnTimeMs); - - virtual ~SolarArrayDeploymentHandler(); - - virtual ReturnValue_t performOperation(uint8_t operationCode = 0) override; - - virtual MessageQueueId_t getCommandQueue() const override; - virtual ReturnValue_t executeAction(ActionId_t actionId, MessageQueueId_t commandedBy, - const uint8_t* data, size_t size) override; - virtual ReturnValue_t initialize() override; - -private: - - static const uint8_t INTERFACE_ID = CLASS_ID::SA_DEPL_HANDLER; - static const ReturnValue_t COMMAND_NOT_SUPPORTED = MAKE_RETURN_CODE(0xA0); - static const ReturnValue_t DEPLOYMENT_ALREADY_EXECUTING = MAKE_RETURN_CODE(0xA1); - static const ReturnValue_t MAIN_SWITCH_TIMEOUT_FAILURE = MAKE_RETURN_CODE(0xA2); - static const ReturnValue_t SWITCHING_DEPL_SA1_FAILED = MAKE_RETURN_CODE(0xA3); - static const ReturnValue_t SWITCHING_DEPL_SA2_FAILED = MAKE_RETURN_CODE(0xA4); - - static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::SA_DEPL_HANDLER; - static const Event MAIN_SWITCH_ON_TIMEOUT = MAKE_EVENT(0, severity::LOW); - static const Event MAIN_SWITCH_OFF_TIMEOUT = MAKE_EVENT(1, severity::LOW); - static const Event DEPLOYMENT_FAILED = MAKE_EVENT(2, severity::HIGH); - static const Event DEPL_SA1_GPIO_SWTICH_ON_FAILED = MAKE_EVENT(3, severity::HIGH); - static const Event DEPL_SA2_GPIO_SWTICH_ON_FAILED = MAKE_EVENT(4, severity::HIGH); - - - enum StateMachine { - WAIT_ON_DELOYMENT_COMMAND, - SWITCH_8V_ON, - WAIT_ON_8V_SWITCH, - SWITCH_DEPL_GPIOS, - WAIT_ON_DEPLOYMENT_FINISH, - WAIT_FOR_MAIN_SWITCH_OFF - }; - - StateMachine stateMachine = WAIT_ON_DELOYMENT_COMMAND; - - /** - * This countdown is used to check if the PCDU sets the 8V line on in the intended time. - */ - Countdown mainSwitchCountdown; - - /** - * This countdown is used to wait for the burn wire being successful cut. - */ - Countdown deploymentCountdown; - - - /** - * The message queue id of the component commanding an action will be stored in this variable. - * This is necessary to send later the action finish replies. - */ - MessageQueueId_t rememberCommanderId = 0; - - /** Size of command queue */ - size_t cmdQueueSize = 20; - - /** The object ID of the GPIO driver which switches the deployment transistors */ - object_id_t gpioDriverId; - - CookieIF * gpioCookie; - - /** Object id of the object responsible to switch the 8V power input. Typically the PCDU. */ - object_id_t mainLineSwitcherObjectId; - - /** Switch number of the 8V power switch */ - uint8_t mainLineSwitch; - - gpioId_t deplSA1; - gpioId_t deplSA2; - - GpioIF* gpioInterface; - - /** Time duration switches are active to cut the burn wire */ - uint32_t burnTimeMs; - - /** Queue to receive messages from other objects. */ - MessageQueueIF* commandQueue = nullptr; - - /** - * After initialization this pointer will hold the reference to the main line switcher object. - */ - PowerSwitchIF *mainLineSwitcher = nullptr; - - ActionHelper actionHelper; - - void readCommandQueue(); - - /** - * @brief This function performs actions dependent on the current state. - */ - void handleStateMachine(); - - /** - * @brief This function polls the 8V switch state and changes the state machine when the - * switch has been enabled. - */ - void performWaitOn8VActions(); - - /** - * @brief This functions handles the switching of the solar array deployment transistors. - */ - void switchDeploymentTransistors(); - - /** - * @brief This function performs actions to finish the deployment. Essentially switches - * are turned of after the burn time has expired. - */ - void handleDeploymentFinish(); -}; - -#endif /* MISSION_DEVICES_SOLARARRAYDEPLOYMENT_H_ */ diff --git a/mission/devices/devicedefinitions/ThermalSensorPacket.h b/mission/devices/devicedefinitions/ThermalSensorPacket.h new file mode 100644 index 00000000..ba6f2d13 --- /dev/null +++ b/mission/devices/devicedefinitions/ThermalSensorPacket.h @@ -0,0 +1,60 @@ +#ifndef MISSION_DEVICES_DEVICEPACKETS_THERMALSENSORPACKET_H_ +#define MISSION_DEVICES_DEVICEPACKETS_THERMALSENSORPACKET_H_ + +#include +#include +#include +#include + +namespace TSensorDefinitions { + +enum ObjIds: object_id_t { + TEST_HKB_HANDLER = objects::SPI_Test_PT1000, + SYRLINKS_HANDLER = objects::PT1000_Syrlinks_DEC1_O1, + MGT_1_HANDLER = objects::PT1000_MGT1_DEC2, + PLOC_HANDLER = objects::PT1000_PLOC_DEC4, + MESHCAM_HANDLER = objects::PT1000_Camera_DEC1_O2 +}; + +enum PoolIds: lp_id_t { + TEMPERATURE_C, + FAULT_BYTE +}; + +static constexpr DeviceCommandId_t CONFIG_CMD = 0x80; +static constexpr DeviceCommandId_t REQUEST_CONFIG = 0x00; +static constexpr DeviceCommandId_t REQUEST_RTD = 0x01; +static constexpr DeviceCommandId_t REQUEST_FAULT_BYTE = 0x07; + +static constexpr uint32_t THERMAL_SENSOR_SET_ID = REQUEST_RTD; + +class ThermalSensorDataset: + public StaticLocalDataSet { +public: + /** + * Constructor used by owner and data creators like device handlers. + * @param owner + * @param setId + */ + ThermalSensorDataset(HasLocalDataPoolIF* owner): + StaticLocalDataSet(owner, THERMAL_SENSOR_SET_ID) { + } + + /** + * Constructor used by data users like controllers. + * @param sid + */ + ThermalSensorDataset(object_id_t objectId): + StaticLocalDataSet(sid_t(objectId, THERMAL_SENSOR_SET_ID)) { + } + + lp_var_t temperatureCelcius = lp_var_t(sid.objectId, + PoolIds::TEMPERATURE_C, this); + lp_var_t errorByte = lp_var_t(sid.objectId, + PoolIds::FAULT_BYTE, this); +}; + +} + +#endif /* MISSION_DEVICES_DEVICEPACKETS_THERMALSENSORPACKET_H_ */ + diff --git a/etl b/thirdparty/etl similarity index 100% rename from etl rename to thirdparty/etl diff --git a/thirdparty/lwgps b/thirdparty/lwgps new file mode 160000 index 00000000..d276f972 --- /dev/null +++ b/thirdparty/lwgps @@ -0,0 +1 @@ +Subproject commit d276f9722d1311b552e7c99ee5b03a68487a0fc5 From a2044d38bc7f84effd3dde4aa2e27e58d47c48ab Mon Sep 17 00:00:00 2001 From: "Jakob.Meier" Date: Sat, 13 Mar 2021 14:42:30 +0100 Subject: [PATCH 15/79] rtd handler compiled --- bsp_hosted/fsfwconfig/devices/gpioIds.h | 26 ++- bsp_q7s/CMakeLists.txt | 1 + bsp_q7s/ObjectFactory.cpp | 48 +++- bsp_q7s/gpio/CMakeLists.txt | 3 + bsp_q7s/gpio/gpioCallbacks.cpp | 220 ++++++++++++++++++ bsp_q7s/gpio/gpioCallbacks.h | 23 ++ fsfwconfig/devices/addresses.h | 19 ++ fsfwconfig/devices/gpioIds.h | 26 ++- fsfwconfig/objects/systemObjectList.h | 20 ++ linux/boardtest/SpiTestClass.cpp | 14 +- linux/gpio/GpioCookie.cpp | 8 +- linux/gpio/GpioCookie.h | 2 +- linux/gpio/LinuxLibgpioIF.cpp | 2 +- linux/spi/SpiCookie.h | 1 + mission/devices/CMakeLists.txt | 1 + mission/devices/Max31865PT1000Handler.cpp | 53 ++--- ...PT100Handler.h => Max31865PT1000Handler.h} | 10 +- ...alSensorPacket.h => Max31865Definitions.h} | 24 +- 18 files changed, 431 insertions(+), 70 deletions(-) create mode 100644 bsp_q7s/gpio/CMakeLists.txt create mode 100644 bsp_q7s/gpio/gpioCallbacks.cpp create mode 100644 bsp_q7s/gpio/gpioCallbacks.h rename mission/devices/{Max31865PT100Handler.h => Max31865PT1000Handler.h} (92%) rename mission/devices/devicedefinitions/{ThermalSensorPacket.h => Max31865Definitions.h} (65%) diff --git a/bsp_hosted/fsfwconfig/devices/gpioIds.h b/bsp_hosted/fsfwconfig/devices/gpioIds.h index 8963bd20..df49c0b7 100644 --- a/bsp_hosted/fsfwconfig/devices/gpioIds.h +++ b/bsp_hosted/fsfwconfig/devices/gpioIds.h @@ -25,7 +25,31 @@ namespace gpioIds { MGM_3_RM3100_CS, TEST_ID_0, - TEST_ID_1 + TEST_ID_1, + + RTD_IC3, + RTD_IC4, + RTD_IC5, + RTD_IC6, + RTD_IC7, + RTD_IC8, + RTD_IC9, + RTD_IC10, + RTD_IC11, + RTD_IC12, + RTD_IC13, + RTD_IC14, + RTD_IC15, + RTD_IC16, + RTD_IC17, + RTD_IC18, + + SPI_MUX_BIT_1, + SPI_MUX_BIT_2, + SPI_MUX_BIT_3, + SPI_MUX_BIT_4, + SPI_MUX_BIT_5, + SPI_MUX_BIT_6 }; } diff --git a/bsp_q7s/CMakeLists.txt b/bsp_q7s/CMakeLists.txt index 7b985558..e567628e 100644 --- a/bsp_q7s/CMakeLists.txt +++ b/bsp_q7s/CMakeLists.txt @@ -8,6 +8,7 @@ add_subdirectory(boardconfig) add_subdirectory(comIF) add_subdirectory(devices) add_subdirectory(boardtest) +add_subdirectory(gpio) diff --git a/bsp_q7s/ObjectFactory.cpp b/bsp_q7s/ObjectFactory.cpp index 13f27f96..143bf6fb 100644 --- a/bsp_q7s/ObjectFactory.cpp +++ b/bsp_q7s/ObjectFactory.cpp @@ -8,6 +8,7 @@ #include #include +#include #include #include @@ -16,6 +17,8 @@ #include #include #include +#include +#include #include #include @@ -31,6 +34,8 @@ #include #include #include +#include +#include #include #include @@ -77,10 +82,13 @@ void ObjectFactory::produce(){ I2cCookie* i2cCookieTmp1075tcs2 = new I2cCookie(addresses::TMP1075_TCS_2, TMP1075::MAX_REPLY_LENGTH, std::string("/dev/i2c-1")); #endif + LinuxLibgpioIF* gpioComIF = new LinuxLibgpioIF(objects::GPIO_IF); + /* Communication interfaces */ new CspComIF(objects::CSP_COM_IF); new I2cComIF(objects::I2C_COM_IF); new UartComIF(objects::UART_COM_IF); + new SpiComIF(objects::SPI_COM_IF, gpioComIF); #if TE0720 == 0 CspCookie* p60DockCspCookie = new CspCookie(P60Dock::MAX_REPLY_LENGTH, @@ -123,42 +131,41 @@ void ObjectFactory::produce(){ tmp1075Handler_2->setStartUpImmediately(); GpioCookie* heaterGpiosCookie = new GpioCookie; - new LinuxLibgpioIF(objects::GPIO_IF); #if TE0720 == 0 /* Pin H2-11 on stack connector */ GpiodRegular gpioConfigHeater0(std::string("gpiochip7"), 16, std::string("Heater0"), gpio::OUT, 0); - heaterGpiosCookie->addGpio(gpioIds::HEATER_0, gpioConfigHeater0); + heaterGpiosCookie->addGpio(gpioIds::HEATER_0, &gpioConfigHeater0); /* Pin H2-12 on stack connector */ GpiodRegular gpioConfigHeater1(std::string("gpiochip7"), 12, std::string("Heater1"), gpio::OUT, 0); - heaterGpiosCookie->addGpio(gpioIds::HEATER_1, gpioConfigHeater1); + heaterGpiosCookie->addGpio(gpioIds::HEATER_1, &gpioConfigHeater1); /* Pin H2-13 on stack connector */ GpiodRegular gpioConfigHeater2(std::string("gpiochip7"), 7, std::string("Heater2"), gpio::OUT, 0); - heaterGpiosCookie->addGpio(gpioIds::HEATER_2, gpioConfigHeater2); + heaterGpiosCookie->addGpio(gpioIds::HEATER_2, &gpioConfigHeater2); GpiodRegular gpioConfigHeater3(std::string("gpiochip7"), 5, std::string("Heater3"), gpio::OUT, 0); - heaterGpiosCookie->addGpio(gpioIds::HEATER_3, gpioConfigHeater3); + heaterGpiosCookie->addGpio(gpioIds::HEATER_3, &gpioConfigHeater3); GpiodRegular gpioConfigHeater4(std::string("gpiochip7"), 3, std::string("Heater4"), gpio::OUT, 0); - heaterGpiosCookie->addGpio(gpioIds::HEATER_4, gpioConfigHeater4); + heaterGpiosCookie->addGpio(gpioIds::HEATER_4, &gpioConfigHeater4); GpiodRegular gpioConfigHeater5(std::string("gpiochip7"), 0, std::string("Heater5"), gpio::OUT, 0); - heaterGpiosCookie->addGpio(gpioIds::HEATER_5, gpioConfigHeater5); + heaterGpiosCookie->addGpio(gpioIds::HEATER_5, &gpioConfigHeater5); GpiodRegular gpioConfigHeater6(std::string("gpiochip7"), 1, std::string("Heater6"), gpio::OUT, 0); - heaterGpiosCookie->addGpio(gpioIds::HEATER_6, gpioConfigHeater6); + heaterGpiosCookie->addGpio(gpioIds::HEATER_6, &gpioConfigHeater6); GpiodRegular gpioConfigHeater7(std::string("gpiochip7"), 11, std::string("Heater7"), gpio::OUT, 0); - heaterGpiosCookie->addGpio(gpioIds::HEATER_7, gpioConfigHeater7); + heaterGpiosCookie->addGpio(gpioIds::HEATER_7, &gpioConfigHeater7); new HeaterHandler(objects::HEATER_HANDLER, objects::GPIO_IF, heaterGpiosCookie, objects::PCDU_HANDLER, pcduSwitches::TCS_BOARD_8V_HEATER_IN); @@ -167,10 +174,10 @@ void ObjectFactory::produce(){ GpiodRegular gpioConfigDeplSA0(std::string("gpiochip7"), 4, std::string("DeplSA1"), gpio::OUT, 0); - solarArrayDeplCookie->addGpio(gpioIds::DEPLSA1, gpioConfigDeplSA0); + solarArrayDeplCookie->addGpio(gpioIds::DEPLSA1, &gpioConfigDeplSA0); GpiodRegular gpioConfigDeplSA1(std::string("gpiochip7"), 2, std::string("DeplSA2"), gpio::OUT, 0); - solarArrayDeplCookie->addGpio(gpioIds::DEPLSA2, gpioConfigDeplSA1); + solarArrayDeplCookie->addGpio(gpioIds::DEPLSA2, &gpioConfigDeplSA1); //TODO: Find out burn time. For now set to 1000 ms. new SolarArrayDeploymentHandler(objects::SOLAR_ARRAY_DEPL_HANDLER, objects::GPIO_IF, @@ -185,6 +192,25 @@ void ObjectFactory::produce(){ objects::UART_COM_IF, syrlinksUartCookie); syrlinksHkHandler->setModeNormal(); + GpioCookie* rtdGpioCookie = new GpioCookie; + + gpioCallbacks::initTcsBoardDecoder(gpioComIF); + GpioCallback gpioRtdIc3(std::string("Chip select RTD IC3"), gpio::OUT, 1, + &gpioCallbacks::tcsBoardDecoderCallback, gpioComIF); + rtdGpioCookie->addGpio(gpioIds::RTD_IC3, &gpioRtdIc3); + GpioCallback gpioRtdIc4(std::string("Chip select RTD IC4"), gpio::OUT, 1, + &gpioCallbacks::tcsBoardDecoderCallback, gpioComIF); + rtdGpioCookie->addGpio(gpioIds::RTD_IC4, &gpioRtdIc4); + + SpiCookie* spiRtdIc3 = new SpiCookie(addresses::RTD_IC3, gpioIds::RTD_IC3, + std::string("/dev/spidev2.0"), Max31865Definitions::MAX_REPLY_SIZE, + spi::SpiMode::MODE_1, 2000000); + SpiCookie* spiRtdIc4 = new SpiCookie(addresses::RTD_IC4, gpioIds::RTD_IC4, + std::string("/dev/spidev2.0"), Max31865Definitions::MAX_REPLY_SIZE, + spi::SpiMode::MODE_1, 2000000); + new Max31865PT1000Handler(objects::RTD_IC3, objects::SPI_COM_IF, spiRtdIc3, 0); // 0 is switchId + new Max31865PT1000Handler(objects::RTD_IC4, objects::SPI_COM_IF, spiRtdIc4, 0); + #endif new TmTcUnixUdpBridge(objects::UDP_BRIDGE, diff --git a/bsp_q7s/gpio/CMakeLists.txt b/bsp_q7s/gpio/CMakeLists.txt new file mode 100644 index 00000000..dd657546 --- /dev/null +++ b/bsp_q7s/gpio/CMakeLists.txt @@ -0,0 +1,3 @@ +target_sources(${TARGET_NAME} PRIVATE + gpioCallbacks.cpp +) diff --git a/bsp_q7s/gpio/gpioCallbacks.cpp b/bsp_q7s/gpio/gpioCallbacks.cpp new file mode 100644 index 00000000..8c0f0662 --- /dev/null +++ b/bsp_q7s/gpio/gpioCallbacks.cpp @@ -0,0 +1,220 @@ +#include +#include +#include +#include +#include + + +namespace gpioCallbacks { + +GpioIF* gpioComInterface; + +void initTcsBoardDecoder(GpioIF* gpioComIF) { + + ReturnValue_t result; + + if (gpioComIF == nullptr) { + sif::debug << "initTcsBoardDecoder: Invalid gpioComIF" << std::endl; + return; + } + + gpioComInterface = gpioComIF; + + GpioCookie* spiMuxGpios = new GpioCookie; + /** + * Initial values of the spi mux gpios can all be set to an arbitrary value expect for spi mux + * bit 1. Setting spi mux bit 1 to high will pull all decoder outputs to high voltage level. + */ + GpiodRegular spiMuxBit1(std::string("gpiochip7"), 13, std::string("SPI Mux Bit 1"), gpio::OUT, + 1); + spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_1, &spiMuxBit1); + GpiodRegular spiMuxBit2(std::string("gpiochip7"), 14, std::string("SPI Mux Bit 2"), gpio::OUT, + 0); + spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_2, &spiMuxBit2); + GpiodRegular spiMuxBit3(std::string("gpiochip7"), 15, std::string("SPI Mux Bit 3"), gpio::OUT, + 0); + spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_3, &spiMuxBit3); + GpiodRegular spiMuxBit4(std::string("gpiochip7"), 16, std::string("SPI Mux Bit 4"), gpio::OUT, + 0); + spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_4, &spiMuxBit4); + GpiodRegular spiMuxBit5(std::string("gpiochip7"), 17, std::string("SPI Mux Bit 5"), gpio::OUT, + 0); + spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_5, &spiMuxBit5); + GpiodRegular spiMuxBit6(std::string("gpiochip7"), 18, std::string("SPI Mux Bit 6"), gpio::OUT, + 0); + spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_6, &spiMuxBit6); + + result = gpioComInterface->addGpios(spiMuxGpios); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::error << "initTcsBoardDecoder: Failed to add mux bit gpios to gpioComIF" + << std::endl; + return; + } +} + +void tcsBoardDecoderCallback(gpioId_t gpioId, gpio::GpioOperation gpioOp, int value, + void* args) { + + if (gpioComInterface == nullptr) { + sif::debug << "tcsBoardDecoderCallback: No gpioComIF specified. Call initTcsBoardDecoder " + << "to specify gpioComIF" << std::endl; + return; + } + + /* Read is not supported by the callback function */ + if (gpioOp == gpio::GpioOperation::READ) { + return; + } + + if (value == 1) { + /* This will pull all 16 decoder outputs to high */ + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_1); + } + else if (value == 0) { + switch (gpioId) { + case(gpioIds::RTD_IC3): { + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_1); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_2); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_3); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_4); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_5); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_6); + break; + } + case(gpioIds::RTD_IC4): { + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_1); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_2); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_3); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_4); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_5); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_6); + break; + } + case(gpioIds::RTD_IC5): { + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_1); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_2); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_3); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_4); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_5); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_6); + break; + } + case(gpioIds::RTD_IC6): { + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_1); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_2); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_3); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_4); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_5); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_6); + break; + } + case(gpioIds::RTD_IC7): { + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_1); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_2); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_3); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_4); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_5); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_6); + break; + } + case(gpioIds::RTD_IC8): { + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_1); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_2); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_3); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_4); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_5); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_6); + break; + } + case(gpioIds::RTD_IC9): { + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_1); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_2); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_3); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_4); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_5); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_6); + break; + } + case(gpioIds::RTD_IC10): { + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_1); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_2); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_3); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_4); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_5); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_6); + break; + } + case(gpioIds::RTD_IC11): { + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_1); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_3); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_4); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_5); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_6); + break; + } + case(gpioIds::RTD_IC12): { + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_1); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_3); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_4); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_5); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_6); + break; + } + case(gpioIds::RTD_IC13): { + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_1); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_3); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_4); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_5); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_6); + break; + } + case(gpioIds::RTD_IC14): { + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_1); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_3); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_4); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_5); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_6); + break; + } + case(gpioIds::RTD_IC15): { + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_1); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_3); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_4); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_5); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_6); + break; + } + case(gpioIds::RTD_IC16): { + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_1); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_3); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_4); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_5); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_6); + break; + } + case(gpioIds::RTD_IC17): { + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_1); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_3); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_4); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_5); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_6); + break; + } + case(gpioIds::RTD_IC18): { + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_1); + gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_3); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_4); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_5); + gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_6); + break; + } + default: + sif::debug << "tcsBoardDecoderCallback: Invalid gpioid " << gpioId << std::endl; + } + } + else { + sif::debug << "tcsBoardDecoderCallback: Invalid value. Must be 0 or 1" << std::endl; + } +} + +} diff --git a/bsp_q7s/gpio/gpioCallbacks.h b/bsp_q7s/gpio/gpioCallbacks.h new file mode 100644 index 00000000..7654e548 --- /dev/null +++ b/bsp_q7s/gpio/gpioCallbacks.h @@ -0,0 +1,23 @@ +#ifndef LINUX_GPIO_GPIOCALLBACKS_H_ +#define LINUX_GPIO_GPIOCALLBACKS_H_ + +#include +#include + + +namespace gpioCallbacks { + + /** + * @brief This function initializes the GPIOs used to control the SN74LVC138APWR decoders on + * the TCS Board. + */ + void initTcsBoardDecoder(GpioIF* gpioComIF); + + /** + * @brief This function implements the decoding to multiply gpios by using the two decoder + * chips SN74LVC138APWR on the TCS board. + */ + void tcsBoardDecoderCallback(gpioId_t gpioId, gpio::GpioOperation gpioOp, int value, void* args); +} + +#endif /* LINUX_GPIO_GPIOCALLBACKS_H_ */ diff --git a/fsfwconfig/devices/addresses.h b/fsfwconfig/devices/addresses.h index cd0b9d29..6a13908d 100644 --- a/fsfwconfig/devices/addresses.h +++ b/fsfwconfig/devices/addresses.h @@ -30,6 +30,25 @@ namespace addresses { TMP1075_TCS_2 = 73, }; + enum spiAddresses: address_t { + RTD_IC3, + RTD_IC4, + RTD_IC5, + RTD_IC6, + RTD_IC7, + RTD_IC8, + RTD_IC9, + RTD_IC10, + RTD_IC11, + RTD_IC12, + RTD_IC13, + RTD_IC14, + RTD_IC15, + RTD_IC16, + RTD_IC17, + RTD_IC18 + }; + /* Addresses of devices supporting the CSP protocol */ enum cspAddresses: uint8_t { P60DOCK = 4, diff --git a/fsfwconfig/devices/gpioIds.h b/fsfwconfig/devices/gpioIds.h index 8963bd20..df49c0b7 100644 --- a/fsfwconfig/devices/gpioIds.h +++ b/fsfwconfig/devices/gpioIds.h @@ -25,7 +25,31 @@ namespace gpioIds { MGM_3_RM3100_CS, TEST_ID_0, - TEST_ID_1 + TEST_ID_1, + + RTD_IC3, + RTD_IC4, + RTD_IC5, + RTD_IC6, + RTD_IC7, + RTD_IC8, + RTD_IC9, + RTD_IC10, + RTD_IC11, + RTD_IC12, + RTD_IC13, + RTD_IC14, + RTD_IC15, + RTD_IC16, + RTD_IC17, + RTD_IC18, + + SPI_MUX_BIT_1, + SPI_MUX_BIT_2, + SPI_MUX_BIT_3, + SPI_MUX_BIT_4, + SPI_MUX_BIT_5, + SPI_MUX_BIT_6 }; } diff --git a/fsfwconfig/objects/systemObjectList.h b/fsfwconfig/objects/systemObjectList.h index f05becbe..8bbd9c2d 100644 --- a/fsfwconfig/objects/systemObjectList.h +++ b/fsfwconfig/objects/systemObjectList.h @@ -59,6 +59,26 @@ namespace objects { /* 0x54 ('T') for thermal objects */ HEATER_HANDLER = 0x54000003, + /** + * Not yet specified which pt1000 will measure which device/location in the satellite. + * Therefore object ids are named according to the IC naming of the RTDs in the schematic. + */ + RTD_IC3 = 0x54000004, + RTD_IC4 = 0x54000005, + RTD_IC5 = 0x54000006, + RTD_IC6 = 0x54000007, + RTD_IC7 = 0x54000008, + RTD_IC8 = 0x54000009, + RTD_IC9 = 0x5400000A, + RTD_IC10 = 0x5400000B, + RTD_IC11 = 0x5400000C, + RTD_IC12 = 0x5400000D, + RTD_IC13 = 0x5400000E, + RTD_IC14 = 0x5400000F, + RTD_IC15 = 0x5400001F, + RTD_IC16 = 0x5400002F, + RTD_IC17 = 0x5400003F, + RTD_IC18 = 0x5400004F, /* 0x54 ('T') for test handlers */ TEST_TASK = 0x54694269, diff --git a/linux/boardtest/SpiTestClass.cpp b/linux/boardtest/SpiTestClass.cpp index df32ec5b..2f68bea0 100644 --- a/linux/boardtest/SpiTestClass.cpp +++ b/linux/boardtest/SpiTestClass.cpp @@ -137,37 +137,37 @@ void SpiTestClass::acsInit() { { GpiodRegular gpio(rpiGpioName, mgm0Lis3ChipSelect, "MGM_0_LIS3", gpio::Direction::OUT, 1); - gpioCookie->addGpio(gpioIds::MGM_0_LIS3_CS, gpio); + gpioCookie->addGpio(gpioIds::MGM_0_LIS3_CS, &gpio); } { GpiodRegular gpio(rpiGpioName, mgm1Rm3100ChipSelect, "MGM_1_RM3100", gpio::Direction::OUT, 1); - gpioCookie->addGpio(gpioIds::MGM_1_RM3100_CS, gpio); + gpioCookie->addGpio(gpioIds::MGM_1_RM3100_CS, &gpio); } { GpiodRegular gpio(rpiGpioName, gyro0AdisChipSelect, "GYRO_0_ADIS", gpio::Direction::OUT, 1); - gpioCookie->addGpio(gpioIds::GYRO_0_ADIS_CS, gpio); + gpioCookie->addGpio(gpioIds::GYRO_0_ADIS_CS, &gpio); } { GpiodRegular gpio(rpiGpioName, gyro1L3gd20ChipSelect, "GYRO_1_L3G", gpio::Direction::OUT, 1); - gpioCookie->addGpio(gpioIds::GYRO_1_L3G_CS, gpio); + gpioCookie->addGpio(gpioIds::GYRO_1_L3G_CS, &gpio); } { GpiodRegular gpio(rpiGpioName, gyro2L3gd20ChipSelect, "GYRO_2_L3G", gpio::Direction::OUT, 1); - gpioCookie->addGpio(gpioIds::GYRO_2_L3G_CS, gpio); + gpioCookie->addGpio(gpioIds::GYRO_2_L3G_CS, &gpio); } { GpiodRegular gpio(rpiGpioName, mgm2Lis3mdlChipSelect, "MGM_2_LIS3", gpio::Direction::OUT, 1); - gpioCookie->addGpio(gpioIds::MGM_2_LIS3_CS, gpio); + gpioCookie->addGpio(gpioIds::MGM_2_LIS3_CS, &gpio); } { GpiodRegular gpio(rpiGpioName, mgm3Rm3100ChipSelect, "MGM_3_RM3100", gpio::Direction::OUT, 1); - gpioCookie->addGpio(gpioIds::MGM_3_RM3100_CS, gpio); + gpioCookie->addGpio(gpioIds::MGM_3_RM3100_CS, &gpio); } if(gpioIF != nullptr) { gpioIF->addGpios(gpioCookie); diff --git a/linux/gpio/GpioCookie.cpp b/linux/gpio/GpioCookie.cpp index f957d070..50b42307 100644 --- a/linux/gpio/GpioCookie.cpp +++ b/linux/gpio/GpioCookie.cpp @@ -4,10 +4,14 @@ GpioCookie::GpioCookie() { } -ReturnValue_t GpioCookie::addGpio(gpioId_t gpioId, GpiodRegular& gpioConfig){ +ReturnValue_t GpioCookie::addGpio(gpioId_t gpioId, GpioBase* gpioConfig){ + if (gpioConfig == nullptr) { + sif::debug << "GpioCookie::addGpio: gpioConfig is nullpointer" << std::endl; + return HasReturnvaluesIF::RETURN_FAILED; + } auto gpioMapIter = gpioMap.find(gpioId); if(gpioMapIter == gpioMap.end()) { - auto statusPair = gpioMap.emplace(gpioId, new GpiodRegular(gpioConfig)); + auto statusPair = gpioMap.emplace(gpioId, gpioConfig); if (statusPair.second == false) { #if FSFW_VERBOSE_LEVEL >= 1 sif::error << "GpioCookie::addGpio: Failed to add GPIO " << gpioId << diff --git a/linux/gpio/GpioCookie.h b/linux/gpio/GpioCookie.h index c7721a98..3f8531ee 100644 --- a/linux/gpio/GpioCookie.h +++ b/linux/gpio/GpioCookie.h @@ -23,7 +23,7 @@ public: virtual ~GpioCookie(); - ReturnValue_t addGpio(gpioId_t gpioId, GpiodRegular& gpioConfig); + ReturnValue_t addGpio(gpioId_t gpioId, GpioBase* gpioConfig); /** * @brief Get map with registered GPIOs. */ diff --git a/linux/gpio/LinuxLibgpioIF.cpp b/linux/gpio/LinuxLibgpioIF.cpp index cdf22a45..0711a1a2 100644 --- a/linux/gpio/LinuxLibgpioIF.cpp +++ b/linux/gpio/LinuxLibgpioIF.cpp @@ -60,7 +60,7 @@ ReturnValue_t LinuxLibgpioIF::configureGpios(GpioMap& mapToAdd) { if(gpioCallback->callback == nullptr) { return GPIO_INVALID_INSTANCE; } - gpioCallback->callback(gpioMapIter->first, gpio::GpioOperation::READ, + gpioCallback->callback(gpioMapIter->first, gpio::GpioOperation::WRITE, gpioCallback->initValue, gpioCallback->callbackArgs); } } diff --git a/linux/spi/SpiCookie.h b/linux/spi/SpiCookie.h index 42004993..1efbc0bd 100644 --- a/linux/spi/SpiCookie.h +++ b/linux/spi/SpiCookie.h @@ -17,6 +17,7 @@ public: * @param chipSelect Chip select. gpio::NO_GPIO can be used for hardware slave selects. * @param spiDev * @param maxSize + * @param spieSpeed SPI clock frequency in Hz. */ SpiCookie(address_t spiAddress, gpioId_t chipSelect, std::string spiDev, const size_t maxReplySize, spi::SpiMode spiMode, uint32_t spiSpeed); diff --git a/mission/devices/CMakeLists.txt b/mission/devices/CMakeLists.txt index 906b172b..a1617d07 100644 --- a/mission/devices/CMakeLists.txt +++ b/mission/devices/CMakeLists.txt @@ -11,6 +11,7 @@ target_sources(${TARGET_NAME} PUBLIC PDU2Handler.cpp ACUHandler.cpp SyrlinksHkHandler.cpp + Max31865PT1000Handler.cpp ) diff --git a/mission/devices/Max31865PT1000Handler.cpp b/mission/devices/Max31865PT1000Handler.cpp index ddf12d2f..c6d98c0a 100644 --- a/mission/devices/Max31865PT1000Handler.cpp +++ b/mission/devices/Max31865PT1000Handler.cpp @@ -1,6 +1,7 @@ +#include "Max31865PT1000Handler.h" + #include #include -#include "Max31865PT100Handler.h" Max31865PT1000Handler::Max31865PT1000Handler(object_id_t objectId, object_id_t comIF, CookieIF *comCookie, uint8_t switchId): @@ -53,11 +54,11 @@ void Max31865PT1000Handler::doShutDown() { ReturnValue_t Max31865PT1000Handler::buildNormalDeviceCommand( DeviceCommandId_t *id) { if(internalState == InternalState::RUNNING) { - *id = TSensorDefinitions::REQUEST_RTD; + *id = Max31865Definitions::REQUEST_RTD; return buildCommandFromCommand(*id, nullptr, 0); } else if(internalState == InternalState::REQUEST_FAULT_BYTE) { - *id = TSensorDefinitions::REQUEST_FAULT_BYTE; + *id = Max31865Definitions::REQUEST_FAULT_BYTE; return buildCommandFromCommand(*id, nullptr, 0); } else { @@ -73,12 +74,12 @@ ReturnValue_t Max31865PT1000Handler::buildTransitionDeviceCommand( case(InternalState::RUNNING): return DeviceHandlerBase::NOTHING_TO_SEND; case(InternalState::CONFIGURE): { - *id = TSensorDefinitions::CONFIG_CMD; + *id = Max31865Definitions::CONFIG_CMD; uint8_t config[1] = {DEFAULT_CONFIG}; return buildCommandFromCommand(*id, config, 1); } case(InternalState::REQUEST_CONFIG): { - *id = TSensorDefinitions::REQUEST_CONFIG; + *id = Max31865Definitions::REQUEST_CONFIG; return buildCommandFromCommand(*id, nullptr, 0); } @@ -96,8 +97,8 @@ ReturnValue_t Max31865PT1000Handler::buildCommandFromCommand( DeviceCommandId_t deviceCommand, const uint8_t *commandData, size_t commandDataLen) { switch(deviceCommand) { - case(TSensorDefinitions::CONFIG_CMD) : { - commandBuffer[0] = static_cast(TSensorDefinitions::CONFIG_CMD); + case(Max31865Definitions::CONFIG_CMD) : { + commandBuffer[0] = static_cast(Max31865Definitions::CONFIG_CMD); if(commandDataLen == 1) { commandBuffer[1] = commandData[0]; DeviceHandlerBase::rawPacketLen = 2; @@ -108,17 +109,17 @@ ReturnValue_t Max31865PT1000Handler::buildCommandFromCommand( return DeviceHandlerIF::NO_COMMAND_DATA; } } - case(TSensorDefinitions::REQUEST_CONFIG): { + case(Max31865Definitions::REQUEST_CONFIG): { commandBuffer[0] = 0x00; // dummy byte commandBuffer[1] = static_cast( - TSensorDefinitions::REQUEST_CONFIG); + Max31865Definitions::REQUEST_CONFIG); DeviceHandlerBase::rawPacketLen = 2; DeviceHandlerBase::rawPacket = commandBuffer.data(); return HasReturnvaluesIF::RETURN_OK; } - case(TSensorDefinitions::REQUEST_RTD): { + case(Max31865Definitions::REQUEST_RTD): { commandBuffer[0] = static_cast( - TSensorDefinitions::REQUEST_RTD); + Max31865Definitions::REQUEST_RTD); // two dummy bytes commandBuffer[1] = 0x00; commandBuffer[2] = 0x00; @@ -126,9 +127,9 @@ ReturnValue_t Max31865PT1000Handler::buildCommandFromCommand( DeviceHandlerBase::rawPacket = commandBuffer.data(); return HasReturnvaluesIF::RETURN_OK; } - case(TSensorDefinitions::REQUEST_FAULT_BYTE): { + case(Max31865Definitions::REQUEST_FAULT_BYTE): { commandBuffer[0] = static_cast( - TSensorDefinitions::REQUEST_FAULT_BYTE); + Max31865Definitions::REQUEST_FAULT_BYTE); commandBuffer[1] = 0x00; DeviceHandlerBase::rawPacketLen = 2; DeviceHandlerBase::rawPacket = commandBuffer.data(); @@ -141,11 +142,11 @@ ReturnValue_t Max31865PT1000Handler::buildCommandFromCommand( } void Max31865PT1000Handler::fillCommandAndReplyMap() { - insertInCommandAndReplyMap(TSensorDefinitions::CONFIG_CMD, 3); - insertInCommandAndReplyMap(TSensorDefinitions::REQUEST_CONFIG, 3); - insertInCommandAndReplyMap(TSensorDefinitions::REQUEST_RTD, 3, + insertInCommandAndReplyMap(Max31865Definitions::CONFIG_CMD, 3); + insertInCommandAndReplyMap(Max31865Definitions::REQUEST_CONFIG, 3); + insertInCommandAndReplyMap(Max31865Definitions::REQUEST_RTD, 3, &sensorDataset); - insertInCommandAndReplyMap(TSensorDefinitions::REQUEST_FAULT_BYTE, 3); + insertInCommandAndReplyMap(Max31865Definitions::REQUEST_FAULT_BYTE, 3); } ReturnValue_t Max31865PT1000Handler::scanForReply(const uint8_t *start, @@ -155,7 +156,7 @@ ReturnValue_t Max31865PT1000Handler::scanForReply(const uint8_t *start, if(remainingSize == rtdReplySize and internalState == InternalState::RUNNING) { - *foundId = TSensorDefinitions::REQUEST_RTD; + *foundId = Max31865Definitions::REQUEST_RTD; *foundLen = rtdReplySize; } @@ -163,15 +164,15 @@ ReturnValue_t Max31865PT1000Handler::scanForReply(const uint8_t *start, if(internalState == InternalState::CONFIGURE) { commandExecuted = true; *foundLen = configReplySize; - *foundId = TSensorDefinitions::CONFIG_CMD; + *foundId = Max31865Definitions::CONFIG_CMD; } else if(internalState == InternalState::REQUEST_FAULT_BYTE) { - *foundId = TSensorDefinitions::REQUEST_FAULT_BYTE; + *foundId = Max31865Definitions::REQUEST_FAULT_BYTE; *foundLen = 2; internalState = InternalState::RUNNING; } else { - *foundId = TSensorDefinitions::REQUEST_CONFIG; + *foundId = Max31865Definitions::REQUEST_CONFIG; *foundLen = configReplySize; } } @@ -182,7 +183,7 @@ ReturnValue_t Max31865PT1000Handler::scanForReply(const uint8_t *start, ReturnValue_t Max31865PT1000Handler::interpretDeviceReply( DeviceCommandId_t id, const uint8_t *packet) { switch(id) { - case(TSensorDefinitions::REQUEST_CONFIG): { + case(Max31865Definitions::REQUEST_CONFIG): { if(packet[1] != DEFAULT_CONFIG) { #if FSFW_CPP_OSTREAM_ENABLED == 1 // it propably would be better if we at least try one restart.. @@ -202,7 +203,7 @@ ReturnValue_t Max31865PT1000Handler::interpretDeviceReply( } break; } - case(TSensorDefinitions::REQUEST_RTD): { + case(Max31865Definitions::REQUEST_RTD): { // first bit of LSB reply byte is the fault bit uint8_t faultBit = packet[2] & 0b0000'0001; if(faultBit == 1) { @@ -272,7 +273,7 @@ ReturnValue_t Max31865PT1000Handler::interpretDeviceReply( break; } - case(TSensorDefinitions::REQUEST_FAULT_BYTE): { + case(Max31865Definitions::REQUEST_FAULT_BYTE): { faultByte = packet[1]; #if OBSW_VERBOSE_LEVEL >= 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 @@ -343,9 +344,9 @@ void Max31865PT1000Handler::doTransition(Mode_t modeFrom, ReturnValue_t Max31865PT1000Handler::initializeLocalDataPool(localpool::DataPool& localDataPoolMap, LocalDataPoolManager& poolManager) { - localDataPoolMap.emplace(TSensorDefinitions::PoolIds::TEMPERATURE_C, + localDataPoolMap.emplace(Max31865Definitions::PoolIds::TEMPERATURE_C, new PoolEntry({0}, 1, true)); - localDataPoolMap.emplace(TSensorDefinitions::PoolIds::FAULT_BYTE, + localDataPoolMap.emplace(Max31865Definitions::PoolIds::FAULT_BYTE, new PoolEntry({0})); poolManager.subscribeForPeriodicPacket(sensorDatasetSid, false, 4.0, false); diff --git a/mission/devices/Max31865PT100Handler.h b/mission/devices/Max31865PT1000Handler.h similarity index 92% rename from mission/devices/Max31865PT100Handler.h rename to mission/devices/Max31865PT1000Handler.h index 9375eee9..19780df2 100644 --- a/mission/devices/Max31865PT100Handler.h +++ b/mission/devices/Max31865PT1000Handler.h @@ -1,7 +1,6 @@ -#ifndef MISSION_DEVICES_MAX31865PT100HANDLER_H_ -#define MISSION_DEVICES_MAX31865PT100HANDLER_H_ +#ifndef MISSION_DEVICES_MAX31865PT1000HANDLER_H_ +#define MISSION_DEVICES_MAX31865PT1000HANDLER_H_ -#include "devicedefinitions/ThermalSensorPacket.h" #include #include @@ -9,6 +8,7 @@ #include #include +#include "devicedefinitions/Max31865Definitions.h" /** * @brief Device Handler for the thermal sensors @@ -92,7 +92,7 @@ private: uint8_t faultByte = 0; std::array commandBuffer { 0 }; - TSensorDefinitions::ThermalSensorDataset sensorDataset; + Max31865Definitions::Max31865Set sensorDataset; sid_t sensorDatasetSid; #if OBSW_VERBOSE_LEVEL >= 1 @@ -100,5 +100,5 @@ private: #endif }; -#endif /* MISSION_DEVICES_MAX31865PT100HANDLER_H_ */ +#endif /* MISSION_DEVICES_MAX31865PT1000HANDLER_H_ */ diff --git a/mission/devices/devicedefinitions/ThermalSensorPacket.h b/mission/devices/devicedefinitions/Max31865Definitions.h similarity index 65% rename from mission/devices/devicedefinitions/ThermalSensorPacket.h rename to mission/devices/devicedefinitions/Max31865Definitions.h index ba6f2d13..d21f41e4 100644 --- a/mission/devices/devicedefinitions/ThermalSensorPacket.h +++ b/mission/devices/devicedefinitions/Max31865Definitions.h @@ -6,15 +6,7 @@ #include #include -namespace TSensorDefinitions { - -enum ObjIds: object_id_t { - TEST_HKB_HANDLER = objects::SPI_Test_PT1000, - SYRLINKS_HANDLER = objects::PT1000_Syrlinks_DEC1_O1, - MGT_1_HANDLER = objects::PT1000_MGT1_DEC2, - PLOC_HANDLER = objects::PT1000_PLOC_DEC4, - MESHCAM_HANDLER = objects::PT1000_Camera_DEC1_O2 -}; +namespace Max31865Definitions { enum PoolIds: lp_id_t { TEMPERATURE_C, @@ -26,9 +18,11 @@ static constexpr DeviceCommandId_t REQUEST_CONFIG = 0x00; static constexpr DeviceCommandId_t REQUEST_RTD = 0x01; static constexpr DeviceCommandId_t REQUEST_FAULT_BYTE = 0x07; -static constexpr uint32_t THERMAL_SENSOR_SET_ID = REQUEST_RTD; +static constexpr uint32_t MAX31865_SET_ID = REQUEST_RTD; -class ThermalSensorDataset: +static constexpr size_t MAX_REPLY_SIZE = 5; + +class Max31865Set: public StaticLocalDataSet { public: /** @@ -36,16 +30,16 @@ public: * @param owner * @param setId */ - ThermalSensorDataset(HasLocalDataPoolIF* owner): - StaticLocalDataSet(owner, THERMAL_SENSOR_SET_ID) { + Max31865Set(HasLocalDataPoolIF* owner): + StaticLocalDataSet(owner, MAX31865_SET_ID) { } /** * Constructor used by data users like controllers. * @param sid */ - ThermalSensorDataset(object_id_t objectId): - StaticLocalDataSet(sid_t(objectId, THERMAL_SENSOR_SET_ID)) { + Max31865Set(object_id_t objectId): + StaticLocalDataSet(sid_t(objectId, MAX31865_SET_ID)) { } lp_var_t temperatureCelcius = lp_var_t(sid.objectId, From 9a55eb5508eb52be30fef5ccb736451592a017da Mon Sep 17 00:00:00 2001 From: "Jakob.Meier" Date: Wed, 17 Mar 2021 11:14:48 +0100 Subject: [PATCH 16/79] IMQT wip --- fsfwconfig/OBSWConfig.h | 3 +- fsfwconfig/returnvalues/classIds.h | 1 + mission/devices/IMTQHandler.cpp | 241 ++++++++++++++++++ mission/devices/IMTQHandler.h | 79 ++++++ .../IMTQHandlerDefinitions.h | 110 ++++++++ 5 files changed, 433 insertions(+), 1 deletion(-) create mode 100644 mission/devices/IMTQHandler.cpp create mode 100644 mission/devices/IMTQHandler.h create mode 100644 mission/devices/devicedefinitions/IMTQHandlerDefinitions.h diff --git a/fsfwconfig/OBSWConfig.h b/fsfwconfig/OBSWConfig.h index 5a9106b5..c64e1a56 100644 --- a/fsfwconfig/OBSWConfig.h +++ b/fsfwconfig/OBSWConfig.h @@ -25,7 +25,8 @@ debugging. */ #define PDU1_DEBUG 0 #define PDU2_DEBUG 0 #define ACU_DEBUG 0 -#define SYRLINKS_DEBUG 1 +#define SYRLINKS_DEBUG 0 +#define IMQT_DEBUG 1 #include "OBSWVersion.h" diff --git a/fsfwconfig/returnvalues/classIds.h b/fsfwconfig/returnvalues/classIds.h index 51412cbf..9a47ea19 100644 --- a/fsfwconfig/returnvalues/classIds.h +++ b/fsfwconfig/returnvalues/classIds.h @@ -19,6 +19,7 @@ enum { HEATER_HANDLER, SA_DEPL_HANDLER, SYRLINKS_HANDLER, + IMQT_HANDLER, }; } diff --git a/mission/devices/IMTQHandler.cpp b/mission/devices/IMTQHandler.cpp new file mode 100644 index 00000000..7ebeff05 --- /dev/null +++ b/mission/devices/IMTQHandler.cpp @@ -0,0 +1,241 @@ +#include "IMTQHandler.h" + +#include +#include +#include +#include + +IMTQHandler::IMTQHandler(object_id_t objectId, object_id_t comIF, CookieIF * comCookie) : + DeviceHandlerBase(objectId, comIF, comCookie), engHkDataset(this) { + if (comCookie == NULL) { + sif::error << "IMTQHandler: Invalid com cookie" << std::endl; + } +} + +IMTQHandler::~IMTQHandler() { +} + + +void IMTQHandler::doStartUp(){ + if(mode == _MODE_START_UP){ + setMode(MODE_ON); + } +} + +void IMTQHandler::doShutDown(){ + +} + +ReturnValue_t IMTQHandler::buildNormalDeviceCommand( + DeviceCommandId_t * id) { + *id = IMTQ::GET_ENG_HK_DATA; + return buildCommandFromCommand(*id, NULL, 0); +} + +ReturnValue_t IMTQHandler::buildTransitionDeviceCommand( + DeviceCommandId_t * id){ + return HasReturnvaluesIF::RETURN_OK; +} + +ReturnValue_t IMTQHandler::buildCommandFromCommand( + DeviceCommandId_t deviceCommand, const uint8_t * commandData, + size_t commandDataLen) { + switch(deviceCommand) { + case(IMTQ::GET_ENG_HK_DATA): { + commandBuffer[0] = IMTQ::CC::GET_ENG_HK_DATA; + rawPacket = commandBuffer; + return RETURN_OK; + } + case(IMTQ::START_ACTUATION_DIPOLE): { + commandBuffer[0] = IMTQ::CC::START_ACTUATION_DIPOLE; + commandBuffer[1] = *(commandData + 1); + commandBuffer[2] = *(commandData + 2); + rawPacket = commandBuffer; + return RETURN_OK; + } + default: + return DeviceHandlerIF::COMMAND_NOT_IMPLEMENTED; + } + return HasReturnvaluesIF::RETURN_FAILED; +} + +void IMTQHandler::fillCommandAndReplyMap() { + this->insertInCommandAndReplyMap(IMTQ::GET_ENG_HK_DATA, 1, &engHkDataset, + IMTQ::SIZE_ENG_HK_COMMAND, false, true, IMTQ::SIZE_ENG_HK_DATA); +} + +ReturnValue_t IMTQHandler::scanForReply(const uint8_t *start, + size_t remainingSize, DeviceCommandId_t *foundId, size_t *foundLen) { + + ReturnValue_t result = RETURN_OK; + + switch(*start) { + case(IMTQ::CC::GET_ENG_HK_DATA): + *foundLen = IMTQ::SIZE_ENG_HK_DATA_REPLY; + *foundId = IMTQ::GET_ENG_HK_DATA; + break; + default: + sif::debug << "IMTQHandler::scanForReply: Reply contains invalid command code" << std::endl; + result = IGNORE_REPLY_DATA; + break; + } + + return result; +} + +ReturnValue_t IMTQHandler::interpretDeviceReply(DeviceCommandId_t id, + const uint8_t *packet) { + + ReturnValue_t result = RETURN_OK; + + result = parseStatusByte(packet); + + if (result != RETURN_OK) { + return result; + } + + switch (id) { + case (IMTQ::GET_ENG_HK_DATA): + fillEngHkDataset(packet); + break; + default: { + sif::debug << "IMTQHandler::interpretDeviceReply: Unknown device reply id" << std::endl; + return DeviceHandlerIF::UNKNOWN_DEVICE_REPLY; + } + } + + return RETURN_OK; +} + +ReturnValue_t IMTQHandler::parseStatusByte(const uint8_t* packet) { + uint8_t cmdErrorField = *(packet + 1) & 0xF; + switch (cmdErrorField) { + case 0: + return RETURN_OK; + case 1: + return REJECTED_WITHOUT_REASON; + case 2: + return INVALID_COMMAND_CODE; + case 3: + return PARAMETER_MISSING; + case 4: + return PARAMETER_INVALID; + case 5: + return CC_UNAVAILABLE; + case 7: + return INTERNAL_PROCESSING_ERROR; + default: + sif::error << "IMTQHandler::parseStatusByte: CMD Error field contains unknown error code " + << cmdErrorField << std::endl; + return CMD_ERR_UNKNOWN; + } +} + +void IMTQHandler::fillEngHkDataset(const uint8_t* packet) { + uint8_t offset = 2; + engHkDataset.digitalVoltageMv = *(packet + offset + 1) | *(packet + offset); + offset += 2; + engHkDataset.analogVoltageMv = *(packet + offset + 1) | *(packet + offset); + offset += 2; + engHkDataset.digitalCurrentA = (*(packet + offset + 1) | *(packet + offset)) * 0.0001; + offset += 2; + engHkDataset.analogCurrentA = (*(packet + offset + 1) | *(packet + offset)) * 0.0001; + offset += 2; + engHkDataset.coilXcurrentA = (*(packet + offset + 1) | *(packet + offset)) * 0.0001; + offset += 2; + engHkDataset.coilYcurrentA = (*(packet + offset + 1) | *(packet + offset)) * 0.0001; + offset += 2; + engHkDataset.coilZcurrentA = (*(packet + offset + 1) | *(packet + offset)) * 0.0001; + offset += 2; + engHkDataset.coilXTemperature = (*(packet + offset + 1) | *(packet + offset)); + offset += 2; + engHkDataset.coilYTemperature = (*(packet + offset + 1) | *(packet + offset)); + offset += 2; + engHkDataset.coilZTemperature = (*(packet + offset + 1) | *(packet + offset)); + offset += 2; + engHkDataset.mcuTemperature = (*(packet + offset + 1) | *(packet + offset)); + +#if OBSW_VERBOSE_LEVEL >= 1 && IMTQ_DEBUG == 1 + sif::info << "IMTQ digital voltage: " << engHkDataset.digitalVoltageMv << " mV" << std::endl; + sif::info << "IMTQ analog voltage: " << engHkDataset.analogVoltageMv << " mV" << std::endl; + sif::info << "IMTQ digital current: " << engHkDataset.digitalCurrentA << " A" << std::endl; + sif::info << "IMTQ analog current: " << engHkDataset.analogCurrentA << " A" << std::endl; + sif::info << "IMTQ coil X current: " << engHkDataset.coilXcurrentA << " A" << std::endl; + sif::info << "IMTQ coil Y current: " << engHkDataset.coilYcurrentA << " A" << std::endl; + sif::info << "IMTQ coil Z current: " << engHkDataset.coilZcurrentA << " A" << std::endl; + sif::info << "IMTQ coil X temperature: " << engHkDataset.coilXTemperature << " °C" + << std::endl; + sif::info << "IMTQ coil Y temperature: " << engHkDataset.coilYTemperature << " °C" + << std::endl; + sif::info << "IMTQ coil Z temperature: " << engHkDataset.coilZTemperature << " °C" + << std::endl; + sif::info << "IMTQ coil MCU temperature: " << engHkDataset.mcuTemperature << " °C" + << std::endl; +#endif +} + + +void IMTQHandler::parseRxStatusRegistersReply(const uint8_t* packet) { + PoolReadHelper readHelper(&rxDataset); + uint16_t offset = SYRLINKS::MESSAGE_HEADER_SIZE; + rxDataset.rxStatus = convertHexStringToUint8(reinterpret_cast(packet + offset)); + offset += 2; + rxDataset.rxSensitivity = convertHexStringToUint32(reinterpret_cast(packet + offset), 6); + offset += 6; + rxDataset.rxFrequencyShift = convertHexStringToUint32(reinterpret_cast(packet + offset), 6); + offset += 6; + rxDataset.rxIqPower = convertHexStringToUint16(reinterpret_cast(packet + offset)); + offset += 4; + rxDataset.rxAgcValue = convertHexStringToUint16(reinterpret_cast(packet + offset)); + offset += 4; + offset += 2; // reserved register + rxDataset.rxDemodEb= convertHexStringToUint32(reinterpret_cast(packet + offset), 6); + offset += 6; + rxDataset.rxDemodN0= convertHexStringToUint32(reinterpret_cast(packet + offset), 6); + offset += 6; + rxDataset.rxDataRate = convertHexStringToUint8(reinterpret_cast(packet + offset)); + +#if OBSW_VERBOSE_LEVEL >= 1 && SYRLINKS_DEBUG == 1 + sif::info << "Syrlinks RX Status: 0x" << std::hex << (unsigned int)rxDataset.rxStatus.value << std::endl; + sif::info << "Syrlinks RX Sensitivity: " << std::dec << rxDataset.rxSensitivity << std::endl; + sif::info << "Syrlinks RX Frequency Shift: " << rxDataset.rxFrequencyShift << std::endl; + sif::info << "Syrlinks RX IQ Power: " << rxDataset.rxIqPower << std::endl; + sif::info << "Syrlinks RX AGC Value: " << rxDataset.rxAgcValue << std::endl; + sif::info << "Syrlinks RX Demod Eb: " << rxDataset.rxDemodEb << std::endl; + sif::info << "Syrlinks RX Demod N0: " << rxDataset.rxDemodN0 << std::endl; + sif::info << "Syrlinks RX Datarate: " << (unsigned int)rxDataset.rxDataRate.value << std::endl; +#endif +} + + + +void IMTQHandler::setNormalDatapoolEntriesInvalid(){ + +} + +uint32_t IMTQHandler::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo){ + return 500; +} + +ReturnValue_t IMTQHandler::initializeLocalDataPool(localpool::DataPool& localDataPoolMap, + LocalDataPoolManager& poolManager) { + + localDataPoolMap.emplace(IMTQ::DIGITAL_VOLTAGE_MV, new PoolEntry( { 0 })); + localDataPoolMap.emplace(IMTQ::ANALOG_VOLTAGE_MV, new PoolEntry( { 0 })); + localDataPoolMap.emplace(IMTQ::DIGITAL_CURRENT_A, new PoolEntry( { 0 })); + localDataPoolMap.emplace(IMTQ::ANALOG_CURRENT_A, new PoolEntry( { 0 })); + localDataPoolMap.emplace(IMTQ::COIL_X_CURRENT_A, new PoolEntry( { 0 })); + localDataPoolMap.emplace(IMTQ::COIL_Y_CURRENT_A, new PoolEntry( { 0 })); + localDataPoolMap.emplace(IMTQ::COIL_Z_CURRENT_A, new PoolEntry( { 0 })); + localDataPoolMap.emplace(IMTQ::COIL_X_TEMPERATURE, new PoolEntry( { 0 })); + localDataPoolMap.emplace(IMTQ::COIL_Y_TEMPERATURE, new PoolEntry( { 0 })); + localDataPoolMap.emplace(IMTQ::COIL_Z_TEMPERATURE, new PoolEntry( { 0 })); + localDataPoolMap.emplace(IMTQ::MCU_TEMPERATURE, new PoolEntry( { 0 })); + + return HasReturnvaluesIF::RETURN_OK; +} + +void IMTQHandler::setModeNormal() { + mode = MODE_NORMAL; +} + diff --git a/mission/devices/IMTQHandler.h b/mission/devices/IMTQHandler.h new file mode 100644 index 00000000..207b7560 --- /dev/null +++ b/mission/devices/IMTQHandler.h @@ -0,0 +1,79 @@ +#ifndef MISSION_DEVICES_IMTQHANDLER_H_ +#define MISSION_DEVICES_IMTQHANDLER_H_ + +#include +#include +#include + +/** + * @brief This is the device handler for the ISIS Magnetorquer iMTQ. + * + * @author J. Meier + */ +class IMTQHandler: public DeviceHandlerBase { +public: + + IMTQHandler(object_id_t objectId, object_id_t comIF, + CookieIF * comCookie); + virtual ~IMTQHandler(); + + /** + * @brief Sets mode to MODE_NORMAL. Can be used for debugging. + */ + void setModeNormal(); + +protected: + void doStartUp() override; + void doShutDown() override; + ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t * id) override; + ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t * id) override; + void fillCommandAndReplyMap() override; + ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, + const uint8_t * commandData,size_t commandDataLen) override; + ReturnValue_t scanForReply(const uint8_t *start, size_t remainingSize, + DeviceCommandId_t *foundId, size_t *foundLen) override; + ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, + const uint8_t *packet) override; + void setNormalDatapoolEntriesInvalid() override; + uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override; + ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap, + LocalDataPoolManager& poolManager) override; + LocalPoolDataSetBase* getDataSetHandle(sid_t sid) override; + +private: + + static const uint8_t INTERFACE_ID = CLASS_ID::IMTQ_HANDLER; + + static const ReturnValue_t INVALID_COMMAND_CODE = MAKE_RETURN_CODE(0xA0); + static const ReturnValue_t PARAMETER_MISSING = MAKE_RETURN_CODE(0xA1); + static const ReturnValue_t PARAMETER_INVALID = MAKE_RETURN_CODE(0xA2); + static const ReturnValue_t CC_UNAVAILABLE = MAKE_RETURN_CODE(0xA3); + static const ReturnValue_t INTERNAL_PROCESSING_ERROR = MAKE_RETURN_CODE(0xA4); + static const ReturnValue_t REJECTED_WITHOUT_REASON = MAKE_RETURN_CODE(0xA5); + static const ReturnValue_t CMD_ERR_UNKNOWN = MAKE_RETURN_CODE(0xA6); + + + IMTQ::EngHkDataset engHkDataset; + + uint8_t commandBuffer[IMTQ::MAX_COMMAND_SIZE]; + + /** + * @brief Each reply contains a status byte giving information about a request. This function + * parses this byte and returns the associated failure message. + * + * @param packet Pointer to the received message containing the status byte. + * + * @return The return code derived from the received status byte. + */ + ReturnValue_t parseStatusByte(const uint8_t* packet); + + /** + * @brief This function fills the engineering housekeeping dataset with the received data. + + * @param packet Pointer to the received data. + * + */ + void fillEngHkDataset(const uint8_t* packet); +}; + +#endif /* MISSION_DEVICES_IMTQHANDLER_H_ */ diff --git a/mission/devices/devicedefinitions/IMTQHandlerDefinitions.h b/mission/devices/devicedefinitions/IMTQHandlerDefinitions.h new file mode 100644 index 00000000..34e14dc6 --- /dev/null +++ b/mission/devices/devicedefinitions/IMTQHandlerDefinitions.h @@ -0,0 +1,110 @@ +#ifndef MISSION_DEVICES_DEVICEDEFINITIONS_IMTQDEFINITIONS_H_ +#define MISSION_DEVICES_DEVICEDEFINITIONS_IMTQDEFINITIONS_H_ + +namespace IMTQ { + + static const DeviceCommandId_t NONE = 0x0; + static const DeviceCommandId_t GET_ENG_HK_DATA = 0x1; + static const DeviceCommandId_t START_ACTUATION_DIPOLE = 0x2; + + static const uint8_t GET_TEMP_REPLY_SIZE = 2; + static const uint8_t CFGR_CMD_SIZE = 3; + static const uint8_t POINTER_REG_SIZE = 1; + + static const uint32_t ENG_HK_DATA_SET_ID = GET_ENG_HK_DATA; + static const uint8_t SIZE_ENG_HK_COMMAND = 1; + static const uint8_t SIZE_ENG_HK_DATA_REPLY = 24; + + static const uint8_t MAX_REPLY_SIZE = SIZE_ENG_HK_DATA_REPLY; + static const uint8_t MAX_COMMAND_SIZE = 9; + + static const uint8_t POOL_ENTRIES = 8; + + /** + * Command code definitions. Each command or reply of an IMTQ request will begin with one of + * the following command codes. + */ + namespace CC { + static const uint8_t START_ACTUATION_DIPOLE = 0x6; + static const uint8_t SOFTWARE_RESET = 0xAA; + static const uint8_t GET_ENG_HK_DATA = 0x4A; + }; + + enum IMTQPoolIds: lp_id_t { + DIGITAL_VOLTAGE_MV, + ANALOG_VOLTAGE_MV, + DIGITAL_CURRENT_A, + ANALOG_CURRENT_A, + COIL_X_CURRENT_A, + COIL_Y_CURRENT_A, + COIL_Z_CURRENT_A, + COIL_X_TEMPERATURE, + COIL_Y_TEMPERATURE, + COIL_Z_TEMPERATURE, + MCU_TEMPERATURE + }; + +class EngHkDataset: + public StaticLocalDataSet { +public: + + EngHkDataset(HasLocalDataPoolIF* owner): + StaticLocalDataSet(owner, ENG_HK_DATA_SET_ID) { + } + + EngHkDataset(object_id_t objectId): + StaticLocalDataSet(sid_t(objectId, ENG_HK_DATA_SET_ID)) { + } + + lp_var_t digitalVoltageMv = lp_var_t(sid.objectId, + DIGITAL_VOLTAGE_MV, this); + lp_var_t analogVoltageMv = lp_var_t(sid.objectId, + ANALOG_VOLTAGE_MV, this); + lp_var_t digitalCurrentA = lp_var_t(sid.objectId, + DIGITAL_CURRENT_A, this); + lp_var_t analogCurrentA = lp_var_t(sid.objectId, + ANALOG_CURRENT_A, this); + lp_var_t coilXcurrentA = lp_var_t(sid.objectId, + COIL_X_CURRENT_A, this); + lp_var_t coilYcurrentA = lp_var_t(sid.objectId, + COIL_Y_CURRENT_A, this); + lp_var_t coilZcurrentA = lp_var_t(sid.objectId, + COIL_Z_CURRENT_A, this); + /** All temperatures in [°C] */ + lp_var_t coilXTemperature = lp_var_t(sid.objectId, + COIL_X_TEMPEARTURE, this); + lp_var_t coilYTemperature = lp_var_t(sid.objectId, + COIL_Y_TEMPERATURE, this); + lp_var_t coilZTemperature = lp_var_t(sid.objectId, + COIL_Z_TEMPERATURE, this); + lp_var_t mcuTemperature = lp_var_t(sid.objectId, + MCU_TEMPERATURE, this); +}; + +/** + * @brief This class can be used to ease the generation of an action message commanding the + * IMTQHandler to configure the magnettorquer with the desired dipoles. + */ +class CommandDipolePacket : public SerialLinkedListAdapter { +public: + + CommandDipolePacket() { + setLinks(); + } + +private: + CommandDipolePacket(uint16_t xDipole, uint16_t yDipole, uint16_t zDipole); + void setLinks() { + setStart(&cspPort); + cspPort.setNext(&querySize); + querySize.setNext(&magic); + } + SerializeElement cspPort = GOMSPACE::P60_PORT_GNDWDT_RESET; + SerializeElement querySize = 1; + /* Sending 0x78 to port 9 of a gomspace device resets the ground watchdog */ + SerializeElement magic = 0x78; +}; +} + + +#endif /* MISSION_DEVICES_DEVICEDEFINITIONS_IMTQDEFINITIONS_H_ */ From 97c5d01d2e972b98830eadf14d1911a608bbc477 Mon Sep 17 00:00:00 2001 From: "Jakob.Meier" Date: Fri, 19 Mar 2021 15:33:43 +0100 Subject: [PATCH 17/79] IMTQ dipole actuation command, wip --- mission/devices/IMTQHandler.cpp | 9 ++++- .../IMTQHandlerDefinitions.h | 35 ++++++++++++++----- 2 files changed, 34 insertions(+), 10 deletions(-) diff --git a/mission/devices/IMTQHandler.cpp b/mission/devices/IMTQHandler.cpp index 7ebeff05..d6de4ab2 100644 --- a/mission/devices/IMTQHandler.cpp +++ b/mission/devices/IMTQHandler.cpp @@ -47,9 +47,16 @@ ReturnValue_t IMTQHandler::buildCommandFromCommand( return RETURN_OK; } case(IMTQ::START_ACTUATION_DIPOLE): { + /* IMTQ expects low byte first */ commandBuffer[0] = IMTQ::CC::START_ACTUATION_DIPOLE; commandBuffer[1] = *(commandData + 1); - commandBuffer[2] = *(commandData + 2); + commandBuffer[2] = *(commandData); + commandBuffer[3] = *(commandData + 3); + commandBuffer[4] = *(commandData + 2); + commandBuffer[5] = *(commandData + 5); + commandBuffer[6] = *(commandData + 4); + commandBuffer[7] = *(commandData + 7); + commandBuffer[8] = *(commandData + 6); rawPacket = commandBuffer; return RETURN_OK; } diff --git a/mission/devices/devicedefinitions/IMTQHandlerDefinitions.h b/mission/devices/devicedefinitions/IMTQHandlerDefinitions.h index 34e14dc6..a153e4e2 100644 --- a/mission/devices/devicedefinitions/IMTQHandlerDefinitions.h +++ b/mission/devices/devicedefinitions/IMTQHandlerDefinitions.h @@ -84,6 +84,9 @@ public: /** * @brief This class can be used to ease the generation of an action message commanding the * IMTQHandler to configure the magnettorquer with the desired dipoles. + * + * @details Deserialize the packet, write the deserialized data to the ipc store and store the + * the ipc store address in the action message. */ class CommandDipolePacket : public SerialLinkedListAdapter { public: @@ -93,16 +96,30 @@ public: } private: - CommandDipolePacket(uint16_t xDipole, uint16_t yDipole, uint16_t zDipole); - void setLinks() { - setStart(&cspPort); - cspPort.setNext(&querySize); - querySize.setNext(&magic); + + /** + * @brief Constructor + * + * @param xDipole The dipole of the x coil in 10^-4*Am^2 + * @param yDipole The dipole of the y coil in 10^-4*Am^2 + * @param zDipole The dipole of the z coil in 10^-4*Am^2 + * @param duration The duration in milliseconds the dipole will be generated by the coils. + * When set to 0, the dipole will be generated until a new dipole actuation + * command is sent. + */ + CommandDipolePacket(uint16_t xDipole, uint16_t yDipole, uint16_t zDipole) : + xDipole(xDipole), yDipole(yDipole), zDipole(zDipole), duration(duration) { } - SerializeElement cspPort = GOMSPACE::P60_PORT_GNDWDT_RESET; - SerializeElement querySize = 1; - /* Sending 0x78 to port 9 of a gomspace device resets the ground watchdog */ - SerializeElement magic = 0x78; + void setLinks() { + setStart(&xDipole); + xDipole.setNext(&yDipole); + yDipole.setNext(&zDipole); + zDipole.setNext(&duration); + } + SerializeElement xDipole; + SerializeElement yDipole; + SerializeElement zDipole; + SerializeElement duration; }; } From 3fd5f72d003af8862be6da31a8c1d2bfbfe4b870 Mon Sep 17 00:00:00 2001 From: "Jakob.Meier" Date: Sun, 21 Mar 2021 17:35:14 +0100 Subject: [PATCH 18/79] IMTQHandler wip --- mission/devices/IMTQHandler.cpp | 37 +-------------------------------- 1 file changed, 1 insertion(+), 36 deletions(-) diff --git a/mission/devices/IMTQHandler.cpp b/mission/devices/IMTQHandler.cpp index d6de4ab2..8e592cac 100644 --- a/mission/devices/IMTQHandler.cpp +++ b/mission/devices/IMTQHandler.cpp @@ -2,7 +2,7 @@ #include #include -#include +#include #include IMTQHandler::IMTQHandler(object_id_t objectId, object_id_t comIF, CookieIF * comCookie) : @@ -181,41 +181,6 @@ void IMTQHandler::fillEngHkDataset(const uint8_t* packet) { #endif } - -void IMTQHandler::parseRxStatusRegistersReply(const uint8_t* packet) { - PoolReadHelper readHelper(&rxDataset); - uint16_t offset = SYRLINKS::MESSAGE_HEADER_SIZE; - rxDataset.rxStatus = convertHexStringToUint8(reinterpret_cast(packet + offset)); - offset += 2; - rxDataset.rxSensitivity = convertHexStringToUint32(reinterpret_cast(packet + offset), 6); - offset += 6; - rxDataset.rxFrequencyShift = convertHexStringToUint32(reinterpret_cast(packet + offset), 6); - offset += 6; - rxDataset.rxIqPower = convertHexStringToUint16(reinterpret_cast(packet + offset)); - offset += 4; - rxDataset.rxAgcValue = convertHexStringToUint16(reinterpret_cast(packet + offset)); - offset += 4; - offset += 2; // reserved register - rxDataset.rxDemodEb= convertHexStringToUint32(reinterpret_cast(packet + offset), 6); - offset += 6; - rxDataset.rxDemodN0= convertHexStringToUint32(reinterpret_cast(packet + offset), 6); - offset += 6; - rxDataset.rxDataRate = convertHexStringToUint8(reinterpret_cast(packet + offset)); - -#if OBSW_VERBOSE_LEVEL >= 1 && SYRLINKS_DEBUG == 1 - sif::info << "Syrlinks RX Status: 0x" << std::hex << (unsigned int)rxDataset.rxStatus.value << std::endl; - sif::info << "Syrlinks RX Sensitivity: " << std::dec << rxDataset.rxSensitivity << std::endl; - sif::info << "Syrlinks RX Frequency Shift: " << rxDataset.rxFrequencyShift << std::endl; - sif::info << "Syrlinks RX IQ Power: " << rxDataset.rxIqPower << std::endl; - sif::info << "Syrlinks RX AGC Value: " << rxDataset.rxAgcValue << std::endl; - sif::info << "Syrlinks RX Demod Eb: " << rxDataset.rxDemodEb << std::endl; - sif::info << "Syrlinks RX Demod N0: " << rxDataset.rxDemodN0 << std::endl; - sif::info << "Syrlinks RX Datarate: " << (unsigned int)rxDataset.rxDataRate.value << std::endl; -#endif -} - - - void IMTQHandler::setNormalDatapoolEntriesInvalid(){ } From 58b94642da4c2de1ff169162e781a14950453ebd Mon Sep 17 00:00:00 2001 From: Martin Zietz Date: Mon, 22 Mar 2021 12:17:00 +0100 Subject: [PATCH 19/79] added fsfw --- fsfw | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/fsfw b/fsfw index 91f69aa3..e994d81e 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit 91f69aa34fcdde9d3f6ae1a71e72a084bf3bc49d +Subproject commit e994d81e1862fade52b090311b3978fb59061966 From 88138af39d886986e11f0a281098652f222a4f6f Mon Sep 17 00:00:00 2001 From: Martin Zietz Date: Mon, 22 Mar 2021 13:09:06 +0100 Subject: [PATCH 20/79] solved all merge conflicts --- bsp_q7s/ObjectFactory.cpp | 19 +-- fsfwconfig/objects/systemObjectList.h | 11 -- .../pollingSequenceFactory.cpp | 141 ++++++++++++++++++ linux/boardtest/SpiTestClass.cpp | 14 +- linux/boardtest/SpiTestClass.h | 9 -- linux/gpio/LinuxLibgpioIF.cpp | 4 - mission/devices/MGMHandlerLIS3MDL.cpp | 2 +- mission/devices/SyrlinksHkHandler.cpp | 12 +- 8 files changed, 158 insertions(+), 54 deletions(-) create mode 100644 fsfwconfig/pollingsequence/pollingSequenceFactory.cpp diff --git a/bsp_q7s/ObjectFactory.cpp b/bsp_q7s/ObjectFactory.cpp index c0fd9b4b..054d59c3 100644 --- a/bsp_q7s/ObjectFactory.cpp +++ b/bsp_q7s/ObjectFactory.cpp @@ -8,10 +8,7 @@ #include #include -<<<<<<< HEAD #include -======= ->>>>>>> develop #include #include @@ -20,13 +17,10 @@ #include #include #include -<<<<<<< HEAD #include #include - #include -======= ->>>>>>> develop + #include #include #include @@ -127,18 +121,11 @@ void ObjectFactory::produce(){ * Setting PCDU devices to mode normal immediately after start up because PCDU is always * running. */ -<<<<<<< HEAD /** For now this needs to be commented out because there is no PCDU connected to the OBC */ // p60dockhandler->setModeNormal(); // pdu1handler->setModeNormal(); // pdu2handler->setModeNormal(); // acuhandler->setModeNormal(); -======= - //p60dockhandler->setModeNormal(); - //pdu1handler->setModeNormal(); - //pdu2handler->setModeNormal(); - //acuhandler->setModeNormal(); ->>>>>>> develop #endif /* Temperature sensors */ Tmp1075Handler* tmp1075Handler_1 = new Tmp1075Handler( @@ -224,10 +211,10 @@ void ObjectFactory::produce(){ SpiCookie* spiRtdIc3 = new SpiCookie(addresses::RTD_IC3, gpioIds::RTD_IC3, std::string("/dev/spidev2.0"), Max31865Definitions::MAX_REPLY_SIZE, - spi::SpiMode::MODE_1, 2000000); + spi::SpiModes::MODE_1, 2000000); SpiCookie* spiRtdIc4 = new SpiCookie(addresses::RTD_IC4, gpioIds::RTD_IC4, std::string("/dev/spidev2.0"), Max31865Definitions::MAX_REPLY_SIZE, - spi::SpiMode::MODE_1, 2000000); + spi::SpiModes::MODE_1, 2000000); new Max31865PT1000Handler(objects::RTD_IC3, objects::SPI_COM_IF, spiRtdIc3, 0); // 0 is switchId new Max31865PT1000Handler(objects::RTD_IC4, objects::SPI_COM_IF, spiRtdIc4, 0); diff --git a/fsfwconfig/objects/systemObjectList.h b/fsfwconfig/objects/systemObjectList.h index 715fec4f..9787fc0d 100644 --- a/fsfwconfig/objects/systemObjectList.h +++ b/fsfwconfig/objects/systemObjectList.h @@ -43,14 +43,6 @@ namespace objects { ACU_HANDLER = 0x44000004, TMP1075_HANDLER_1 = 0x44000005, TMP1075_HANDLER_2 = 0x44000006, - MGM_0_LIS3_HANDLER = 0x4400007, - MGM_1_RM3100_HANDLER = 0x44000008, - MGM_2_LIS3_HANDLER = 0x44000009, - MGM_3_RM3100_HANDLER = 0x44000010, - GYRO_0_ADIS_HANDLER = 0x44000011, - GYRO_1_L3G_HANDLER = 0x44000012, - GYRO_2_L3G_HANDLER = 0x44000013, - MGM_0_LIS3_HANDLER = 0x4400007, MGM_1_RM3100_HANDLER = 0x44000008, MGM_2_LIS3_HANDLER = 0x44000009, @@ -62,10 +54,7 @@ namespace objects { /* Custom device handler */ PCDU_HANDLER = 0x44001000, SOLAR_ARRAY_DEPL_HANDLER = 0x44001001, -<<<<<<< HEAD SYRLINKS_HK_HANDLER = 0x44000009, -======= ->>>>>>> develop /* 0x54 ('T') for thermal objects */ HEATER_HANDLER = 0x54000003, diff --git a/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp b/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp new file mode 100644 index 00000000..04b1367b --- /dev/null +++ b/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp @@ -0,0 +1,141 @@ +#include "pollingSequenceFactory.h" + +#include +#include +#include +#include +#include + + +ReturnValue_t pst::pollingSequenceInitDefault(FixedTimeslotTaskIF *thisSequence) +{ + /* Length of a communication cycle */ + uint32_t length = thisSequence->getPeriodMs(); + + thisSequence->addSlot(objects::TMP1075_HANDLER_1, length * 0, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::TMP1075_HANDLER_2, length * 0, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::HEATER_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::SOLAR_ARRAY_DEPL_HANDLER, length * 0, + DeviceHandlerIF::PERFORM_OPERATION); + + thisSequence->addSlot(objects::TMP1075_HANDLER_1, length * 0.2, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::TMP1075_HANDLER_2, length * 0.2, DeviceHandlerIF::SEND_WRITE); + + thisSequence->addSlot(objects::TMP1075_HANDLER_1, length * 0.4, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::TMP1075_HANDLER_2, length * 0.4, DeviceHandlerIF::GET_WRITE); + + thisSequence->addSlot(objects::TMP1075_HANDLER_1, length * 0.6, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::TMP1075_HANDLER_2, length * 0.6, DeviceHandlerIF::SEND_READ); + + thisSequence->addSlot(objects::TMP1075_HANDLER_1, length * 0.8, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::TMP1075_HANDLER_2, length * 0.8, DeviceHandlerIF::GET_READ); + + if (thisSequence->checkSequence() == HasReturnvaluesIF::RETURN_OK) { + return HasReturnvaluesIF::RETURN_OK; + } + + sif::error << "PollingSequence::initialize has errors!" << std::endl; + return HasReturnvaluesIF::RETURN_FAILED; +} + +ReturnValue_t pst::gomspacePstInit(FixedTimeslotTaskIF *thisSequence){ + uint32_t length = thisSequence->getPeriodMs(); + + thisSequence->addSlot(objects::PCDU_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::PCDU_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + + thisSequence->addSlot(objects::P60DOCK_HANDLER, + length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::PDU1_HANDLER, + length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::PDU2_HANDLER, + length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::ACU_HANDLER, + length * 0, DeviceHandlerIF::PERFORM_OPERATION); + + thisSequence->addSlot(objects::P60DOCK_HANDLER, + length * 0.2, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::PDU1_HANDLER, + length * 0.2, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::PDU2_HANDLER, + length * 0.2, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::ACU_HANDLER, + length * 0.2, DeviceHandlerIF::SEND_WRITE); + + thisSequence->addSlot(objects::P60DOCK_HANDLER, + length * 0.4, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::PDU1_HANDLER, + length * 0.4, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::PDU2_HANDLER, + length * 0.4, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::ACU_HANDLER, + length * 0.4, DeviceHandlerIF::GET_WRITE); + + thisSequence->addSlot(objects::P60DOCK_HANDLER, + length * 0.6, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::PDU1_HANDLER, + length * 0.6, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::PDU2_HANDLER, + length * 0.6, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::ACU_HANDLER, + length * 0.6, DeviceHandlerIF::SEND_READ); + + thisSequence->addSlot(objects::P60DOCK_HANDLER, + length * 0.8, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::PDU1_HANDLER, + length * 0.8, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::PDU2_HANDLER, + length * 0.8, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::ACU_HANDLER, + length * 0.8, DeviceHandlerIF::GET_READ); + + if (thisSequence->checkSequence() != HasReturnvaluesIF::RETURN_OK) { + sif::error << "Initialization of GomSpace PST failed" << std::endl; + return HasReturnvaluesIF::RETURN_FAILED; + } + return HasReturnvaluesIF::RETURN_OK; +} + +ReturnValue_t pst::pollingSequenceAcsTest(FixedTimeslotTaskIF *thisSequence) { + uint32_t length = thisSequence->getPeriodMs(); + + thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0.2, + DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0.4, + DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0.6, + DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0.8, + DeviceHandlerIF::GET_READ); + + thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.2, + DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.4, + DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.6, + DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.8, + DeviceHandlerIF::GET_READ); + + thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.2, + DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.4, + DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.6, + DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.8, + DeviceHandlerIF::GET_READ); + if (thisSequence->checkSequence() != HasReturnvaluesIF::RETURN_OK) { + sif::error << "Initialization of ACS Board PST failed" << std::endl; + return HasReturnvaluesIF::RETURN_FAILED; + } + return HasReturnvaluesIF::RETURN_OK; +} diff --git a/linux/boardtest/SpiTestClass.cpp b/linux/boardtest/SpiTestClass.cpp index ed0f5a71..898fc748 100644 --- a/linux/boardtest/SpiTestClass.cpp +++ b/linux/boardtest/SpiTestClass.cpp @@ -296,37 +296,37 @@ void SpiTestClass::acsInit() { { GpiodRegular gpio(rpiGpioName, mgm0Lis3ChipSelect, "MGM_0_LIS3", gpio::Direction::OUT, 1); - gpioCookie->addGpio(gpioIds::MGM_0_LIS3_CS, gpio); + gpioCookie->addGpio(gpioIds::MGM_0_LIS3_CS, &gpio); } { GpiodRegular gpio(rpiGpioName, mgm1Rm3100ChipSelect, "MGM_1_RM3100", gpio::Direction::OUT, 1); - gpioCookie->addGpio(gpioIds::MGM_1_RM3100_CS, gpio); + gpioCookie->addGpio(gpioIds::MGM_1_RM3100_CS, &gpio); } { GpiodRegular gpio(rpiGpioName, gyro0AdisChipSelect, "GYRO_0_ADIS", gpio::Direction::OUT, 1); - gpioCookie->addGpio(gpioIds::GYRO_0_ADIS_CS, gpio); + gpioCookie->addGpio(gpioIds::GYRO_0_ADIS_CS, &gpio); } { GpiodRegular gpio(rpiGpioName, gyro1L3gd20ChipSelect, "GYRO_1_L3G", gpio::Direction::OUT, 1); - gpioCookie->addGpio(gpioIds::GYRO_1_L3G_CS, gpio); + gpioCookie->addGpio(gpioIds::GYRO_1_L3G_CS, &gpio); } { GpiodRegular gpio(rpiGpioName, gyro2L3gd20ChipSelect, "GYRO_2_L3G", gpio::Direction::OUT, 1); - gpioCookie->addGpio(gpioIds::GYRO_2_L3G_CS, gpio); + gpioCookie->addGpio(gpioIds::GYRO_2_L3G_CS, &gpio); } { GpiodRegular gpio(rpiGpioName, mgm2Lis3mdlChipSelect, "MGM_2_LIS3", gpio::Direction::OUT, 1); - gpioCookie->addGpio(gpioIds::MGM_2_LIS3_CS, gpio); + gpioCookie->addGpio(gpioIds::MGM_2_LIS3_CS, &gpio); } { GpiodRegular gpio(rpiGpioName, mgm3Rm3100ChipSelect, "MGM_3_RM3100", gpio::Direction::OUT, 1); - gpioCookie->addGpio(gpioIds::MGM_3_RM3100_CS, gpio); + gpioCookie->addGpio(gpioIds::MGM_3_RM3100_CS, &gpio); } if(gpioIF != nullptr) { gpioIF->addGpios(gpioCookie); diff --git a/linux/boardtest/SpiTestClass.h b/linux/boardtest/SpiTestClass.h index b56b59e2..c567bc45 100644 --- a/linux/boardtest/SpiTestClass.h +++ b/linux/boardtest/SpiTestClass.h @@ -47,14 +47,6 @@ private: uint8_t mgm3Rm3100ChipSelect = 27; static constexpr uint8_t STM_READ_MASK = 0b1000'0000; -<<<<<<< HEAD - static constexpr uint8_t STM_AUTO_INCR_MASK = 0b0100'0000; - - void setSpiSpeedAndMode(int spiFd, spi::SpiMode mode, uint32_t speed); - void writeStmRegister(int fd, gpioId_t chipSelect, uint8_t reg, uint8_t value, - bool autoIncrement); - uint8_t readStmRegister(int fd, gpioId_t chipSelect, uint8_t reg, bool autoIncrement); -======= static constexpr uint8_t RM3100_READ_MASK = STM_READ_MASK; static constexpr uint8_t STM_AUTO_INCR_MASK = 0b0100'0000; @@ -75,7 +67,6 @@ private: size_t len); void readMultipleRegisters(int fd, gpioId_t chipSelect, uint8_t reg, uint8_t* reply, size_t len); ->>>>>>> develop }; diff --git a/linux/gpio/LinuxLibgpioIF.cpp b/linux/gpio/LinuxLibgpioIF.cpp index e0f061dc..0711a1a2 100644 --- a/linux/gpio/LinuxLibgpioIF.cpp +++ b/linux/gpio/LinuxLibgpioIF.cpp @@ -88,12 +88,8 @@ ReturnValue_t LinuxLibgpioIF::configureRegularGpio(gpioId_t gpioId, GpiodRegular lineNum = regularGpio->lineNum; lineHandle = gpiod_chip_get_line(chip, lineNum); if (!lineHandle) { -<<<<<<< HEAD sif::error << "LinuxLibgpioIF::configureGpios: Failed to open line for GPIO with id " << gpioId << std::endl; -======= - sif::error << "LinuxLibgpioIF::configureGpios: Failed to open line" << std::endl; ->>>>>>> develop gpiod_chip_close(chip); return RETURN_FAILED; } diff --git a/mission/devices/MGMHandlerLIS3MDL.cpp b/mission/devices/MGMHandlerLIS3MDL.cpp index 52dd3865..17854de7 100644 --- a/mission/devices/MGMHandlerLIS3MDL.cpp +++ b/mission/devices/MGMHandlerLIS3MDL.cpp @@ -1,4 +1,4 @@ -#include +#include #include "MGMHandlerLIS3MDL.h" #include diff --git a/mission/devices/SyrlinksHkHandler.cpp b/mission/devices/SyrlinksHkHandler.cpp index d9b05b18..bab5e551 100644 --- a/mission/devices/SyrlinksHkHandler.cpp +++ b/mission/devices/SyrlinksHkHandler.cpp @@ -1,7 +1,7 @@ #include #include #include -#include +#include #include SyrlinksHkHandler::SyrlinksHkHandler(object_id_t objectId, object_id_t comIF, CookieIF * comCookie) : @@ -364,7 +364,7 @@ ReturnValue_t SyrlinksHkHandler::verifyReply(const uint8_t* packet, uint8_t size } void SyrlinksHkHandler::parseRxStatusRegistersReply(const uint8_t* packet) { - PoolReadHelper readHelper(&rxDataset); + PoolReadGuard readHelper(&rxDataset); uint16_t offset = SYRLINKS::MESSAGE_HEADER_SIZE; rxDataset.rxStatus = convertHexStringToUint8(reinterpret_cast(packet + offset)); offset += 2; @@ -396,7 +396,7 @@ void SyrlinksHkHandler::parseRxStatusRegistersReply(const uint8_t* packet) { } void SyrlinksHkHandler::parseTxStatusReply(const uint8_t* packet) { - PoolReadHelper readHelper(&txDataset); + PoolReadGuard readHelper(&txDataset); uint16_t offset = SYRLINKS::MESSAGE_HEADER_SIZE; txDataset.txStatus = convertHexStringToUint8(reinterpret_cast(packet + offset)); #if OBSW_VERBOSE_LEVEL >= 1 && SYRLINKS_DEBUG == 1 @@ -406,7 +406,7 @@ void SyrlinksHkHandler::parseTxStatusReply(const uint8_t* packet) { } void SyrlinksHkHandler::parseTxWaveformReply(const uint8_t* packet) { - PoolReadHelper readHelper(&txDataset); + PoolReadGuard readHelper(&txDataset); uint16_t offset = SYRLINKS::MESSAGE_HEADER_SIZE; txDataset.txWaveform = convertHexStringToUint8(reinterpret_cast(packet + offset)); #if OBSW_VERBOSE_LEVEL >= 1 && SYRLINKS_DEBUG == 1 @@ -416,7 +416,7 @@ void SyrlinksHkHandler::parseTxWaveformReply(const uint8_t* packet) { } void SyrlinksHkHandler::parseAgcLowByte(const uint8_t* packet) { - PoolReadHelper readHelper(&txDataset); + PoolReadGuard readHelper(&txDataset); uint16_t offset = SYRLINKS::MESSAGE_HEADER_SIZE; txDataset.txAgcValue = agcValueHighByte << 8 | convertHexStringToUint8(reinterpret_cast(packet + offset)); #if OBSW_VERBOSE_LEVEL >= 1 && SYRLINKS_DEBUG == 1 @@ -425,7 +425,7 @@ void SyrlinksHkHandler::parseAgcLowByte(const uint8_t* packet) { } void SyrlinksHkHandler::parseAgcHighByte(const uint8_t* packet) { - PoolReadHelper readHelper(&txDataset); + PoolReadGuard readHelper(&txDataset); uint16_t offset = SYRLINKS::MESSAGE_HEADER_SIZE; agcValueHighByte = convertHexStringToUint8(reinterpret_cast(packet + offset)); } From 8fedd2315fa68fd2d39a33ea937e7e84144eedfb Mon Sep 17 00:00:00 2001 From: "Jakob.Meier" Date: Mon, 22 Mar 2021 13:57:21 +0100 Subject: [PATCH 21/79] minor changes in object factory --- bsp_q7s/ObjectFactory.cpp | 3 +++ fsfw | 2 +- thirdparty/lwgps | 2 +- 3 files changed, 5 insertions(+), 2 deletions(-) diff --git a/bsp_q7s/ObjectFactory.cpp b/bsp_q7s/ObjectFactory.cpp index 143bf6fb..b0cd289f 100644 --- a/bsp_q7s/ObjectFactory.cpp +++ b/bsp_q7s/ObjectFactory.cpp @@ -18,7 +18,10 @@ #include #include #include +#include #include +#include + #include #include diff --git a/fsfw b/fsfw index 91f69aa3..83d0db82 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit 91f69aa34fcdde9d3f6ae1a71e72a084bf3bc49d +Subproject commit 83d0db824289b28dbad81cce0c80276c4fc839c8 diff --git a/thirdparty/lwgps b/thirdparty/lwgps index d276f972..3dbfe390 160000 --- a/thirdparty/lwgps +++ b/thirdparty/lwgps @@ -1 +1 @@ -Subproject commit d276f9722d1311b552e7c99ee5b03a68487a0fc5 +Subproject commit 3dbfe390a6784ebc723d3907062cf883c8cf85cd From 2b10df9e7febf91debe185f4436753d844b94b86 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 23 Mar 2021 13:44:45 +0100 Subject: [PATCH 22/79] updated tmtc submodule --- tmtc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tmtc b/tmtc index 5f1803b6..74c61842 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 5f1803b66393210ded8c5d88fbc28cd8130cef91 +Subproject commit 74c61842c87e6a25751904116fdc82dd61a14333 From d4ac84abba16f3c7a40b34665c21f2ec3f8c9646 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 23 Mar 2021 16:06:23 +0100 Subject: [PATCH 23/79] added fsfw hal --- .gitmodules | 3 +++ fsfw_hal | 1 + 2 files changed, 4 insertions(+) create mode 160000 fsfw_hal diff --git a/.gitmodules b/.gitmodules index 7af82082..4a973500 100644 --- a/.gitmodules +++ b/.gitmodules @@ -13,3 +13,6 @@ [submodule "thirdparty/lwgps"] path = thirdparty/lwgps url = https://github.com/rmspacefish/lwgps.git +[submodule "fsfw_hal"] + path = fsfw_hal + url = https://egit.irs.uni-stuttgart.de/fsfw/fsfw_hal.git diff --git a/fsfw_hal b/fsfw_hal new file mode 160000 index 00000000..45eb9cbe --- /dev/null +++ b/fsfw_hal @@ -0,0 +1 @@ +Subproject commit 45eb9cbe2bc7e7e11aca7a6262098251f358ec8d From 485f61041f862806cd0d3ad2f0686b16e39d70df Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 23 Mar 2021 16:15:31 +0100 Subject: [PATCH 24/79] integrating fsfw_hal --- CMakeLists.txt | 6 ++++++ bsp_rpi/gpio/CMakeLists.txt | 1 - fsfw_hal | 2 +- linux/CMakeLists.txt | 2 +- linux/{ => archive}/gpio/CMakeLists.txt | 0 linux/{ => archive}/gpio/GpioCookie.cpp | 0 linux/{ => archive}/gpio/GpioCookie.h | 0 linux/{ => archive}/gpio/GpioIF.h | 0 linux/{ => archive}/gpio/LinuxLibgpioIF.cpp | 0 linux/{ => archive}/gpio/LinuxLibgpioIF.h | 0 linux/{ => archive}/gpio/gpioDefinitions.h | 0 {bsp_rpi/gpio => misc/archive}/GPIORPi.cpp | 0 {bsp_rpi/gpio => misc/archive}/GPIORPi.h | 0 13 files changed, 8 insertions(+), 3 deletions(-) rename linux/{ => archive}/gpio/CMakeLists.txt (100%) rename linux/{ => archive}/gpio/GpioCookie.cpp (100%) rename linux/{ => archive}/gpio/GpioCookie.h (100%) rename linux/{ => archive}/gpio/GpioIF.h (100%) rename linux/{ => archive}/gpio/LinuxLibgpioIF.cpp (100%) rename linux/{ => archive}/gpio/LinuxLibgpioIF.h (100%) rename linux/{ => archive}/gpio/gpioDefinitions.h (100%) rename {bsp_rpi/gpio => misc/archive}/GPIORPi.cpp (100%) rename {bsp_rpi/gpio => misc/archive}/GPIORPi.h (100%) diff --git a/CMakeLists.txt b/CMakeLists.txt index 53689123..61b99287 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -40,6 +40,7 @@ set(TARGET_NAME ${CMAKE_PROJECT_NAME}) set(LIB_FSFW_NAME fsfw) set(LIB_ETL_NAME etl) set(LIB_CSP_NAME libcsp) +set(LIB_FSFW_HAL_NAME fsfw_hal) set(LIB_LWGPS_NAME lwgps) set(THIRD_PARTY_FOLDER thirdparty) @@ -50,6 +51,7 @@ set(TEST_PATH test/testtasks) set(LINUX_PATH linux) set(COMMON_PATH common) +set(FSFW_HAL_LIB_PATH fsfw_hal) set(CSP_LIB_PATH ${THIRD_PARTY_FOLDER}/libcsp) set(ETL_LIB_PATH ${THIRD_PARTY_FOLDER}/etl) set(LWGPS_LIB_PATH ${THIRD_PARTY_FOLDER}/lwgps) @@ -68,10 +70,12 @@ if(TGT_BSP) set(FSFW_CONFIG_PATH "fsfwconfig") set(ADD_LINUX_FILES TRUE) set(ADD_CSP_LIB TRUE) + set(FSFW_HAL_ADD_LINUX ON) endif() if(${TGT_BSP} MATCHES "arm/raspberrypi") add_definitions(-DRASPBERRY_PI) + set(FSFW_HAL_ADD_RASPBERRY_PI ON) endif() if(${TGT_BSP} MATCHES "arm/q7s") @@ -113,6 +117,7 @@ add_subdirectory(${BSP_PATH}) add_subdirectory(${FSFW_PATH}) add_subdirectory(${MISSION_PATH}) add_subdirectory(${TEST_PATH}) +add_subdirectory(${FSFW_HAL_LIB_PATH}) add_subdirectory(${COMMON_PATH}) ################################################################################ @@ -126,6 +131,7 @@ target_link_libraries(${TARGET_NAME} PRIVATE ${LIB_FSFW_NAME} ${LIB_OS_NAME} ${LIB_LWGPS_NAME} + ${LIB_FSFW_HAL_NAME} ) if(ADD_ETL_LIB) diff --git a/bsp_rpi/gpio/CMakeLists.txt b/bsp_rpi/gpio/CMakeLists.txt index 85bd6aa6..b816684d 100644 --- a/bsp_rpi/gpio/CMakeLists.txt +++ b/bsp_rpi/gpio/CMakeLists.txt @@ -1,5 +1,4 @@ target_sources(${TARGET_NAME} PUBLIC - GPIORPi.cpp ) diff --git a/fsfw_hal b/fsfw_hal index 45eb9cbe..547c788c 160000 --- a/fsfw_hal +++ b/fsfw_hal @@ -1 +1 @@ -Subproject commit 45eb9cbe2bc7e7e11aca7a6262098251f358ec8d +Subproject commit 547c788c818069abb9eaea12a0c997376641f9aa diff --git a/linux/CMakeLists.txt b/linux/CMakeLists.txt index 77bea0ef..13748f41 100644 --- a/linux/CMakeLists.txt +++ b/linux/CMakeLists.txt @@ -1,4 +1,4 @@ -add_subdirectory(gpio) +# add_subdirectory(gpio) add_subdirectory(i2c) add_subdirectory(csp) add_subdirectory(spi) diff --git a/linux/gpio/CMakeLists.txt b/linux/archive/gpio/CMakeLists.txt similarity index 100% rename from linux/gpio/CMakeLists.txt rename to linux/archive/gpio/CMakeLists.txt diff --git a/linux/gpio/GpioCookie.cpp b/linux/archive/gpio/GpioCookie.cpp similarity index 100% rename from linux/gpio/GpioCookie.cpp rename to linux/archive/gpio/GpioCookie.cpp diff --git a/linux/gpio/GpioCookie.h b/linux/archive/gpio/GpioCookie.h similarity index 100% rename from linux/gpio/GpioCookie.h rename to linux/archive/gpio/GpioCookie.h diff --git a/linux/gpio/GpioIF.h b/linux/archive/gpio/GpioIF.h similarity index 100% rename from linux/gpio/GpioIF.h rename to linux/archive/gpio/GpioIF.h diff --git a/linux/gpio/LinuxLibgpioIF.cpp b/linux/archive/gpio/LinuxLibgpioIF.cpp similarity index 100% rename from linux/gpio/LinuxLibgpioIF.cpp rename to linux/archive/gpio/LinuxLibgpioIF.cpp diff --git a/linux/gpio/LinuxLibgpioIF.h b/linux/archive/gpio/LinuxLibgpioIF.h similarity index 100% rename from linux/gpio/LinuxLibgpioIF.h rename to linux/archive/gpio/LinuxLibgpioIF.h diff --git a/linux/gpio/gpioDefinitions.h b/linux/archive/gpio/gpioDefinitions.h similarity index 100% rename from linux/gpio/gpioDefinitions.h rename to linux/archive/gpio/gpioDefinitions.h diff --git a/bsp_rpi/gpio/GPIORPi.cpp b/misc/archive/GPIORPi.cpp similarity index 100% rename from bsp_rpi/gpio/GPIORPi.cpp rename to misc/archive/GPIORPi.cpp diff --git a/bsp_rpi/gpio/GPIORPi.h b/misc/archive/GPIORPi.h similarity index 100% rename from bsp_rpi/gpio/GPIORPi.h rename to misc/archive/GPIORPi.h From 88d0f9fc0eda8437f3d7a5437e59987ccc937a4c Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 23 Mar 2021 16:45:07 +0100 Subject: [PATCH 25/79] using new fsfw_hal now --- bsp_rpi/ObjectFactory.cpp | 9 +- fsfw_hal | 2 +- fsfwconfig/devices/gpioIds.h | 2 +- linux/boardtest/LibgpiodTest.h | 4 +- linux/boardtest/SpiTestClass.cpp | 4 +- linux/boardtest/SpiTestClass.h | 2 +- linux/spi/SpiComIF.h | 2 +- linux/spi/SpiCookie.h | 2 +- misc/eclipse/.cproject | 434 ++++++++++--------------------- 9 files changed, 148 insertions(+), 313 deletions(-) diff --git a/bsp_rpi/ObjectFactory.cpp b/bsp_rpi/ObjectFactory.cpp index 13cadfb3..a5c81961 100644 --- a/bsp_rpi/ObjectFactory.cpp +++ b/bsp_rpi/ObjectFactory.cpp @@ -1,5 +1,5 @@ #include "ObjectFactory.h" -#include +#include #include #include @@ -11,11 +11,10 @@ #include #include -#include -#include #include #include +#include #include #include #include @@ -28,7 +27,9 @@ #include #include #include -#include + +#include +#include void Factory::setStaticFrameworkObjectIds() { diff --git a/fsfw_hal b/fsfw_hal index 547c788c..f094e992 160000 --- a/fsfw_hal +++ b/fsfw_hal @@ -1 +1 @@ -Subproject commit 547c788c818069abb9eaea12a0c997376641f9aa +Subproject commit f094e9921db807344ed5488f662295034eb89731 diff --git a/fsfwconfig/devices/gpioIds.h b/fsfwconfig/devices/gpioIds.h index 8963bd20..10c0a553 100644 --- a/fsfwconfig/devices/gpioIds.h +++ b/fsfwconfig/devices/gpioIds.h @@ -1,7 +1,7 @@ #ifndef FSFWCONFIG_DEVICES_GPIOIDS_H_ #define FSFWCONFIG_DEVICES_GPIOIDS_H_ -#include +#include namespace gpioIds { enum gpioId_t { diff --git a/linux/boardtest/LibgpiodTest.h b/linux/boardtest/LibgpiodTest.h index e9c6c030..a18c618e 100644 --- a/linux/boardtest/LibgpiodTest.h +++ b/linux/boardtest/LibgpiodTest.h @@ -2,8 +2,8 @@ #define TEST_TESTTASKS_LIBGPIODTEST_H_ #include "TestTask.h" -#include -#include +#include +#include #include /** diff --git a/linux/boardtest/SpiTestClass.cpp b/linux/boardtest/SpiTestClass.cpp index 3090c115..374cb644 100644 --- a/linux/boardtest/SpiTestClass.cpp +++ b/linux/boardtest/SpiTestClass.cpp @@ -7,9 +7,9 @@ #include #include -#include -#include #include +#include +#include #include #include diff --git a/linux/boardtest/SpiTestClass.h b/linux/boardtest/SpiTestClass.h index c567bc45..2e3d8b8c 100644 --- a/linux/boardtest/SpiTestClass.h +++ b/linux/boardtest/SpiTestClass.h @@ -1,7 +1,7 @@ #ifndef LINUX_BOARDTEST_SPITESTCLASS_H_ #define LINUX_BOARDTEST_SPITESTCLASS_H_ -#include +#include #include #include diff --git a/linux/spi/SpiComIF.h b/linux/spi/SpiComIF.h index 0e27a595..c5076ba6 100644 --- a/linux/spi/SpiComIF.h +++ b/linux/spi/SpiComIF.h @@ -3,7 +3,7 @@ #include #include -#include +#include #include #include diff --git a/linux/spi/SpiCookie.h b/linux/spi/SpiCookie.h index 59d0e206..aff4d770 100644 --- a/linux/spi/SpiCookie.h +++ b/linux/spi/SpiCookie.h @@ -3,7 +3,7 @@ #include "spiDefinitions.h" #include -#include +#include #include class SpiCookie: public CookieIF { diff --git a/misc/eclipse/.cproject b/misc/eclipse/.cproject index 6caf4a08..e06537d3 100644 --- a/misc/eclipse/.cproject +++ b/misc/eclipse/.cproject @@ -15,11 +15,11 @@ - + - + @@ -70,7 +70,7 @@ - + @@ -219,9 +219,6 @@ - - - @@ -233,7 +230,7 @@ - + - + @@ -370,9 +363,6 @@ - - - @@ -461,7 +451,7 @@ - + - - + + - + @@ -535,277 +521,134 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - + @@ -813,14 +656,11 @@ - + - - - @@ -831,50 +671,44 @@ - + - - - - make - -f Makefile-Hosted -j16 - hardclean - true - true - true - - - - + - + - + - + - + - + - + - + + + + + + + From 3342b280c90cda7af17b44296ae2af54f713f480 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 23 Mar 2021 16:47:35 +0100 Subject: [PATCH 26/79] updated project files again --- misc/eclipse/.cproject | 434 ++++++++++++++++++++++++++++------------- misc/eclipse/.project | 2 +- 2 files changed, 301 insertions(+), 135 deletions(-) diff --git a/misc/eclipse/.cproject b/misc/eclipse/.cproject index e06537d3..6caf4a08 100644 --- a/misc/eclipse/.cproject +++ b/misc/eclipse/.cproject @@ -15,11 +15,11 @@ - + - + @@ -70,7 +70,7 @@ - + @@ -219,6 +219,9 @@ + + + @@ -230,7 +233,7 @@ - + - + @@ -363,6 +370,9 @@ + + + @@ -451,7 +461,7 @@ - - + + - + @@ -521,134 +535,277 @@ - - - - + + + + + + + + + + + + + + + + + + + + + + @@ -656,11 +813,14 @@ - + + + + @@ -671,44 +831,50 @@ + - + + + + make + -f Makefile-Hosted -j16 + hardclean + true + true + true + + + - + - + - + - + - + - + - + - - - - - - - + diff --git a/misc/eclipse/.project b/misc/eclipse/.project index 906c567f..059a5c19 100644 --- a/misc/eclipse/.project +++ b/misc/eclipse/.project @@ -7,7 +7,7 @@ org.eclipse.cdt.managedbuilder.core.genmakebuilder - clean,full,incremental, + full,incremental, From 27617106bbec1b0bc28dbc2bc1c09da451381c8f Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 23 Mar 2021 16:52:19 +0100 Subject: [PATCH 27/79] fixed q7s --- bsp_q7s/ObjectFactory.cpp | 4 ++-- bsp_q7s/devices/HeaterHandler.cpp | 2 +- bsp_q7s/devices/HeaterHandler.h | 2 +- bsp_q7s/devices/SolarArrayDeploymentHandler.cpp | 2 +- bsp_q7s/devices/SolarArrayDeploymentHandler.h | 4 +--- fsfw_hal | 2 +- 6 files changed, 7 insertions(+), 9 deletions(-) diff --git a/bsp_q7s/ObjectFactory.cpp b/bsp_q7s/ObjectFactory.cpp index f81fc173..70e2db20 100644 --- a/bsp_q7s/ObjectFactory.cpp +++ b/bsp_q7s/ObjectFactory.cpp @@ -24,8 +24,8 @@ #include #include #include -#include -#include +#include +#include #include #include diff --git a/bsp_q7s/devices/HeaterHandler.cpp b/bsp_q7s/devices/HeaterHandler.cpp index 9a44c57b..21a4a3f4 100644 --- a/bsp_q7s/devices/HeaterHandler.cpp +++ b/bsp_q7s/devices/HeaterHandler.cpp @@ -2,7 +2,7 @@ #include #include #include -#include +#include HeaterHandler::HeaterHandler(object_id_t setObjectId_, object_id_t gpioDriverId_, CookieIF * gpioCookie_, object_id_t mainLineSwitcherObjectId_, uint8_t mainLineSwitch_) : diff --git a/bsp_q7s/devices/HeaterHandler.h b/bsp_q7s/devices/HeaterHandler.h index 01319ce9..8969ebd9 100644 --- a/bsp_q7s/devices/HeaterHandler.h +++ b/bsp_q7s/devices/HeaterHandler.h @@ -10,7 +10,7 @@ #include #include #include -#include +#include #include /** diff --git a/bsp_q7s/devices/SolarArrayDeploymentHandler.cpp b/bsp_q7s/devices/SolarArrayDeploymentHandler.cpp index d307ef15..25be3927 100644 --- a/bsp_q7s/devices/SolarArrayDeploymentHandler.cpp +++ b/bsp_q7s/devices/SolarArrayDeploymentHandler.cpp @@ -3,7 +3,7 @@ #include #include -#include +#include #include diff --git a/bsp_q7s/devices/SolarArrayDeploymentHandler.h b/bsp_q7s/devices/SolarArrayDeploymentHandler.h index b7e94f23..5e573128 100644 --- a/bsp_q7s/devices/SolarArrayDeploymentHandler.h +++ b/bsp_q7s/devices/SolarArrayDeploymentHandler.h @@ -1,8 +1,6 @@ #ifndef MISSION_DEVICES_SOLARARRAYDEPLOYMENT_H_ #define MISSION_DEVICES_SOLARARRAYDEPLOYMENT_H_ -#include - #include #include #include @@ -11,7 +9,7 @@ #include #include #include - +#include #include /** diff --git a/fsfw_hal b/fsfw_hal index f094e992..20b4b5d5 160000 --- a/fsfw_hal +++ b/fsfw_hal @@ -1 +1 @@ -Subproject commit f094e9921db807344ed5488f662295034eb89731 +Subproject commit 20b4b5d5d3c5f1af807634e75f859ded2dc74012 From 0b4dac0e3d38931c4258cd575dfd951abca699cd Mon Sep 17 00:00:00 2001 From: "Jakob.Meier" Date: Wed, 24 Mar 2021 12:53:25 +0100 Subject: [PATCH 28/79] rtd handler improvements --- bsp_q7s/ObjectFactory.cpp | 75 ++++++++++--------- bsp_q7s/gpio/gpioCallbacks.cpp | 36 ++++----- .../pollingSequenceFactory.cpp | 5 ++ linux/gpio/GpioCookie.cpp | 2 +- linux/gpio/LinuxLibgpioIF.cpp | 4 +- mission/devices/Max31865PT1000Handler.cpp | 2 +- tmtc | 2 +- 7 files changed, 67 insertions(+), 59 deletions(-) diff --git a/bsp_q7s/ObjectFactory.cpp b/bsp_q7s/ObjectFactory.cpp index 054d59c3..848ee016 100644 --- a/bsp_q7s/ObjectFactory.cpp +++ b/bsp_q7s/ObjectFactory.cpp @@ -140,51 +140,51 @@ void ObjectFactory::produce(){ GpioCookie* heaterGpiosCookie = new GpioCookie; #if TE0720 == 0 /* Pin H2-11 on stack connector */ - GpiodRegular gpioConfigHeater0(std::string("gpiochip7"), 16, std::string("Heater0"), gpio::OUT, - 0); - heaterGpiosCookie->addGpio(gpioIds::HEATER_0, &gpioConfigHeater0); + GpiodRegular* gpioConfigHeater0 = new GpiodRegular(std::string("gpiochip7"), 6, + std::string("Heater0"), gpio::OUT, 0); + heaterGpiosCookie->addGpio(gpioIds::HEATER_0, gpioConfigHeater0); /* Pin H2-12 on stack connector */ - GpiodRegular gpioConfigHeater1(std::string("gpiochip7"), 12, - std::string("Heater1"), gpio::OUT, 0); - heaterGpiosCookie->addGpio(gpioIds::HEATER_1, &gpioConfigHeater1); + GpiodRegular* gpioConfigHeater1 = new GpiodRegular(std::string("gpiochip7"), 12, + std::string("Heater1"), gpio::OUT, 0); + heaterGpiosCookie->addGpio(gpioIds::HEATER_1, gpioConfigHeater1); /* Pin H2-13 on stack connector */ - GpiodRegular gpioConfigHeater2(std::string("gpiochip7"), 7, + GpiodRegular* gpioConfigHeater2 = new GpiodRegular(std::string("gpiochip7"), 7, std::string("Heater2"), gpio::OUT, 0); - heaterGpiosCookie->addGpio(gpioIds::HEATER_2, &gpioConfigHeater2); + heaterGpiosCookie->addGpio(gpioIds::HEATER_2, gpioConfigHeater2); - GpiodRegular gpioConfigHeater3(std::string("gpiochip7"), 5, std::string("Heater3"), gpio::OUT, - 0); - heaterGpiosCookie->addGpio(gpioIds::HEATER_3, &gpioConfigHeater3); + GpiodRegular* gpioConfigHeater3 = new GpiodRegular(std::string("gpiochip7"), 5, + std::string("Heater3"), gpio::OUT, 0); + heaterGpiosCookie->addGpio(gpioIds::HEATER_3, gpioConfigHeater3); - GpiodRegular gpioConfigHeater4(std::string("gpiochip7"), 3, std::string("Heater4"), gpio::OUT, - 0); - heaterGpiosCookie->addGpio(gpioIds::HEATER_4, &gpioConfigHeater4); + GpiodRegular* gpioConfigHeater4 = new GpiodRegular(std::string("gpiochip7"), 3, + std::string("Heater4"), gpio::OUT, 0); + heaterGpiosCookie->addGpio(gpioIds::HEATER_4, gpioConfigHeater4); - GpiodRegular gpioConfigHeater5(std::string("gpiochip7"), 0, std::string("Heater5"), gpio::OUT, - 0); - heaterGpiosCookie->addGpio(gpioIds::HEATER_5, &gpioConfigHeater5); + GpiodRegular* gpioConfigHeater5 = new GpiodRegular(std::string("gpiochip7"), 0, + std::string("Heater5"), gpio::OUT, 0); + heaterGpiosCookie->addGpio(gpioIds::HEATER_5, gpioConfigHeater5); - GpiodRegular gpioConfigHeater6(std::string("gpiochip7"), 1, std::string("Heater6"), gpio::OUT, - 0); - heaterGpiosCookie->addGpio(gpioIds::HEATER_6, &gpioConfigHeater6); + GpiodRegular* gpioConfigHeater6 = new GpiodRegular(std::string("gpiochip7"), 1, + std::string("Heater6"), gpio::OUT, 0); + heaterGpiosCookie->addGpio(gpioIds::HEATER_6, gpioConfigHeater6); - GpiodRegular gpioConfigHeater7(std::string("gpiochip7"), 11, std::string("Heater7"), gpio::OUT, - 0); - heaterGpiosCookie->addGpio(gpioIds::HEATER_7, &gpioConfigHeater7); + GpiodRegular* gpioConfigHeater7 = new GpiodRegular(std::string("gpiochip7"), 11, + std::string("Heater7"), gpio::OUT, 0); + heaterGpiosCookie->addGpio(gpioIds::HEATER_7, gpioConfigHeater7); - new HeaterHandler(objects::HEATER_HANDLER, objects::GPIO_IF, heaterGpiosCookie, objects::PCDU_HANDLER, - pcduSwitches::TCS_BOARD_8V_HEATER_IN); + new HeaterHandler(objects::HEATER_HANDLER, objects::GPIO_IF, heaterGpiosCookie, + objects::PCDU_HANDLER, pcduSwitches::TCS_BOARD_8V_HEATER_IN); GpioCookie* solarArrayDeplCookie = new GpioCookie; - GpiodRegular gpioConfigDeplSA0(std::string("gpiochip7"), 4, + GpiodRegular* gpioConfigDeplSA0 = new GpiodRegular(std::string("gpiochip7"), 4, std::string("DeplSA1"), gpio::OUT, 0); - solarArrayDeplCookie->addGpio(gpioIds::DEPLSA1, &gpioConfigDeplSA0); - GpiodRegular gpioConfigDeplSA1(std::string("gpiochip7"), 2, + solarArrayDeplCookie->addGpio(gpioIds::DEPLSA1, gpioConfigDeplSA0); + GpiodRegular* gpioConfigDeplSA1 = new GpiodRegular(std::string("gpiochip7"), 2, std::string("DeplSA2"), gpio::OUT, 0); - solarArrayDeplCookie->addGpio(gpioIds::DEPLSA2, &gpioConfigDeplSA1); + solarArrayDeplCookie->addGpio(gpioIds::DEPLSA2, gpioConfigDeplSA1); //TODO: Find out burn time. For now set to 1000 ms. new SolarArrayDeploymentHandler(objects::SOLAR_ARRAY_DEPL_HANDLER, objects::GPIO_IF, @@ -202,12 +202,14 @@ void ObjectFactory::produce(){ GpioCookie* rtdGpioCookie = new GpioCookie; gpioCallbacks::initTcsBoardDecoder(gpioComIF); - GpioCallback gpioRtdIc3(std::string("Chip select RTD IC3"), gpio::OUT, 1, + GpioCallback* gpioRtdIc3 = new GpioCallback(std::string("Chip select RTD IC3"), gpio::OUT, 1, &gpioCallbacks::tcsBoardDecoderCallback, gpioComIF); - rtdGpioCookie->addGpio(gpioIds::RTD_IC3, &gpioRtdIc3); - GpioCallback gpioRtdIc4(std::string("Chip select RTD IC4"), gpio::OUT, 1, + rtdGpioCookie->addGpio(gpioIds::RTD_IC3, gpioRtdIc3); + GpioCallback* gpioRtdIc4 = new GpioCallback(std::string("Chip select RTD IC4"), gpio::OUT, 1, &gpioCallbacks::tcsBoardDecoderCallback, gpioComIF); - rtdGpioCookie->addGpio(gpioIds::RTD_IC4, &gpioRtdIc4); + rtdGpioCookie->addGpio(gpioIds::RTD_IC4, gpioRtdIc4); + + gpioComIF->addGpios(rtdGpioCookie); SpiCookie* spiRtdIc3 = new SpiCookie(addresses::RTD_IC3, gpioIds::RTD_IC3, std::string("/dev/spidev2.0"), Max31865Definitions::MAX_REPLY_SIZE, @@ -215,9 +217,10 @@ void ObjectFactory::produce(){ SpiCookie* spiRtdIc4 = new SpiCookie(addresses::RTD_IC4, gpioIds::RTD_IC4, std::string("/dev/spidev2.0"), Max31865Definitions::MAX_REPLY_SIZE, spi::SpiModes::MODE_1, 2000000); - new Max31865PT1000Handler(objects::RTD_IC3, objects::SPI_COM_IF, spiRtdIc3, 0); // 0 is switchId - new Max31865PT1000Handler(objects::RTD_IC4, objects::SPI_COM_IF, spiRtdIc4, 0); - + Max31865PT1000Handler* rtdIc3 = new Max31865PT1000Handler(objects::RTD_IC3, objects::SPI_COM_IF, spiRtdIc3, 0); // 0 is switchId + Max31865PT1000Handler* rtdIc4 = new Max31865PT1000Handler(objects::RTD_IC4, objects::SPI_COM_IF, spiRtdIc4, 0); + rtdIc3->setStartUpImmediately(); +// rtdIc4->setStartUpImmediately(); #endif new TmTcUnixUdpBridge(objects::UDP_BRIDGE, diff --git a/bsp_q7s/gpio/gpioCallbacks.cpp b/bsp_q7s/gpio/gpioCallbacks.cpp index 8c0f0662..b85de9ab 100644 --- a/bsp_q7s/gpio/gpioCallbacks.cpp +++ b/bsp_q7s/gpio/gpioCallbacks.cpp @@ -25,24 +25,24 @@ void initTcsBoardDecoder(GpioIF* gpioComIF) { * Initial values of the spi mux gpios can all be set to an arbitrary value expect for spi mux * bit 1. Setting spi mux bit 1 to high will pull all decoder outputs to high voltage level. */ - GpiodRegular spiMuxBit1(std::string("gpiochip7"), 13, std::string("SPI Mux Bit 1"), gpio::OUT, - 1); - spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_1, &spiMuxBit1); - GpiodRegular spiMuxBit2(std::string("gpiochip7"), 14, std::string("SPI Mux Bit 2"), gpio::OUT, - 0); - spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_2, &spiMuxBit2); - GpiodRegular spiMuxBit3(std::string("gpiochip7"), 15, std::string("SPI Mux Bit 3"), gpio::OUT, - 0); - spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_3, &spiMuxBit3); - GpiodRegular spiMuxBit4(std::string("gpiochip7"), 16, std::string("SPI Mux Bit 4"), gpio::OUT, - 0); - spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_4, &spiMuxBit4); - GpiodRegular spiMuxBit5(std::string("gpiochip7"), 17, std::string("SPI Mux Bit 5"), gpio::OUT, - 0); - spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_5, &spiMuxBit5); - GpiodRegular spiMuxBit6(std::string("gpiochip7"), 18, std::string("SPI Mux Bit 6"), gpio::OUT, - 0); - spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_6, &spiMuxBit6); + GpiodRegular* spiMuxBit1 = new GpiodRegular(std::string("gpiochip7"), 13, + std::string("SPI Mux Bit 1"), gpio::OUT, 1); + spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_1, spiMuxBit1); + GpiodRegular* spiMuxBit2 = new GpiodRegular(std::string("gpiochip7"), 14, + std::string("SPI Mux Bit 2"), gpio::OUT, 0); + spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_2, spiMuxBit2); + GpiodRegular* spiMuxBit3 = new GpiodRegular(std::string("gpiochip7"), 15, + std::string("SPI Mux Bit 3"), gpio::OUT, 0); + spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_3, spiMuxBit3); + GpiodRegular* spiMuxBit4 = new GpiodRegular(std::string("gpiochip7"), 16, + std::string("SPI Mux Bit 4"), gpio::OUT, 0); + spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_4, spiMuxBit4); + GpiodRegular* spiMuxBit5 = new GpiodRegular(std::string("gpiochip7"), 17, + std::string("SPI Mux Bit 5"), gpio::OUT, 0); + spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_5, spiMuxBit5); + GpiodRegular* spiMuxBit6 = new GpiodRegular(std::string("gpiochip7"), 18, + std::string("SPI Mux Bit 6"), gpio::OUT, 0); + spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_6, spiMuxBit6); result = gpioComInterface->addGpios(spiMuxGpios); if (result != HasReturnvaluesIF::RETURN_OK) { diff --git a/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp b/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp index 04b1367b..eccb510f 100644 --- a/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp +++ b/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp @@ -19,18 +19,23 @@ ReturnValue_t pst::pollingSequenceInitDefault(FixedTimeslotTaskIF *thisSequence) thisSequence->addSlot(objects::HEATER_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); thisSequence->addSlot(objects::SOLAR_ARRAY_DEPL_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::RTD_IC3, length * 0, DeviceHandlerIF::PERFORM_OPERATION); thisSequence->addSlot(objects::TMP1075_HANDLER_1, length * 0.2, DeviceHandlerIF::SEND_WRITE); thisSequence->addSlot(objects::TMP1075_HANDLER_2, length * 0.2, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::RTD_IC3, length * 0.2, DeviceHandlerIF::SEND_WRITE); thisSequence->addSlot(objects::TMP1075_HANDLER_1, length * 0.4, DeviceHandlerIF::GET_WRITE); thisSequence->addSlot(objects::TMP1075_HANDLER_2, length * 0.4, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::RTD_IC3, length * 0.4, DeviceHandlerIF::GET_WRITE); thisSequence->addSlot(objects::TMP1075_HANDLER_1, length * 0.6, DeviceHandlerIF::SEND_READ); thisSequence->addSlot(objects::TMP1075_HANDLER_2, length * 0.6, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::RTD_IC3, length * 0.6, DeviceHandlerIF::SEND_READ); thisSequence->addSlot(objects::TMP1075_HANDLER_1, length * 0.8, DeviceHandlerIF::GET_READ); thisSequence->addSlot(objects::TMP1075_HANDLER_2, length * 0.8, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::RTD_IC3, length * 0.8, DeviceHandlerIF::GET_READ); if (thisSequence->checkSequence() == HasReturnvaluesIF::RETURN_OK) { return HasReturnvaluesIF::RETURN_OK; diff --git a/linux/gpio/GpioCookie.cpp b/linux/gpio/GpioCookie.cpp index 50b42307..c729502b 100644 --- a/linux/gpio/GpioCookie.cpp +++ b/linux/gpio/GpioCookie.cpp @@ -15,7 +15,7 @@ ReturnValue_t GpioCookie::addGpio(gpioId_t gpioId, GpioBase* gpioConfig){ if (statusPair.second == false) { #if FSFW_VERBOSE_LEVEL >= 1 sif::error << "GpioCookie::addGpio: Failed to add GPIO " << gpioId << - "to GPIO map" << std::endl; + " to GPIO map" << std::endl; #endif return HasReturnvaluesIF::RETURN_FAILED; } diff --git a/linux/gpio/LinuxLibgpioIF.cpp b/linux/gpio/LinuxLibgpioIF.cpp index 0711a1a2..64ee2982 100644 --- a/linux/gpio/LinuxLibgpioIF.cpp +++ b/linux/gpio/LinuxLibgpioIF.cpp @@ -56,11 +56,11 @@ ReturnValue_t LinuxLibgpioIF::configureGpios(GpioMap& mapToAdd) { break; } case(gpio::GpioTypes::CALLBACK): { - auto gpioCallback = dynamic_cast(gpioMapIter->second); + auto gpioCallback = dynamic_cast(gpioConfig.second); if(gpioCallback->callback == nullptr) { return GPIO_INVALID_INSTANCE; } - gpioCallback->callback(gpioMapIter->first, gpio::GpioOperation::WRITE, + gpioCallback->callback(gpioConfig.first, gpio::GpioOperation::WRITE, gpioCallback->initValue, gpioCallback->callbackArgs); } } diff --git a/mission/devices/Max31865PT1000Handler.cpp b/mission/devices/Max31865PT1000Handler.cpp index c6d98c0a..3ef48120 100644 --- a/mission/devices/Max31865PT1000Handler.cpp +++ b/mission/devices/Max31865PT1000Handler.cpp @@ -329,7 +329,7 @@ void Max31865PT1000Handler::debugInterface(uint8_t positionTracker, uint32_t Max31865PT1000Handler::getTransitionDelayMs( Mode_t modeFrom, Mode_t modeTo) { - return 5000; + return 10000; } ReturnValue_t Max31865PT1000Handler::getSwitches( diff --git a/tmtc b/tmtc index 81cd88f5..754edffe 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 81cd88f5211e0d9853ba3d9dd7611a9c2149cd55 +Subproject commit 754edffeae9d884ce1a4d289d9cc9f0cd9192e59 From 9d40ddc3da4821007f52e64c4c9f7a731cb57717 Mon Sep 17 00:00:00 2001 From: Martin Zietz Date: Thu, 25 Mar 2021 13:10:48 +0100 Subject: [PATCH 29/79] added all max handler --- bsp_q7s/ObjectFactory.cpp | 101 +++++++++++++++++- .../pollingSequenceFactory.cpp | 75 +++++++++++++ tmtc | 2 +- 3 files changed, 176 insertions(+), 2 deletions(-) diff --git a/bsp_q7s/ObjectFactory.cpp b/bsp_q7s/ObjectFactory.cpp index 848ee016..137a040a 100644 --- a/bsp_q7s/ObjectFactory.cpp +++ b/bsp_q7s/ObjectFactory.cpp @@ -208,6 +208,48 @@ void ObjectFactory::produce(){ GpioCallback* gpioRtdIc4 = new GpioCallback(std::string("Chip select RTD IC4"), gpio::OUT, 1, &gpioCallbacks::tcsBoardDecoderCallback, gpioComIF); rtdGpioCookie->addGpio(gpioIds::RTD_IC4, gpioRtdIc4); + GpioCallback* gpioRtdIc5 = new GpioCallback(std::string("Chip select RTD IC5"), gpio::OUT, 1, + &gpioCallbacks::tcsBoardDecoderCallback, gpioComIF); + rtdGpioCookie->addGpio(gpioIds::RTD_IC5, gpioRtdIc5); + GpioCallback* gpioRtdIc6 = new GpioCallback(std::string("Chip select RTD IC6"), gpio::OUT, 1, + &gpioCallbacks::tcsBoardDecoderCallback, gpioComIF); + rtdGpioCookie->addGpio(gpioIds::RTD_IC6, gpioRtdIc6); + GpioCallback* gpioRtdIc7 = new GpioCallback(std::string("Chip select RTD IC7"), gpio::OUT, 1, + &gpioCallbacks::tcsBoardDecoderCallback, gpioComIF); + rtdGpioCookie->addGpio(gpioIds::RTD_IC7, gpioRtdIc7); + GpioCallback* gpioRtdIc8 = new GpioCallback(std::string("Chip select RTD IC8"), gpio::OUT, 1, + &gpioCallbacks::tcsBoardDecoderCallback, gpioComIF); + rtdGpioCookie->addGpio(gpioIds::RTD_IC8, gpioRtdIc8); + GpioCallback* gpioRtdIc9 = new GpioCallback(std::string("Chip select RTD IC9"), gpio::OUT, 1, + &gpioCallbacks::tcsBoardDecoderCallback, gpioComIF); + rtdGpioCookie->addGpio(gpioIds::RTD_IC9, gpioRtdIc9); + GpioCallback* gpioRtdIc10 = new GpioCallback(std::string("Chip select RTD IC10"), gpio::OUT, 1, + &gpioCallbacks::tcsBoardDecoderCallback, gpioComIF); + rtdGpioCookie->addGpio(gpioIds::RTD_IC10, gpioRtdIc10); + GpioCallback* gpioRtdIc11 = new GpioCallback(std::string("Chip select RTD IC11"), gpio::OUT, 1, + &gpioCallbacks::tcsBoardDecoderCallback, gpioComIF); + rtdGpioCookie->addGpio(gpioIds::RTD_IC11, gpioRtdIc11); + GpioCallback* gpioRtdIc12 = new GpioCallback(std::string("Chip select RTD IC12"), gpio::OUT, 1, + &gpioCallbacks::tcsBoardDecoderCallback, gpioComIF); + rtdGpioCookie->addGpio(gpioIds::RTD_IC12, gpioRtdIc12); + GpioCallback* gpioRtdIc13 = new GpioCallback(std::string("Chip select RTD IC13"), gpio::OUT, 1, + &gpioCallbacks::tcsBoardDecoderCallback, gpioComIF); + rtdGpioCookie->addGpio(gpioIds::RTD_IC13, gpioRtdIc13); + GpioCallback* gpioRtdIc14 = new GpioCallback(std::string("Chip select RTD IC14"), gpio::OUT, 1, + &gpioCallbacks::tcsBoardDecoderCallback, gpioComIF); + rtdGpioCookie->addGpio(gpioIds::RTD_IC14, gpioRtdIc14); + GpioCallback* gpioRtdIc15 = new GpioCallback(std::string("Chip select RTD IC15"), gpio::OUT, 1, + &gpioCallbacks::tcsBoardDecoderCallback, gpioComIF); + rtdGpioCookie->addGpio(gpioIds::RTD_IC15, gpioRtdIc15); + GpioCallback* gpioRtdIc16 = new GpioCallback(std::string("Chip select RTD IC16"), gpio::OUT, 1, + &gpioCallbacks::tcsBoardDecoderCallback, gpioComIF); + rtdGpioCookie->addGpio(gpioIds::RTD_IC16, gpioRtdIc16); + GpioCallback* gpioRtdIc17 = new GpioCallback(std::string("Chip select RTD IC17"), gpio::OUT, 1, + &gpioCallbacks::tcsBoardDecoderCallback, gpioComIF); + rtdGpioCookie->addGpio(gpioIds::RTD_IC17, gpioRtdIc17); + GpioCallback* gpioRtdIc18 = new GpioCallback(std::string("Chip select RTD IC18"), gpio::OUT, 1, + &gpioCallbacks::tcsBoardDecoderCallback, gpioComIF); + rtdGpioCookie->addGpio(gpioIds::RTD_IC18, gpioRtdIc18); gpioComIF->addGpios(rtdGpioCookie); @@ -217,9 +259,66 @@ void ObjectFactory::produce(){ SpiCookie* spiRtdIc4 = new SpiCookie(addresses::RTD_IC4, gpioIds::RTD_IC4, std::string("/dev/spidev2.0"), Max31865Definitions::MAX_REPLY_SIZE, spi::SpiModes::MODE_1, 2000000); + SpiCookie* spiRtdIc5 = new SpiCookie(addresses::RTD_IC5, gpioIds::RTD_IC5, + std::string("/dev/spidev2.0"), Max31865Definitions::MAX_REPLY_SIZE, + spi::SpiModes::MODE_1, 2000000); + SpiCookie* spiRtdIc6 = new SpiCookie(addresses::RTD_IC6, gpioIds::RTD_IC6, + std::string("/dev/spidev2.0"), Max31865Definitions::MAX_REPLY_SIZE, + spi::SpiModes::MODE_1, 2000000); + SpiCookie* spiRtdIc7 = new SpiCookie(addresses::RTD_IC7, gpioIds::RTD_IC7, + std::string("/dev/spidev2.0"), Max31865Definitions::MAX_REPLY_SIZE, + spi::SpiModes::MODE_1, 2000000); + SpiCookie* spiRtdIc8 = new SpiCookie(addresses::RTD_IC8, gpioIds::RTD_IC8, + std::string("/dev/spidev2.0"), Max31865Definitions::MAX_REPLY_SIZE, + spi::SpiModes::MODE_1, 2000000); + SpiCookie* spiRtdIc9 = new SpiCookie(addresses::RTD_IC9, gpioIds::RTD_IC9, + std::string("/dev/spidev2.0"), Max31865Definitions::MAX_REPLY_SIZE, + spi::SpiModes::MODE_1, 2000000); + SpiCookie* spiRtdIc10 = new SpiCookie(addresses::RTD_IC10, gpioIds::RTD_IC10, + std::string("/dev/spidev2.0"), Max31865Definitions::MAX_REPLY_SIZE, + spi::SpiModes::MODE_1, 2000000); + SpiCookie* spiRtdIc11 = new SpiCookie(addresses::RTD_IC11, gpioIds::RTD_IC11, + std::string("/dev/spidev2.0"), Max31865Definitions::MAX_REPLY_SIZE, + spi::SpiModes::MODE_1, 2000000); + SpiCookie* spiRtdIc12 = new SpiCookie(addresses::RTD_IC12, gpioIds::RTD_IC12, + std::string("/dev/spidev2.0"), Max31865Definitions::MAX_REPLY_SIZE, + spi::SpiModes::MODE_1, 2000000); + SpiCookie* spiRtdIc13 = new SpiCookie(addresses::RTD_IC13, gpioIds::RTD_IC13, + std::string("/dev/spidev2.0"), Max31865Definitions::MAX_REPLY_SIZE, + spi::SpiModes::MODE_1, 2000000); + SpiCookie* spiRtdIc14 = new SpiCookie(addresses::RTD_IC14, gpioIds::RTD_IC14, + std::string("/dev/spidev2.0"), Max31865Definitions::MAX_REPLY_SIZE, + spi::SpiModes::MODE_1, 2000000); + SpiCookie* spiRtdIc15 = new SpiCookie(addresses::RTD_IC15, gpioIds::RTD_IC15, + std::string("/dev/spidev2.0"), Max31865Definitions::MAX_REPLY_SIZE, + spi::SpiModes::MODE_1, 2000000); + SpiCookie* spiRtdIc16 = new SpiCookie(addresses::RTD_IC16, gpioIds::RTD_IC16, + std::string("/dev/spidev2.0"), Max31865Definitions::MAX_REPLY_SIZE, + spi::SpiModes::MODE_1, 2000000); + SpiCookie* spiRtdIc17 = new SpiCookie(addresses::RTD_IC17, gpioIds::RTD_IC17, + std::string("/dev/spidev2.0"), Max31865Definitions::MAX_REPLY_SIZE, + spi::SpiModes::MODE_1, 2000000); + SpiCookie* spiRtdIc18 = new SpiCookie(addresses::RTD_IC18, gpioIds::RTD_IC18, + std::string("/dev/spidev2.0"), Max31865Definitions::MAX_REPLY_SIZE, + spi::SpiModes::MODE_1, 2000000); + Max31865PT1000Handler* rtdIc3 = new Max31865PT1000Handler(objects::RTD_IC3, objects::SPI_COM_IF, spiRtdIc3, 0); // 0 is switchId Max31865PT1000Handler* rtdIc4 = new Max31865PT1000Handler(objects::RTD_IC4, objects::SPI_COM_IF, spiRtdIc4, 0); - rtdIc3->setStartUpImmediately(); + Max31865PT1000Handler* rtdIc5 = new Max31865PT1000Handler(objects::RTD_IC5, objects::SPI_COM_IF, spiRtdIc5, 0); + Max31865PT1000Handler* rtdIc6 = new Max31865PT1000Handler(objects::RTD_IC6, objects::SPI_COM_IF, spiRtdIc6, 0); + Max31865PT1000Handler* rtdIc7 = new Max31865PT1000Handler(objects::RTD_IC7, objects::SPI_COM_IF, spiRtdIc7, 0); + Max31865PT1000Handler* rtdIc8 = new Max31865PT1000Handler(objects::RTD_IC8, objects::SPI_COM_IF, spiRtdIc8, 0); + Max31865PT1000Handler* rtdIc9 = new Max31865PT1000Handler(objects::RTD_IC9, objects::SPI_COM_IF, spiRtdIc9, 0); + Max31865PT1000Handler* rtdIc10 = new Max31865PT1000Handler(objects::RTD_IC10, objects::SPI_COM_IF, spiRtdIc10, 0); + Max31865PT1000Handler* rtdIc11 = new Max31865PT1000Handler(objects::RTD_IC11, objects::SPI_COM_IF, spiRtdIc11, 0); + Max31865PT1000Handler* rtdIc12 = new Max31865PT1000Handler(objects::RTD_IC12, objects::SPI_COM_IF, spiRtdIc12, 0); + Max31865PT1000Handler* rtdIc13 = new Max31865PT1000Handler(objects::RTD_IC13, objects::SPI_COM_IF, spiRtdIc13, 0); + Max31865PT1000Handler* rtdIc14 = new Max31865PT1000Handler(objects::RTD_IC14, objects::SPI_COM_IF, spiRtdIc14, 0); + Max31865PT1000Handler* rtdIc15 = new Max31865PT1000Handler(objects::RTD_IC15, objects::SPI_COM_IF, spiRtdIc15, 0); + Max31865PT1000Handler* rtdIc16 = new Max31865PT1000Handler(objects::RTD_IC16, objects::SPI_COM_IF, spiRtdIc16, 0); + Max31865PT1000Handler* rtdIc17 = new Max31865PT1000Handler(objects::RTD_IC17, objects::SPI_COM_IF, spiRtdIc17, 0); + Max31865PT1000Handler* rtdIc18 = new Max31865PT1000Handler(objects::RTD_IC18, objects::SPI_COM_IF, spiRtdIc18, 0); + rtdIc10->setStartUpImmediately(); // rtdIc4->setStartUpImmediately(); #endif diff --git a/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp b/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp index eccb510f..1de8318a 100644 --- a/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp +++ b/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp @@ -20,22 +20,97 @@ ReturnValue_t pst::pollingSequenceInitDefault(FixedTimeslotTaskIF *thisSequence) thisSequence->addSlot(objects::SOLAR_ARRAY_DEPL_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); thisSequence->addSlot(objects::RTD_IC3, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::RTD_IC4, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::RTD_IC5, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::RTD_IC6, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::RTD_IC7, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::RTD_IC8, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::RTD_IC9, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::RTD_IC10, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::RTD_IC11, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::RTD_IC12, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::RTD_IC13, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::RTD_IC14, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::RTD_IC15, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::RTD_IC16, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::RTD_IC17, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::RTD_IC18, length * 0, DeviceHandlerIF::PERFORM_OPERATION); thisSequence->addSlot(objects::TMP1075_HANDLER_1, length * 0.2, DeviceHandlerIF::SEND_WRITE); thisSequence->addSlot(objects::TMP1075_HANDLER_2, length * 0.2, DeviceHandlerIF::SEND_WRITE); thisSequence->addSlot(objects::RTD_IC3, length * 0.2, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::RTD_IC4, length * 0.2, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::RTD_IC5, length * 0.2, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::RTD_IC6, length * 0.2, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::RTD_IC7, length * 0.2, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::RTD_IC8, length * 0.2, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::RTD_IC9, length * 0.2, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::RTD_IC10, length * 0.2, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::RTD_IC11, length * 0.2, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::RTD_IC12, length * 0.2, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::RTD_IC13, length * 0.2, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::RTD_IC14, length * 0.2, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::RTD_IC15, length * 0.2, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::RTD_IC16, length * 0.2, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::RTD_IC17, length * 0.2, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::RTD_IC18, length * 0.2, DeviceHandlerIF::SEND_WRITE); thisSequence->addSlot(objects::TMP1075_HANDLER_1, length * 0.4, DeviceHandlerIF::GET_WRITE); thisSequence->addSlot(objects::TMP1075_HANDLER_2, length * 0.4, DeviceHandlerIF::GET_WRITE); thisSequence->addSlot(objects::RTD_IC3, length * 0.4, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::RTD_IC4, length * 0.4, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::RTD_IC5, length * 0.4, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::RTD_IC6, length * 0.4, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::RTD_IC7, length * 0.4, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::RTD_IC8, length * 0.4, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::RTD_IC9, length * 0.4, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::RTD_IC10, length * 0.4, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::RTD_IC11, length * 0.4, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::RTD_IC12, length * 0.4, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::RTD_IC13, length * 0.4, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::RTD_IC14, length * 0.4, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::RTD_IC15, length * 0.4, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::RTD_IC16, length * 0.4, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::RTD_IC17, length * 0.4, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::RTD_IC18, length * 0.4, DeviceHandlerIF::GET_WRITE); thisSequence->addSlot(objects::TMP1075_HANDLER_1, length * 0.6, DeviceHandlerIF::SEND_READ); thisSequence->addSlot(objects::TMP1075_HANDLER_2, length * 0.6, DeviceHandlerIF::SEND_READ); thisSequence->addSlot(objects::RTD_IC3, length * 0.6, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::RTD_IC4, length * 0.6, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::RTD_IC5, length * 0.6, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::RTD_IC6, length * 0.6, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::RTD_IC7, length * 0.6, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::RTD_IC8, length * 0.6, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::RTD_IC9, length * 0.6, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::RTD_IC10, length * 0.6, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::RTD_IC11, length * 0.6, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::RTD_IC12, length * 0.6, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::RTD_IC13, length * 0.6, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::RTD_IC14, length * 0.6, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::RTD_IC15, length * 0.6, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::RTD_IC16, length * 0.6, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::RTD_IC17, length * 0.6, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::RTD_IC18, length * 0.6, DeviceHandlerIF::SEND_READ); thisSequence->addSlot(objects::TMP1075_HANDLER_1, length * 0.8, DeviceHandlerIF::GET_READ); thisSequence->addSlot(objects::TMP1075_HANDLER_2, length * 0.8, DeviceHandlerIF::GET_READ); thisSequence->addSlot(objects::RTD_IC3, length * 0.8, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::RTD_IC4, length * 0.8, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::RTD_IC5, length * 0.8, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::RTD_IC6, length * 0.8, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::RTD_IC7, length * 0.8, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::RTD_IC8, length * 0.8, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::RTD_IC9, length * 0.8, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::RTD_IC10, length * 0.8, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::RTD_IC11, length * 0.8, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::RTD_IC12, length * 0.8, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::RTD_IC13, length * 0.8, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::RTD_IC14, length * 0.8, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::RTD_IC15, length * 0.8, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::RTD_IC16, length * 0.8, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::RTD_IC17, length * 0.8, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::RTD_IC18, length * 0.8, DeviceHandlerIF::GET_READ); if (thisSequence->checkSequence() == HasReturnvaluesIF::RETURN_OK) { return HasReturnvaluesIF::RETURN_OK; diff --git a/tmtc b/tmtc index 754edffe..5f1803b6 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 754edffeae9d884ce1a4d289d9cc9f0cd9192e59 +Subproject commit 5f1803b66393210ded8c5d88fbc28cd8130cef91 From d764b77a832da4ac5e0ac384f9c7212a42cbab71 Mon Sep 17 00:00:00 2001 From: "Jakob.Meier" Date: Thu, 25 Mar 2021 17:15:54 +0100 Subject: [PATCH 30/79] transition delay set to 5000 again --- mission/devices/Max31865PT1000Handler.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/mission/devices/Max31865PT1000Handler.cpp b/mission/devices/Max31865PT1000Handler.cpp index 3ef48120..c6d98c0a 100644 --- a/mission/devices/Max31865PT1000Handler.cpp +++ b/mission/devices/Max31865PT1000Handler.cpp @@ -329,7 +329,7 @@ void Max31865PT1000Handler::debugInterface(uint8_t positionTracker, uint32_t Max31865PT1000Handler::getTransitionDelayMs( Mode_t modeFrom, Mode_t modeTo) { - return 10000; + return 5000; } ReturnValue_t Max31865PT1000Handler::getSwitches( From 00f09afe41a6dffe05387d26179d2791b32bcc7f Mon Sep 17 00:00:00 2001 From: "Jakob.Meier" Date: Fri, 26 Mar 2021 12:08:37 +0100 Subject: [PATCH 31/79] imtq instantiation --- bsp_q7s/ObjectFactory.cpp | 5 +++++ fsfw | 2 +- fsfwconfig/devices/addresses.h | 1 + fsfwconfig/objects/systemObjectList.h | 2 ++ fsfwconfig/pollingsequence/PollingSequenceFactory.cpp | 5 +++++ thirdparty/lwgps | 2 +- tmtc | 2 +- 7 files changed, 16 insertions(+), 3 deletions(-) diff --git a/bsp_q7s/ObjectFactory.cpp b/bsp_q7s/ObjectFactory.cpp index 143bf6fb..2fd0a95b 100644 --- a/bsp_q7s/ObjectFactory.cpp +++ b/bsp_q7s/ObjectFactory.cpp @@ -18,6 +18,7 @@ #include #include #include +#include #include #include @@ -211,6 +212,10 @@ void ObjectFactory::produce(){ new Max31865PT1000Handler(objects::RTD_IC3, objects::SPI_COM_IF, spiRtdIc3, 0); // 0 is switchId new Max31865PT1000Handler(objects::RTD_IC4, objects::SPI_COM_IF, spiRtdIc4, 0); + I2cCookie* imtqI2cCookie = new I2cCookie(addresses::IMTQ, IMTQ::MAX_REPLY_SIZE, + std::string("/dev/i2c-0")); + new IMTQHandler(objects::IMTQ_HANDLER, objects::I2C_COM_IF, imtqI2cCookie); + #endif new TmTcUnixUdpBridge(objects::UDP_BRIDGE, diff --git a/fsfw b/fsfw index 91f69aa3..32b289cb 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit 91f69aa34fcdde9d3f6ae1a71e72a084bf3bc49d +Subproject commit 32b289cbec97e66707a416f3696c804c05d84fb0 diff --git a/fsfwconfig/devices/addresses.h b/fsfwconfig/devices/addresses.h index 6a13908d..4974834d 100644 --- a/fsfwconfig/devices/addresses.h +++ b/fsfwconfig/devices/addresses.h @@ -26,6 +26,7 @@ namespace addresses { }; enum i2cAddresses: address_t { + IMTQ = 16, TMP1075_TCS_1 = 72, TMP1075_TCS_2 = 73, }; diff --git a/fsfwconfig/objects/systemObjectList.h b/fsfwconfig/objects/systemObjectList.h index 8bbd9c2d..c4941307 100644 --- a/fsfwconfig/objects/systemObjectList.h +++ b/fsfwconfig/objects/systemObjectList.h @@ -52,6 +52,8 @@ namespace objects { GYRO_1_L3G_HANDLER = 0x44000012, GYRO_2_L3G_HANDLER = 0x44000013, + IMTQ_HANDLER = 0x44000014, + /* Custom device handler */ PCDU_HANDLER = 0x44001000, SOLAR_ARRAY_DEPL_HANDLER = 0x44001001, diff --git a/fsfwconfig/pollingsequence/PollingSequenceFactory.cpp b/fsfwconfig/pollingsequence/PollingSequenceFactory.cpp index abc614c0..b2d9ff75 100644 --- a/fsfwconfig/pollingsequence/PollingSequenceFactory.cpp +++ b/fsfwconfig/pollingsequence/PollingSequenceFactory.cpp @@ -19,22 +19,27 @@ ReturnValue_t pst::pollingSequenceInitDefault(FixedTimeslotTaskIF *thisSequence) thisSequence->addSlot(objects::HEATER_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); thisSequence->addSlot(objects::SOLAR_ARRAY_DEPL_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); thisSequence->addSlot(objects::TMP1075_HANDLER_1, length * 0.2, DeviceHandlerIF::SEND_WRITE); thisSequence->addSlot(objects::TMP1075_HANDLER_2, length * 0.2, DeviceHandlerIF::SEND_WRITE); thisSequence->addSlot(objects::SYRLINKS_HK_HANDLER, length * 0.2, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0.2, DeviceHandlerIF::SEND_WRITE); thisSequence->addSlot(objects::TMP1075_HANDLER_1, length * 0.4, DeviceHandlerIF::GET_WRITE); thisSequence->addSlot(objects::TMP1075_HANDLER_2, length * 0.4, DeviceHandlerIF::GET_WRITE); thisSequence->addSlot(objects::SYRLINKS_HK_HANDLER, length * 0.4, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0.4, DeviceHandlerIF::GET_WRITE); thisSequence->addSlot(objects::TMP1075_HANDLER_1, length * 0.6, DeviceHandlerIF::SEND_READ); thisSequence->addSlot(objects::TMP1075_HANDLER_2, length * 0.6, DeviceHandlerIF::SEND_READ); thisSequence->addSlot(objects::SYRLINKS_HK_HANDLER, length * 0.6, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0.6, DeviceHandlerIF::SEND_READ); thisSequence->addSlot(objects::TMP1075_HANDLER_1, length * 0.8, DeviceHandlerIF::GET_READ); thisSequence->addSlot(objects::TMP1075_HANDLER_2, length * 0.8, DeviceHandlerIF::GET_READ); thisSequence->addSlot(objects::SYRLINKS_HK_HANDLER, length * 0.8, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0.8, DeviceHandlerIF::GET_READ); if (thisSequence->checkSequence() == HasReturnvaluesIF::RETURN_OK) { return HasReturnvaluesIF::RETURN_OK; diff --git a/thirdparty/lwgps b/thirdparty/lwgps index d276f972..3dbfe390 160000 --- a/thirdparty/lwgps +++ b/thirdparty/lwgps @@ -1 +1 @@ -Subproject commit d276f9722d1311b552e7c99ee5b03a68487a0fc5 +Subproject commit 3dbfe390a6784ebc723d3907062cf883c8cf85cd diff --git a/tmtc b/tmtc index 81cd88f5..80ee4208 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 81cd88f5211e0d9853ba3d9dd7611a9c2149cd55 +Subproject commit 80ee42089e5baadd60479178417299a8c660c80a From 34ef313ab0983497b89eda0fb8bd27632f7d58b0 Mon Sep 17 00:00:00 2001 From: "Jakob.Meier" Date: Fri, 26 Mar 2021 13:55:32 +0100 Subject: [PATCH 32/79] imqt handler compiled --- mission/devices/CMakeLists.txt | 1 + mission/devices/IMTQHandler.cpp | 2 +- mission/devices/IMTQHandler.h | 4 +--- mission/devices/devicedefinitions/IMTQHandlerDefinitions.h | 2 +- 4 files changed, 4 insertions(+), 5 deletions(-) diff --git a/mission/devices/CMakeLists.txt b/mission/devices/CMakeLists.txt index a1617d07..6e8518b0 100644 --- a/mission/devices/CMakeLists.txt +++ b/mission/devices/CMakeLists.txt @@ -12,6 +12,7 @@ target_sources(${TARGET_NAME} PUBLIC ACUHandler.cpp SyrlinksHkHandler.cpp Max31865PT1000Handler.cpp + IMTQHandler.cpp ) diff --git a/mission/devices/IMTQHandler.cpp b/mission/devices/IMTQHandler.cpp index 8e592cac..cc740409 100644 --- a/mission/devices/IMTQHandler.cpp +++ b/mission/devices/IMTQHandler.cpp @@ -68,7 +68,7 @@ ReturnValue_t IMTQHandler::buildCommandFromCommand( void IMTQHandler::fillCommandAndReplyMap() { this->insertInCommandAndReplyMap(IMTQ::GET_ENG_HK_DATA, 1, &engHkDataset, - IMTQ::SIZE_ENG_HK_COMMAND, false, true, IMTQ::SIZE_ENG_HK_DATA); + IMTQ::SIZE_ENG_HK_DATA_REPLY, false, true, IMTQ::SIZE_ENG_HK_DATA_REPLY); } ReturnValue_t IMTQHandler::scanForReply(const uint8_t *start, diff --git a/mission/devices/IMTQHandler.h b/mission/devices/IMTQHandler.h index 207b7560..2e2a7612 100644 --- a/mission/devices/IMTQHandler.h +++ b/mission/devices/IMTQHandler.h @@ -13,8 +13,7 @@ class IMTQHandler: public DeviceHandlerBase { public: - IMTQHandler(object_id_t objectId, object_id_t comIF, - CookieIF * comCookie); + IMTQHandler(object_id_t objectId, object_id_t comIF, CookieIF * comCookie); virtual ~IMTQHandler(); /** @@ -38,7 +37,6 @@ protected: uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override; ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap, LocalDataPoolManager& poolManager) override; - LocalPoolDataSetBase* getDataSetHandle(sid_t sid) override; private: diff --git a/mission/devices/devicedefinitions/IMTQHandlerDefinitions.h b/mission/devices/devicedefinitions/IMTQHandlerDefinitions.h index 117dc91a..21ad7dec 100644 --- a/mission/devices/devicedefinitions/IMTQHandlerDefinitions.h +++ b/mission/devices/devicedefinitions/IMTQHandlerDefinitions.h @@ -107,7 +107,7 @@ private: * When set to 0, the dipole will be generated until a new dipole actuation * command is sent. */ - CommandDipolePacket(uint16_t xDipole, uint16_t yDipole, uint16_t zDipole) : + CommandDipolePacket(uint16_t xDipole, uint16_t yDipole, uint16_t zDipole, uint16_t duration) : xDipole(xDipole), yDipole(yDipole), zDipole(zDipole), duration(duration) { } void setLinks() { From 5d6bf3d402aa99ef0f6df700dcd70150f73cb31d Mon Sep 17 00:00:00 2001 From: Martin Zietz Date: Fri, 26 Mar 2021 14:05:56 +0100 Subject: [PATCH 33/79] submodules add --- fsfw | 2 +- thirdparty/lwgps | 2 +- tmtc | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/fsfw b/fsfw index 91f69aa3..83d0db82 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit 91f69aa34fcdde9d3f6ae1a71e72a084bf3bc49d +Subproject commit 83d0db824289b28dbad81cce0c80276c4fc839c8 diff --git a/thirdparty/lwgps b/thirdparty/lwgps index d276f972..3dbfe390 160000 --- a/thirdparty/lwgps +++ b/thirdparty/lwgps @@ -1 +1 @@ -Subproject commit d276f9722d1311b552e7c99ee5b03a68487a0fc5 +Subproject commit 3dbfe390a6784ebc723d3907062cf883c8cf85cd diff --git a/tmtc b/tmtc index 81cd88f5..f40b70f6 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 81cd88f5211e0d9853ba3d9dd7611a9c2149cd55 +Subproject commit f40b70f66eba176d3c36533a779e4e0ed13ae701 From 79ef32fa1a8888ec298f8161540f418ec10a54a6 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 29 Mar 2021 14:31:55 +0200 Subject: [PATCH 34/79] added way to supply definesto cmake --- cmake/scripts/cmake_build_config.py | 3 +++ 1 file changed, 3 insertions(+) diff --git a/cmake/scripts/cmake_build_config.py b/cmake/scripts/cmake_build_config.py index 0e4b6f25..32b560f6 100644 --- a/cmake/scripts/cmake_build_config.py +++ b/cmake/scripts/cmake_build_config.py @@ -26,6 +26,9 @@ def main(): "Information)", default="debug") parser.add_argument("-l", "--builddir", type=str, help="Specify build directory.") parser.add_argument("-g", "--generator", type=str, help="CMake Generator") + parser.add_argument("-d", "--defines", + help="Additional custom defines passed to CMake (supply without -D prefix!)", + nargs="*", type=str) parser.add_argument("-t", "--target-bsp", type=str, help="Target BSP, combination of architecture and machine") args = parser.parse_args() From c867fabb6ea7fa18323135d807a4900f84f900f1 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 29 Mar 2021 14:37:08 +0200 Subject: [PATCH 35/79] fsfw updated --- fsfw | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/fsfw b/fsfw index 83d0db82..f2da3123 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit 83d0db824289b28dbad81cce0c80276c4fc839c8 +Subproject commit f2da31239c43422f7254b8f4a26e663cffd8e3f3 From 7066c315f00b6d94e05efc19ec340ed439ea84a3 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 29 Mar 2021 14:42:33 +0200 Subject: [PATCH 36/79] corrections ofr updated common udp code --- bsp_q7s/ObjectFactory.cpp | 10 ++++++---- bsp_rpi/ObjectFactory.cpp | 10 ++++++---- 2 files changed, 12 insertions(+), 8 deletions(-) diff --git a/bsp_q7s/ObjectFactory.cpp b/bsp_q7s/ObjectFactory.cpp index 70e2db20..3e52402a 100644 --- a/bsp_q7s/ObjectFactory.cpp +++ b/bsp_q7s/ObjectFactory.cpp @@ -30,9 +30,11 @@ #include #include #include -#include #include -#include + +/* UDP server includes */ +#include +#include #if TEST_LIBGPIOD == 1 #include @@ -170,10 +172,10 @@ void ObjectFactory::produce(){ gpioIds::DEPLSA1, gpioIds::DEPLSA2, 1000); #endif - new TmTcUnixUdpBridge(objects::UDP_BRIDGE, + new UdpTmTcBridge(objects::UDP_BRIDGE, objects::CCSDS_PACKET_DISTRIBUTOR, objects::TM_STORE, objects::TC_STORE); - new TcUnixUdpPollingTask(objects::UDP_POLLING_TASK, objects::UDP_BRIDGE); + new UdpTcPollingTask(objects::UDP_POLLING_TASK, objects::UDP_BRIDGE); #if TE0720 == 1 && TEST_LIBGPIOD == 1 /* Configure MIO0 as input */ diff --git a/bsp_rpi/ObjectFactory.cpp b/bsp_rpi/ObjectFactory.cpp index a5c81961..0c75cf81 100644 --- a/bsp_rpi/ObjectFactory.cpp +++ b/bsp_rpi/ObjectFactory.cpp @@ -23,11 +23,13 @@ #include #include #include -#include #include -#include #include +/* UDP server includes */ +#include +#include + #include #include @@ -55,10 +57,10 @@ void ObjectFactory::produce(){ Factory::setStaticFrameworkObjectIds(); ObjectFactory::produceGenericObjects(); - new TmTcUnixUdpBridge(objects::UDP_BRIDGE, + new UdpTmTcBridge(objects::UDP_BRIDGE, objects::CCSDS_PACKET_DISTRIBUTOR, objects::TM_STORE, objects::TC_STORE); - new TcUnixUdpPollingTask(objects::UDP_POLLING_TASK, objects::UDP_BRIDGE); + new UdpTcPollingTask(objects::UDP_POLLING_TASK, objects::UDP_BRIDGE); GpioIF* gpioIF = new LinuxLibgpioIF(objects::GPIO_IF); From 9cec3f4b1a9a3af7fbfb8b886b1d02491e263262 Mon Sep 17 00:00:00 2001 From: "Jakob.Meier" Date: Mon, 29 Mar 2021 16:40:14 +0200 Subject: [PATCH 37/79] fixes in imqt --- bsp_q7s/ObjectFactory.cpp | 2 +- mission/devices/IMTQHandler.cpp | 5 ++++- mission/devices/devicedefinitions/IMTQHandlerDefinitions.h | 2 +- tmtc | 2 +- 4 files changed, 7 insertions(+), 4 deletions(-) diff --git a/bsp_q7s/ObjectFactory.cpp b/bsp_q7s/ObjectFactory.cpp index 6cd3ec64..4d063238 100644 --- a/bsp_q7s/ObjectFactory.cpp +++ b/bsp_q7s/ObjectFactory.cpp @@ -319,7 +319,7 @@ void ObjectFactory::produce(){ Max31865PT1000Handler* rtdIc16 = new Max31865PT1000Handler(objects::RTD_IC16, objects::SPI_COM_IF, spiRtdIc16, 0); Max31865PT1000Handler* rtdIc17 = new Max31865PT1000Handler(objects::RTD_IC17, objects::SPI_COM_IF, spiRtdIc17, 0); Max31865PT1000Handler* rtdIc18 = new Max31865PT1000Handler(objects::RTD_IC18, objects::SPI_COM_IF, spiRtdIc18, 0); - rtdIc10->setStartUpImmediately(); +// rtdIc10->setStartUpImmediately(); // rtdIc4->setStartUpImmediately(); I2cCookie* imtqI2cCookie = new I2cCookie(addresses::IMTQ, IMTQ::MAX_REPLY_SIZE, diff --git a/mission/devices/IMTQHandler.cpp b/mission/devices/IMTQHandler.cpp index cc740409..88fd00ba 100644 --- a/mission/devices/IMTQHandler.cpp +++ b/mission/devices/IMTQHandler.cpp @@ -18,7 +18,8 @@ IMTQHandler::~IMTQHandler() { void IMTQHandler::doStartUp(){ if(mode == _MODE_START_UP){ - setMode(MODE_ON); + //TODO: Set to MODE_ON again + setMode(MODE_NORMAL); } } @@ -44,6 +45,7 @@ ReturnValue_t IMTQHandler::buildCommandFromCommand( case(IMTQ::GET_ENG_HK_DATA): { commandBuffer[0] = IMTQ::CC::GET_ENG_HK_DATA; rawPacket = commandBuffer; + rawPacketLen = 1; return RETURN_OK; } case(IMTQ::START_ACTUATION_DIPOLE): { @@ -58,6 +60,7 @@ ReturnValue_t IMTQHandler::buildCommandFromCommand( commandBuffer[7] = *(commandData + 7); commandBuffer[8] = *(commandData + 6); rawPacket = commandBuffer; + rawPacketLen = 9; return RETURN_OK; } default: diff --git a/mission/devices/devicedefinitions/IMTQHandlerDefinitions.h b/mission/devices/devicedefinitions/IMTQHandlerDefinitions.h index 21ad7dec..23ff8b9a 100644 --- a/mission/devices/devicedefinitions/IMTQHandlerDefinitions.h +++ b/mission/devices/devicedefinitions/IMTQHandlerDefinitions.h @@ -18,7 +18,7 @@ namespace IMTQ { static const uint8_t MAX_REPLY_SIZE = SIZE_ENG_HK_DATA_REPLY; static const uint8_t MAX_COMMAND_SIZE = 9; - static const uint8_t POOL_ENTRIES = 8; + static const uint8_t POOL_ENTRIES = 11; /** * Command code definitions. Each command or reply of an IMTQ request will begin with one of diff --git a/tmtc b/tmtc index 80ee4208..f40b70f6 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 80ee42089e5baadd60479178417299a8c660c80a +Subproject commit f40b70f66eba176d3c36533a779e4e0ed13ae701 From f17261db0fff12de727546ab0bda083670dbf2be Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 1 Apr 2021 10:09:37 +0200 Subject: [PATCH 38/79] fsfw update --- fsfw | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/fsfw b/fsfw index 83d0db82..f2da3123 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit 83d0db824289b28dbad81cce0c80276c4fc839c8 +Subproject commit f2da31239c43422f7254b8f4a26e663cffd8e3f3 From a1ed7ffb71c7fbc56fa4e49cb4af8aecb4a585bd Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 1 Apr 2021 10:12:57 +0200 Subject: [PATCH 39/79] updated to new fsfw --- bsp_q7s/ObjectFactory.cpp | 8 ++++---- bsp_rpi/ObjectFactory.cpp | 9 ++++----- 2 files changed, 8 insertions(+), 9 deletions(-) diff --git a/bsp_q7s/ObjectFactory.cpp b/bsp_q7s/ObjectFactory.cpp index 70e2db20..abec2e19 100644 --- a/bsp_q7s/ObjectFactory.cpp +++ b/bsp_q7s/ObjectFactory.cpp @@ -30,9 +30,9 @@ #include #include #include -#include #include -#include +#include +#include #if TEST_LIBGPIOD == 1 #include @@ -170,10 +170,10 @@ void ObjectFactory::produce(){ gpioIds::DEPLSA1, gpioIds::DEPLSA2, 1000); #endif - new TmTcUnixUdpBridge(objects::UDP_BRIDGE, + new UdpTmTcBridge(objects::UDP_BRIDGE, objects::CCSDS_PACKET_DISTRIBUTOR, objects::TM_STORE, objects::TC_STORE); - new TcUnixUdpPollingTask(objects::UDP_POLLING_TASK, objects::UDP_BRIDGE); + new UdpTcPollingTask(objects::UDP_POLLING_TASK, objects::UDP_BRIDGE); #if TE0720 == 1 && TEST_LIBGPIOD == 1 /* Configure MIO0 as input */ diff --git a/bsp_rpi/ObjectFactory.cpp b/bsp_rpi/ObjectFactory.cpp index a5c81961..b2e6f23d 100644 --- a/bsp_rpi/ObjectFactory.cpp +++ b/bsp_rpi/ObjectFactory.cpp @@ -23,9 +23,9 @@ #include #include #include -#include #include -#include +#include +#include #include #include @@ -55,10 +55,9 @@ void ObjectFactory::produce(){ Factory::setStaticFrameworkObjectIds(); ObjectFactory::produceGenericObjects(); - new TmTcUnixUdpBridge(objects::UDP_BRIDGE, - objects::CCSDS_PACKET_DISTRIBUTOR, + new UdpTmTcBridge(objects::UDP_BRIDGE, objects::CCSDS_PACKET_DISTRIBUTOR, objects::TM_STORE, objects::TC_STORE); - new TcUnixUdpPollingTask(objects::UDP_POLLING_TASK, objects::UDP_BRIDGE); + new UdpTcPollingTask(objects::UDP_POLLING_TASK, objects::UDP_BRIDGE); GpioIF* gpioIF = new LinuxLibgpioIF(objects::GPIO_IF); From 4177f54f6860184ccd0f0920ae835f22e5936d4b Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 1 Apr 2021 10:24:21 +0200 Subject: [PATCH 40/79] added unix path helper --- cmake/scripts/Q7S/unix_path_helper.sh | 6 ++++++ 1 file changed, 6 insertions(+) create mode 100644 cmake/scripts/Q7S/unix_path_helper.sh diff --git a/cmake/scripts/Q7S/unix_path_helper.sh b/cmake/scripts/Q7S/unix_path_helper.sh new file mode 100644 index 00000000..296bfdd8 --- /dev/null +++ b/cmake/scripts/Q7S/unix_path_helper.sh @@ -0,0 +1,6 @@ +#!/bin/sh +export PATH=$PATH:"/opt/Xilinx/SDK/2018.2/gnu/aarch32/lin/gcc-arm-linux-gnueabi/bin" +export CROSS_COMPILE="arm-linux-gnueabihf" + +export Q7S_SYSROOT="$HOME/Xilinx/cortexa9hf-neon-xiphos-linux-gnueabi" + From 853a728d4c2702070620839b54bd0520d346ec96 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 1 Apr 2021 10:37:34 +0200 Subject: [PATCH 41/79] updated host osal --- bsp_hosted/ObjectFactory.cpp | 21 ++++----------------- test/testtasks/TestTask.cpp | 20 ++++++++++++++------ 2 files changed, 18 insertions(+), 23 deletions(-) diff --git a/bsp_hosted/ObjectFactory.cpp b/bsp_hosted/ObjectFactory.cpp index 798fa7ec..f3d7591d 100644 --- a/bsp_hosted/ObjectFactory.cpp +++ b/bsp_hosted/ObjectFactory.cpp @@ -11,13 +11,8 @@ #include #include -#ifdef LINUX -#include -#include -#elif WIN32 -#include -#include -#endif +#include +#include #include @@ -45,17 +40,9 @@ void ObjectFactory::produce(){ Factory::setStaticFrameworkObjectIds(); ObjectFactory::produceGenericObjects(); -#ifdef LINUX - new TmTcUnixUdpBridge(objects::UDP_BRIDGE, + new UdpTmTcBridge(objects::UDP_BRIDGE, objects::CCSDS_PACKET_DISTRIBUTOR, objects::TM_STORE, objects::TC_STORE); - new TcUnixUdpPollingTask(objects::UDP_POLLING_TASK, objects::UDP_BRIDGE); -#elif WIN32 - new TmTcWinUdpBridge(objects::UDP_BRIDGE, - objects::CCSDS_PACKET_DISTRIBUTOR, objects::TM_STORE, - objects::TC_STORE); - new TcWinUdpPollingTask(objects::UDP_POLLING_TASK, - objects::UDP_BRIDGE); -#endif + new UdpTcPollingTask(objects::UDP_POLLING_TASK, objects::UDP_BRIDGE); } diff --git a/test/testtasks/TestTask.cpp b/test/testtasks/TestTask.cpp index 86f4af38..88a5d13e 100644 --- a/test/testtasks/TestTask.cpp +++ b/test/testtasks/TestTask.cpp @@ -66,6 +66,14 @@ gps_rx_data[] = "" "$GPRMC,183731,A,3907.482,N,12102.436,W,000.0,360.0,080301,015.5,E*67\r\n" "$GPRMB,A,,,,,,,,,,,,V*71\r\n"; +const char hyperion_gps_data[] = "" + "$GNGGA,173225.998892,4908.5596,N,00906.2765,E,1,05,2.1,215.0,M,48.2,M,,0000*74\r\n" + "$GNGLL,4908.5596,N,00906.2765,E,173225.998892,A,A*7F\r\n" + "$GPGSA,A,3,18,16,26,31,20,,,,,,,,3.2,2.1,2.4*3C\r\n" + "$GNRMC,173225.998892,A,4908.5596,N,00906.2765,E,000.0,040.7,270221,,,A*4F\r\n" + "$GNVTG,040.7,T,,M,000.0,N,000.0,K,A*10\r\n" + "$GNZDA,173225.998892,27,02,2021,00,00*75\r\n"; + ReturnValue_t TestTask::performOneShotAction() { #if OBSW_ADD_TEST_CODE == 1 //performLwgpsTest(); @@ -93,18 +101,18 @@ ReturnValue_t TestTask::performActionB() { void TestTask::performLwgpsTest() { /* Everything here will only be performed once. */ - etl::vector testVec; + sif::info << "Processing sample GPS output.." << std::endl; lwgps_t gpsStruct; sif::info << "Size of GPS struct: " << sizeof(gpsStruct) << std::endl; lwgps_init(&gpsStruct); /* Process all input data */ - lwgps_process(&gpsStruct, gps_rx_data, strlen(gps_rx_data)); + lwgps_process(&gpsStruct, hyperion_gps_data, strlen(hyperion_gps_data)); /* Print messages */ - printf("Valid status: %d\r\n", gpsStruct.is_valid); - printf("Latitude: %f degrees\r\n", gpsStruct.latitude); - printf("Longitude: %f degrees\r\n", gpsStruct.longitude); - printf("Altitude: %f meters\r\n", gpsStruct.altitude); + printf("Valid status: %d\n", gpsStruct.is_valid); + printf("Latitude: %f degrees\n", gpsStruct.latitude); + printf("Longitude: %f degrees\n", gpsStruct.longitude); + printf("Altitude: %f meters\n", gpsStruct.altitude); } From c0bb934ddb179d1c4226827684bd5183a6d4a445 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 1 Apr 2021 10:59:36 +0200 Subject: [PATCH 42/79] moved spi code to fsfw_hal --- bsp_rpi/ObjectFactory.cpp | 7 +- fsfw_hal | 2 +- fsfwconfig/devices/spi.h | 2 +- linux/boardtest/SpiTestClass.cpp | 9 +- linux/boardtest/SpiTestClass.h | 2 +- linux/i2c/I2cComIF.cpp | 9 +- linux/spi/CMakeLists.txt | 8 - linux/spi/SpiComIF.cpp | 321 ------------------------------- linux/spi/SpiComIF.h | 63 ------ linux/spi/SpiCookie.cpp | 107 ----------- linux/spi/SpiCookie.h | 119 ------------ linux/spi/spiDefinitions.h | 17 -- linux/utility/CMakeLists.txt | 1 - linux/utility/Utility.cpp | 52 ----- linux/utility/Utility.h | 36 ---- 15 files changed, 17 insertions(+), 738 deletions(-) delete mode 100644 linux/spi/SpiComIF.cpp delete mode 100644 linux/spi/SpiComIF.h delete mode 100644 linux/spi/SpiCookie.cpp delete mode 100644 linux/spi/SpiCookie.h delete mode 100644 linux/spi/spiDefinitions.h delete mode 100644 linux/utility/Utility.cpp delete mode 100644 linux/utility/Utility.h diff --git a/bsp_rpi/ObjectFactory.cpp b/bsp_rpi/ObjectFactory.cpp index 0c75cf81..960abfe6 100644 --- a/bsp_rpi/ObjectFactory.cpp +++ b/bsp_rpi/ObjectFactory.cpp @@ -1,5 +1,4 @@ #include "ObjectFactory.h" -#include #include #include @@ -11,8 +10,6 @@ #include #include -#include -#include #include #include @@ -31,8 +28,10 @@ #include #include +#include #include - +#include +#include void Factory::setStaticFrameworkObjectIds() { PusServiceBase::packetSource = objects::PUS_PACKET_DISTRIBUTOR; diff --git a/fsfw_hal b/fsfw_hal index 20b4b5d5..8f3b0ecc 160000 --- a/fsfw_hal +++ b/fsfw_hal @@ -1 +1 @@ -Subproject commit 20b4b5d5d3c5f1af807634e75f859ded2dc74012 +Subproject commit 8f3b0eccdb1cf9ac5863d3d6411e6ef6528b8005 diff --git a/fsfwconfig/devices/spi.h b/fsfwconfig/devices/spi.h index 7085aa4d..55271a40 100644 --- a/fsfwconfig/devices/spi.h +++ b/fsfwconfig/devices/spi.h @@ -2,7 +2,7 @@ #define FSFWCONFIG_DEVICES_SPI_H_ #include -#include +#include /** * SPI configuration will be contained here to let the device handlers remain independent diff --git a/linux/boardtest/SpiTestClass.cpp b/linux/boardtest/SpiTestClass.cpp index 374cb644..4f2e0e7e 100644 --- a/linux/boardtest/SpiTestClass.cpp +++ b/linux/boardtest/SpiTestClass.cpp @@ -7,7 +7,8 @@ #include #include -#include +#include +#include #include #include @@ -81,7 +82,7 @@ void SpiTestClass::performRm3100Test(uint8_t mgmId) { int fileDescriptor = 0; - utility::UnixFileHelper fileHelper(deviceName, &fileDescriptor, O_RDWR, + UnixFileGuard fileHelper(deviceName, &fileDescriptor, O_RDWR, "SpiComIF::initializeInterface: "); if(fileHelper.getOpenResult()) { sif::error << "SpiTestClass::performRm3100Test: File descriptor could not be opened!" @@ -179,7 +180,7 @@ void SpiTestClass::performLis3MdlTest(uint8_t lis3Id) { #endif int fileDescriptor = 0; - utility::UnixFileHelper fileHelper(deviceName, &fileDescriptor, O_RDWR, + UnixFileGuard fileHelper(deviceName, &fileDescriptor, O_RDWR, "SpiComIF::initializeInterface: "); if(fileHelper.getOpenResult()) { sif::error << "SpiTestClass::performLis3Mdl3100Test: File descriptor could not be opened!" @@ -225,7 +226,7 @@ void SpiTestClass::performL3gTest(uint8_t l3gId) { #endif int fileDescriptor = 0; - utility::UnixFileHelper fileHelper(deviceName, &fileDescriptor, O_RDWR, + UnixFileGuard fileHelper(deviceName, &fileDescriptor, O_RDWR, "SpiComIF::initializeInterface: "); if(fileHelper.getOpenResult()) { sif::error << "SpiTestClass::performLis3Mdl3100Test: File descriptor could not be opened!" diff --git a/linux/boardtest/SpiTestClass.h b/linux/boardtest/SpiTestClass.h index 2e3d8b8c..f92799b5 100644 --- a/linux/boardtest/SpiTestClass.h +++ b/linux/boardtest/SpiTestClass.h @@ -2,7 +2,7 @@ #define LINUX_BOARDTEST_SPITESTCLASS_H_ #include -#include +#include #include #include diff --git a/linux/i2c/I2cComIF.cpp b/linux/i2c/I2cComIF.cpp index ed50293d..753d33a9 100644 --- a/linux/i2c/I2cComIF.cpp +++ b/linux/i2c/I2cComIF.cpp @@ -1,11 +1,14 @@ #include "I2cComIF.h" #include + +#include +#include + #include #include #include #include #include -#include #include @@ -82,7 +85,7 @@ ReturnValue_t I2cComIF::sendMessage(CookieIF *cookie, } deviceFile = i2cCookie->getDeviceFile(); - utility::UnixFileHelper fileHelper(deviceFile, &fd, O_RDWR, "I2cComIF::sendMessage"); + UnixFileGuard fileHelper(deviceFile, &fd, O_RDWR, "I2cComIF::sendMessage"); if(fileHelper.getOpenResult() != HasReturnvaluesIF::RETURN_OK) { return fileHelper.getOpenResult(); } @@ -131,7 +134,7 @@ ReturnValue_t I2cComIF::requestReceiveMessage(CookieIF *cookie, } deviceFile = i2cCookie->getDeviceFile(); - utility::UnixFileHelper fileHelper(deviceFile, &fd, O_RDWR, "I2cComIF::requestReceiveMessage"); + UnixFileGuard fileHelper(deviceFile, &fd, O_RDWR, "I2cComIF::requestReceiveMessage"); if(fileHelper.getOpenResult() != HasReturnvaluesIF::RETURN_OK) { return fileHelper.getOpenResult(); } diff --git a/linux/spi/CMakeLists.txt b/linux/spi/CMakeLists.txt index cb1c9277..e69de29b 100644 --- a/linux/spi/CMakeLists.txt +++ b/linux/spi/CMakeLists.txt @@ -1,8 +0,0 @@ -target_sources(${TARGET_NAME} PUBLIC - SpiComIF.cpp - SpiCookie.cpp -) - - - - diff --git a/linux/spi/SpiComIF.cpp b/linux/spi/SpiComIF.cpp deleted file mode 100644 index b94e1249..00000000 --- a/linux/spi/SpiComIF.cpp +++ /dev/null @@ -1,321 +0,0 @@ -#include "SpiComIF.h" -#include - -#include -#include - -#include -#include -#include - -#include -#include -#include -#include - -#include -#include - -SpiComIF::SpiComIF(object_id_t objectId, GpioIF* gpioComIF): SystemObject(objectId), - gpioComIF(gpioComIF) { - if(gpioComIF == nullptr) { -#if FSFW_VERBOSE_LEVEL >= 1 -#if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "SpiComIF::SpiComIF: GPIO communication interface invalid!" << std::endl; -#else - sif::printError("SpiComIF::SpiComIF: GPIO communication interface invalid!\n"); -#endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ -#endif /* FSFW_VERBOSE_LEVEL >= 1 */ - } - - spiMutex = MutexFactory::instance()->createMutex(); -} - -ReturnValue_t SpiComIF::initializeInterface(CookieIF *cookie) { - int retval = 0; - SpiCookie* spiCookie = dynamic_cast(cookie); - if(spiCookie == nullptr) { - return NULLPOINTER; - } - - address_t spiAddress = spiCookie->getSpiAddress(); - - auto iter = spiDeviceMap.find(spiAddress); - if(iter == spiDeviceMap.end()) { - size_t bufferSize = spiCookie->getMaxBufferSize(); - SpiInstance spiInstance = {std::vector(bufferSize)}; - auto statusPair = spiDeviceMap.emplace(spiAddress, spiInstance); - if (not statusPair.second) { -#if FSFW_VERBOSE_LEVEL >= 1 -#if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "SpiComIF::initializeInterface: Failed to insert device with address " << - spiAddress << "to SPI device map" << std::endl; -#else - sif::printError("SpiComIF::initializeInterface: Failed to insert device with address " - "%lu to SPI device map\n", static_cast(spiAddress)); -#endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ -#endif /* FSFW_VERBOSE_LEVEL >= 1 */ - return HasReturnvaluesIF::RETURN_FAILED; - } - /* Now we emplaced the read buffer in the map, we still need to assign that location - to the SPI driver transfer struct */ - spiCookie->assignReadBuffer(statusPair.first->second.replyBuffer.data()); - } - else { -#if FSFW_VERBOSE_LEVEL >= 1 -#if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "SpiComIF::initializeInterface: SPI address already exists!" << std::endl; -#else - sif::printError("SpiComIF::initializeInterface: SPI address already exists!\n"); -#endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ -#endif /* FSFW_VERBOSE_LEVEL >= 1 */ - return HasReturnvaluesIF::RETURN_FAILED; - } - - /* Pull CS high in any case to be sure that device is inactive */ - gpioId_t gpioId = spiCookie->getChipSelectPin(); - if(gpioId != gpio::NO_GPIO) { - gpioComIF->pullHigh(gpioId); - } - - size_t spiSpeed = 0; - spi::SpiModes spiMode = spi::SpiModes::MODE_0; - - SpiCookie::UncommonParameters params; - spiCookie->getSpiParameters(spiMode, spiSpeed, ¶ms); - - int fileDescriptor = 0; - utility::UnixFileHelper fileHelper(spiCookie->getSpiDevice(), &fileDescriptor, O_RDWR, - "SpiComIF::initializeInterface: "); - if(fileHelper.getOpenResult() != HasReturnvaluesIF::RETURN_OK) { - return fileHelper.getOpenResult(); - } - - /* These flags are rather uncommon */ - if(params.threeWireSpi or params.noCs or params.csHigh) { - uint32_t currentMode = 0; - retval = ioctl(fileDescriptor, SPI_IOC_RD_MODE32, ¤tMode); - if(retval != 0) { - utility::handleIoctlError("SpiComIF::initialiezInterface: Could not read full mode!"); - } - - if(params.threeWireSpi) { - currentMode |= SPI_3WIRE; - } - if(params.noCs) { - /* Some drivers like the Raspberry Pi ignore this flag in any case */ - currentMode |= SPI_NO_CS; - } - if(params.csHigh) { - currentMode |= SPI_CS_HIGH; - } - /* Write adapted mode */ - retval = ioctl(fileDescriptor, SPI_IOC_WR_MODE32, ¤tMode); - if(retval != 0) { - utility::handleIoctlError("SpiComIF::initialiezInterface: Could not write full mode!"); - } - } - if(params.lsbFirst) { - retval = ioctl(fileDescriptor, SPI_IOC_WR_LSB_FIRST, ¶ms.lsbFirst); - if(retval != 0) { - utility::handleIoctlError("SpiComIF::initializeInterface: Setting LSB first failed"); - } - } - if(params.bitsPerWord != 8) { - retval = ioctl(fileDescriptor, SPI_IOC_WR_BITS_PER_WORD, ¶ms.bitsPerWord); - if(retval != 0) { - utility::handleIoctlError("SpiComIF::initializeInterface: " - "Could not write bits per word!"); - } - } - return HasReturnvaluesIF::RETURN_OK; -} - -ReturnValue_t SpiComIF::sendMessage(CookieIF *cookie, const uint8_t *sendData, size_t sendLen) { - SpiCookie* spiCookie = dynamic_cast(cookie); - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - int retval = 0; - - if(spiCookie == nullptr) { - return NULLPOINTER; - } - - if(sendLen > spiCookie->getMaxBufferSize()) { -#if FSFW_VERBOSE_LEVEL >= 1 -#if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "SpiComIF::sendMessage: Too much data sent, send length" << sendLen << - "larger than maximum buffer length" << spiCookie->getMaxBufferSize() << std::endl; -#else - sif::printWarning("SpiComIF::sendMessage: Too much data sent, send length %lu larger " - "than maximum buffer length %lu!\n", static_cast(sendLen), - static_cast(spiCookie->getMaxBufferSize())); -#endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ -#endif /* FSFW_VERBOSE_LEVEL >= 1 */ - return DeviceCommunicationIF::TOO_MUCH_DATA; - } - - - /* Prepare transfer */ - int fileDescriptor = 0; - std::string device = spiCookie->getSpiDevice(); - utility::UnixFileHelper fileHelper(device, &fileDescriptor, O_RDWR, - "SpiComIF::sendMessage: "); - if(fileHelper.getOpenResult() != HasReturnvaluesIF::RETURN_OK) { - return OPENING_FILE_FAILED; - } - spi::SpiModes spiMode = spi::SpiModes::MODE_0; - uint32_t spiSpeed = 0; - spiCookie->getSpiParameters(spiMode, spiSpeed, nullptr); - setSpiSpeedAndMode(fileDescriptor, spiMode, spiSpeed); - spiCookie->assignWriteBuffer(sendData); - spiCookie->assignTransferSize(sendLen); - - bool fullDuplex = spiCookie->isFullDuplex(); - gpioId_t gpioId = spiCookie->getChipSelectPin(); - - /* GPIO access is mutex protected */ - MutexGuard(spiMutex, timeoutType, timeoutMs); - - /* Pull SPI CS low. For now, no support for active high given */ - if(gpioId != gpio::NO_GPIO) { - gpioComIF->pullLow(gpioId); - } - - /* Execute transfer */ - if(fullDuplex) { - /* Initiate a full duplex SPI transfer. */ - retval = ioctl(fileDescriptor, SPI_IOC_MESSAGE(1), spiCookie->getTransferStructHandle()); - if(retval < 0) { - utility::handleIoctlError("SpiComIF::sendMessage: ioctl error."); - result = FULL_DUPLEX_TRANSFER_FAILED; - } -#if FSFW_LINUX_SPI_WIRETAPPING == 1 -#if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::info << "Sent SPI data: " << std::endl; - size_t dataLen = spiCookie->getTransferStructHandle()->len; - uint8_t* dataPtr = reinterpret_cast(spiCookie->getTransferStructHandle()->tx_buf); - arrayprinter::print(dataPtr, dataLen, OutputType::HEX, false); - sif::info << "Received SPI data: " << std::endl; - dataPtr = reinterpret_cast(spiCookie->getTransferStructHandle()->rx_buf); - arrayprinter::print(dataPtr, dataLen, OutputType::HEX, false); -#else -#endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ -#endif /* FSFW_LINUX_SPI_WIRETAPPING == 1 */ - } - else { - /* We write with a blocking half-duplex transfer here */ - if (write(fileDescriptor, sendData, sendLen) != static_cast(sendLen)) { -#if FSFW_VERBOSE_LEVEL >= 1 -#if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "SpiComIF::sendMessage: Half-Duplex write operation failed!" << - std::endl; -#else - sif::printWarning("SpiComIF::sendMessage: Half-Duplex write operation failed!\n"); -#endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ -#endif /* FSFW_VERBOSE_LEVEL >= 1 */ - result = HALF_DUPLEX_TRANSFER_FAILED; - } - } - - if(gpioId != gpio::NO_GPIO) { - gpioComIF->pullHigh(gpioId); - } - return result; -} - -ReturnValue_t SpiComIF::getSendSuccess(CookieIF *cookie) { - return HasReturnvaluesIF::RETURN_OK; -} - -ReturnValue_t SpiComIF::requestReceiveMessage(CookieIF *cookie, size_t requestLen) { - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - SpiCookie* spiCookie = dynamic_cast(cookie); - if(spiCookie == nullptr) { - return NULLPOINTER; - } - - bool fullDuplex = spiCookie->isFullDuplex(); - if(fullDuplex) { - return HasReturnvaluesIF::RETURN_OK; - } - - std::string device = spiCookie->getSpiDevice(); - int fileDescriptor = 0; - utility::UnixFileHelper fileHelper(device, &fileDescriptor, O_RDWR, - "SpiComIF::requestReceiveMessage: "); - if(fileHelper.getOpenResult() != HasReturnvaluesIF::RETURN_OK) { - return OPENING_FILE_FAILED; - } - - uint8_t* rxBuf = nullptr; - size_t readSize = spiCookie->getCurrentTransferSize(); - result = getReadBuffer(spiCookie->getSpiAddress(), &rxBuf); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - - gpioId_t gpioId = spiCookie->getChipSelectPin(); - MutexGuard(spiMutex, timeoutType, timeoutMs); - if(gpioId != gpio::NO_GPIO) { - gpioComIF->pullLow(gpioId); - } - - if(read(fileDescriptor, rxBuf, readSize) != static_cast(readSize)) { -#if FSFW_VERBOSE_LEVEL >= 1 -#if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "SpiComIF::sendMessage: Half-Duplex read operation failed!" << std::endl; -#else - sif::printWarning("SpiComIF::sendMessage: Half-Duplex read operation failed!\n"); -#endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ -#endif /* FSFW_VERBOSE_LEVEL >= 1 */ - result = HALF_DUPLEX_TRANSFER_FAILED; - } - - if(gpioId != gpio::NO_GPIO) { - gpioComIF->pullHigh(gpioId); - } - - return HasReturnvaluesIF::RETURN_OK; -} - -ReturnValue_t SpiComIF::readReceivedMessage(CookieIF *cookie, uint8_t **buffer, size_t *size) { - SpiCookie* spiCookie = dynamic_cast(cookie); - if(spiCookie == nullptr) { - return HasReturnvaluesIF::RETURN_FAILED; - } - uint8_t* rxBuf = nullptr; - ReturnValue_t result = getReadBuffer(spiCookie->getSpiAddress(), &rxBuf); - if(result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - - *buffer = rxBuf; - *size = spiCookie->getCurrentTransferSize(); - return HasReturnvaluesIF::RETURN_OK; -} - -ReturnValue_t SpiComIF::getReadBuffer(address_t spiAddress, uint8_t** buffer) { - if(buffer == nullptr) { - return HasReturnvaluesIF::RETURN_FAILED; - } - - auto iter = spiDeviceMap.find(spiAddress); - if(iter == spiDeviceMap.end()) { - return HasReturnvaluesIF::RETURN_FAILED; - } - - *buffer = iter->second.replyBuffer.data(); - return HasReturnvaluesIF::RETURN_OK; -} - -void SpiComIF::setSpiSpeedAndMode(int spiFd, spi::SpiModes mode, uint32_t speed) { - int retval = ioctl(spiFd, SPI_IOC_WR_MODE, reinterpret_cast(&mode)); - if(retval != 0) { - utility::handleIoctlError("SpiTestClass::performRm3100Test: Setting SPI mode failed!"); - } - - retval = ioctl(spiFd, SPI_IOC_WR_MAX_SPEED_HZ, &speed); - if(retval != 0) { - utility::handleIoctlError("SpiTestClass::performRm3100Test: Setting SPI speed failed!"); - } -} diff --git a/linux/spi/SpiComIF.h b/linux/spi/SpiComIF.h deleted file mode 100644 index c5076ba6..00000000 --- a/linux/spi/SpiComIF.h +++ /dev/null @@ -1,63 +0,0 @@ -#ifndef LINUX_SPI_SPICOMIF_H_ -#define LINUX_SPI_SPICOMIF_H_ - -#include -#include -#include -#include -#include - -#include -#include - -/** - * @brief Encapsulates access to linux SPI driver for FSFW objects - * @details - * Right now, only full-duplex SPI is supported. - * @author R. Mueller - */ -class SpiComIF: public DeviceCommunicationIF, public SystemObject { -public: - static constexpr uint8_t spiRetvalId = CLASS_ID::LINUX_SPI_COM_IF; - static constexpr ReturnValue_t OPENING_FILE_FAILED = - HasReturnvaluesIF::makeReturnCode(spiRetvalId, 0); - /* Full duplex (ioctl) transfer failure */ - static constexpr ReturnValue_t FULL_DUPLEX_TRANSFER_FAILED = - HasReturnvaluesIF::makeReturnCode(spiRetvalId, 1); - /* Half duplex (read/write) transfer failure */ - static constexpr ReturnValue_t HALF_DUPLEX_TRANSFER_FAILED = - HasReturnvaluesIF::makeReturnCode(spiRetvalId, 2); - - SpiComIF(object_id_t objectId, GpioIF* gpioComIF); - - ReturnValue_t initializeInterface(CookieIF * cookie) override; - ReturnValue_t sendMessage(CookieIF *cookie,const uint8_t *sendData, - size_t sendLen) override; - ReturnValue_t getSendSuccess(CookieIF *cookie) override; - ReturnValue_t requestReceiveMessage(CookieIF *cookie, - size_t requestLen) override; - ReturnValue_t readReceivedMessage(CookieIF *cookie, uint8_t **buffer, - size_t *size) override; -private: - - struct SpiInstance { - std::vector replyBuffer; - }; - - GpioIF* gpioComIF = nullptr; - - MutexIF* spiMutex = nullptr; - MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING; - uint32_t timeoutMs = 20; - - using SpiDeviceMap = std::unordered_map; - using SpiDeviceMapIter = SpiDeviceMap::iterator; - - SpiDeviceMap spiDeviceMap; - - - ReturnValue_t getReadBuffer(address_t spiAddress, uint8_t** buffer); - void setSpiSpeedAndMode(int spiFd, spi::SpiModes mode, uint32_t speed); -}; - -#endif /* LINUX_SPI_SPICOMIF_H_ */ diff --git a/linux/spi/SpiCookie.cpp b/linux/spi/SpiCookie.cpp deleted file mode 100644 index 91117682..00000000 --- a/linux/spi/SpiCookie.cpp +++ /dev/null @@ -1,107 +0,0 @@ -#include "SpiCookie.h" - -SpiCookie::SpiCookie(address_t spiAddress, gpioId_t chipSelect, std::string spiDev, - const size_t maxSize, spi::SpiModes spiMode, uint32_t spiSpeed): spiAddress(spiAddress), - chipSelectPin(chipSelect), spiDevice(spiDev), maxSize(maxSize), spiMode(spiMode), - spiSpeed(spiSpeed) { -} - -SpiCookie::SpiCookie(address_t spiAddress, std::string spiDev, const size_t maxSize, - spi::SpiModes spiMode, uint32_t spiSpeed): - SpiCookie(spiAddress, gpio::NO_GPIO, spiDev, maxSize, spiMode, spiSpeed) { -} - -void SpiCookie::getSpiParameters(spi::SpiModes& spiMode, uint32_t& spiSpeed, - UncommonParameters* parameters) const { - spiMode = this->spiMode; - spiSpeed = this->spiSpeed; - - if(parameters != nullptr) { - parameters->threeWireSpi = uncommonParameters.threeWireSpi; - parameters->lsbFirst = uncommonParameters.lsbFirst; - parameters->noCs = uncommonParameters.noCs; - parameters->bitsPerWord = uncommonParameters.bitsPerWord; - parameters->csHigh = uncommonParameters.csHigh; - } -} - -gpioId_t SpiCookie::getChipSelectPin() const { - return chipSelectPin; -} - -size_t SpiCookie::getMaxBufferSize() const { - return maxSize; -} - -address_t SpiCookie::getSpiAddress() const { - return spiAddress; -} - -std::string SpiCookie::getSpiDevice() const { - return spiDevice; -} - -void SpiCookie::setThreeWireSpi(bool enable) { - uncommonParameters.threeWireSpi = enable; -} - -void SpiCookie::setLsbFirst(bool enable) { - uncommonParameters.lsbFirst = enable; -} - -void SpiCookie::setNoCs(bool enable) { - uncommonParameters.noCs = enable; -} - -void SpiCookie::setBitsPerWord(uint8_t bitsPerWord) { - uncommonParameters.bitsPerWord = bitsPerWord; -} - -void SpiCookie::setCsHigh(bool enable) { - uncommonParameters.csHigh = enable; -} - -void SpiCookie::activateCsDeselect(bool deselectCs, uint16_t delayUsecs) { - spiTransferStruct.cs_change = deselectCs; - spiTransferStruct.delay_usecs = delayUsecs; -} - -void SpiCookie::assignReadBuffer(uint8_t* rx) { - if(rx != nullptr) { - spiTransferStruct.rx_buf = reinterpret_cast<__u64>(rx); - } -} - -void SpiCookie::assignWriteBuffer(const uint8_t* tx) { - if(tx != nullptr) { - spiTransferStruct.tx_buf = reinterpret_cast<__u64>(tx); - } -} - -spi_ioc_transfer* SpiCookie::getTransferStructHandle() { - return &spiTransferStruct; -} - -void SpiCookie::setFullOrHalfDuplex(bool halfDuplex) { - this->halfDuplex = halfDuplex; -} - -bool SpiCookie::isFullDuplex() const { - return not this->halfDuplex; -} - -void SpiCookie::assignTransferSize(size_t transferSize) { - spiTransferStruct.len = transferSize; -} - -size_t SpiCookie::getCurrentTransferSize() const { - return spiTransferStruct.len; -} - -void SpiCookie::setSpiSpeed(uint32_t newSpeed) { - this->spiSpeed = newSpeed; -} - -void SpiCookie::setSpiMode(spi::SpiModes newMode) { - this->spiMode = newMode; -} diff --git a/linux/spi/SpiCookie.h b/linux/spi/SpiCookie.h deleted file mode 100644 index aff4d770..00000000 --- a/linux/spi/SpiCookie.h +++ /dev/null @@ -1,119 +0,0 @@ -#ifndef LINUX_SPI_SPICOOKIE_H_ -#define LINUX_SPI_SPICOOKIE_H_ - -#include "spiDefinitions.h" -#include -#include -#include - -class SpiCookie: public CookieIF { -public: - - /** - * Each SPI device will have a corresponding cookie. The cookie is used by the communication - * interface and contains device specific information like the largest expected size to be - * sent and received and the GPIO pin used to toggle the SPI slave select pin. - * @param spiAddress - * @param chipSelect Chip select. gpio::NO_GPIO can be used for hardware slave selects. - * @param spiDev - * @param maxSize - */ - SpiCookie(address_t spiAddress, gpioId_t chipSelect, std::string spiDev, - const size_t maxReplySize, spi::SpiModes spiMode, uint32_t spiSpeed); - - /** - * Like constructor above, but without a dedicated GPIO CS. Can be used for hardware - * slave select or if CS logic is performed with decoders. - */ - SpiCookie(address_t spiAddress, std::string spiDev, const size_t maxReplySize, - spi::SpiModes spiMode, uint32_t spiSpeed); - - address_t getSpiAddress() const; - std::string getSpiDevice() const; - gpioId_t getChipSelectPin() const; - size_t getMaxBufferSize() const; - - /** Enables changing SPI speed at run-time */ - void setSpiSpeed(uint32_t newSpeed); - /** Enables changing the SPI mode at run-time */ - void setSpiMode(spi::SpiModes newMode); - - /** - * True if SPI transfers should be performed in full duplex mode - * @return - */ - bool isFullDuplex() const; - - /** - * Set transfer type to full duplex or half duplex. Full duplex is the default setting, - * ressembling common SPI hardware implementation with shift registers, where read and writes - * happen simultaneosly. - * @param fullDuplex - */ - void setFullOrHalfDuplex(bool halfDuplex); - - /** - * This needs to be called to specify where the SPI driver writes to or reads from. - * @param readLocation - * @param writeLocation - */ - void assignReadBuffer(uint8_t* rx); - void assignWriteBuffer(const uint8_t* tx); - /** - * Assign size for the next transfer. - * @param transferSize - */ - void assignTransferSize(size_t transferSize); - size_t getCurrentTransferSize() const; - - struct UncommonParameters { - uint8_t bitsPerWord = 8; - bool noCs = false; - bool csHigh = false; - bool threeWireSpi = false; - /* MSB first is more common */ - bool lsbFirst = false; - }; - - /** - * Can be used to explicitely disable hardware chip select. - * Some drivers like the Raspberry Pi Linux driver will not use hardware chip select by default - * (see https://www.raspberrypi.org/documentation/hardware/raspberrypi/spi/README.md) - * @param enable - */ - void setNoCs(bool enable); - void setThreeWireSpi(bool enable); - void setLsbFirst(bool enable); - void setCsHigh(bool enable); - void setBitsPerWord(uint8_t bitsPerWord); - - void getSpiParameters(spi::SpiModes& spiMode, uint32_t& spiSpeed, - UncommonParameters* parameters = nullptr) const; - - /** - * See spidev.h cs_change and delay_usecs - * @param deselectCs - * @param delayUsecs - */ - void activateCsDeselect(bool deselectCs, uint16_t delayUsecs); - - spi_ioc_transfer* getTransferStructHandle(); -private: - size_t currentTransferSize = 0; - - address_t spiAddress; - gpioId_t chipSelectPin; - std::string spiDevice; - - const size_t maxSize; - spi::SpiModes spiMode; - uint32_t spiSpeed; - bool halfDuplex = false; - - struct spi_ioc_transfer spiTransferStruct = {}; - UncommonParameters uncommonParameters; -}; - - - -#endif /* LINUX_SPI_SPICOOKIE_H_ */ diff --git a/linux/spi/spiDefinitions.h b/linux/spi/spiDefinitions.h deleted file mode 100644 index e8c48147..00000000 --- a/linux/spi/spiDefinitions.h +++ /dev/null @@ -1,17 +0,0 @@ -#ifndef LINUX_SPI_SPIDEFINITONS_H_ -#define LINUX_SPI_SPIDEFINITONS_H_ - -#include - -namespace spi { - -enum SpiModes: uint8_t { - MODE_0, - MODE_1, - MODE_2, - MODE_3 -}; - -} - -#endif /* LINUX_SPI_SPIDEFINITONS_H_ */ diff --git a/linux/utility/CMakeLists.txt b/linux/utility/CMakeLists.txt index 71151b6c..45a7edcc 100644 --- a/linux/utility/CMakeLists.txt +++ b/linux/utility/CMakeLists.txt @@ -1,5 +1,4 @@ target_sources(${TARGET_NAME} PUBLIC - Utility.cpp ) diff --git a/linux/utility/Utility.cpp b/linux/utility/Utility.cpp deleted file mode 100644 index 45c347db..00000000 --- a/linux/utility/Utility.cpp +++ /dev/null @@ -1,52 +0,0 @@ -#include "Utility.h" - -void utility::handleIoctlError(const char* const customPrintout) { -#if FSFW_VERBOSE_LEVEL >= 1 -#if FSFW_CPP_OSTREAM_ENABLED == 1 - if(customPrintout != nullptr) { - sif::warning << customPrintout << std::endl; - } - sif::warning << "handleIoctlError: Error code " << errno << ", "<< strerror(errno) << - std::endl; -#else - if(customPrintout != nullptr) { - sif::printWarning("%s\n", customPrintout); - } - sif::printWarning("handleIoctlError: Error code %d, %s\n", errno, strerror(errno)); -#endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ -#endif /* FSFW_VERBOSE_LEVEL >= 1 */ - -} - -utility::UnixFileHelper::UnixFileHelper(std::string device, int* fileDescriptor, int flags, - std::string diagnosticPrefix): - fileDescriptor(fileDescriptor) { - if(fileDescriptor == nullptr) { - return; - } - *fileDescriptor = open(device.c_str(), flags); - if (*fileDescriptor < 0) { -#if FSFW_VERBOSE_LEVEL >= 1 -#if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << diagnosticPrefix <<"Opening device failed with error code " << errno << - "." << std::endl; - sif::warning << "Error description: " << strerror(errno) << std::endl; -#else - sif::printError("%sOpening device failed with error code %d.\n", diagnosticPrefix); - sif::printWarning("Error description: %s\n", strerror(errno)); -#endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ -#endif /* FSFW_VERBOSE_LEVEL >= 1 */ - openStatus = OPEN_FILE_FAILED; - } -} - -utility::UnixFileHelper::~UnixFileHelper() { - if(fileDescriptor != nullptr) { - close(*fileDescriptor); - } -} - -ReturnValue_t utility::UnixFileHelper::getOpenResult() const { - return openStatus; -} - diff --git a/linux/utility/Utility.h b/linux/utility/Utility.h deleted file mode 100644 index a93b4936..00000000 --- a/linux/utility/Utility.h +++ /dev/null @@ -1,36 +0,0 @@ -#ifndef LINUX_UTILITY_UTILITY_H_ -#define LINUX_UTILITY_UTILITY_H_ - -#include -#include -#include - -#include -#include - -namespace utility { - -void handleIoctlError(const char* const customPrintout); - -class UnixFileHelper { -public: - static constexpr int READ_WRITE_FLAG = O_RDWR; - static constexpr int READ_ONLY_FLAG = O_RDONLY; - static constexpr int NON_BLOCKING_IO_FLAG = O_NONBLOCK; - - static constexpr ReturnValue_t OPEN_FILE_FAILED = 1; - - UnixFileHelper(std::string device, int* fileDescriptor, int flags, - std::string diagnosticPrefix = ""); - - virtual~ UnixFileHelper(); - - ReturnValue_t getOpenResult() const; -private: - int* fileDescriptor = nullptr; - ReturnValue_t openStatus = HasReturnvaluesIF::RETURN_OK; -}; - -} - -#endif /* LINUX_UTILITY_UTILITY_H_ */ From ed46e6f1bba18ab8eb7e731bb45cd62209a4f894 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 1 Apr 2021 11:06:26 +0200 Subject: [PATCH 43/79] moved i2c to fsfw_hal as well --- bsp_q7s/ObjectFactory.cpp | 4 +- fsfw_hal | 2 +- linux/i2c/CMakeLists.txt | 2 - linux/i2c/I2cComIF.cpp | 199 -------------------------------------- linux/i2c/I2cComIF.h | 59 ----------- linux/i2c/I2cCookie.cpp | 20 ---- linux/i2c/I2cCookie.h | 37 ------- 7 files changed, 3 insertions(+), 320 deletions(-) delete mode 100644 linux/i2c/I2cComIF.cpp delete mode 100644 linux/i2c/I2cComIF.h delete mode 100644 linux/i2c/I2cCookie.cpp delete mode 100644 linux/i2c/I2cCookie.h diff --git a/bsp_q7s/ObjectFactory.cpp b/bsp_q7s/ObjectFactory.cpp index 3e52402a..6b4e94e1 100644 --- a/bsp_q7s/ObjectFactory.cpp +++ b/bsp_q7s/ObjectFactory.cpp @@ -22,8 +22,8 @@ #include #include -#include -#include +#include +#include #include #include diff --git a/fsfw_hal b/fsfw_hal index 8f3b0ecc..7a3190e5 160000 --- a/fsfw_hal +++ b/fsfw_hal @@ -1 +1 @@ -Subproject commit 8f3b0eccdb1cf9ac5863d3d6411e6ef6528b8005 +Subproject commit 7a3190e5b6980ad2addc5e8a76d21994b542f0e0 diff --git a/linux/i2c/CMakeLists.txt b/linux/i2c/CMakeLists.txt index 179abd06..45a7edcc 100644 --- a/linux/i2c/CMakeLists.txt +++ b/linux/i2c/CMakeLists.txt @@ -1,6 +1,4 @@ target_sources(${TARGET_NAME} PUBLIC - I2cComIF.cpp - I2cCookie.cpp ) diff --git a/linux/i2c/I2cComIF.cpp b/linux/i2c/I2cComIF.cpp deleted file mode 100644 index 753d33a9..00000000 --- a/linux/i2c/I2cComIF.cpp +++ /dev/null @@ -1,199 +0,0 @@ -#include "I2cComIF.h" -#include - -#include -#include - -#include -#include -#include -#include -#include - -#include - - -I2cComIF::I2cComIF(object_id_t objectId): SystemObject(objectId){ -} - -I2cComIF::~I2cComIF() {} - -ReturnValue_t I2cComIF::initializeInterface(CookieIF* cookie) { - - address_t i2cAddress; - std::string deviceFile; - - if(cookie == nullptr) { - sif::error << "I2cComIF::initializeInterface: Invalid cookie!" << std::endl; - return NULLPOINTER; - } - I2cCookie* i2cCookie = dynamic_cast(cookie); - if(i2cCookie == nullptr) { - sif::error << "I2cComIF::initializeInterface: Invalid I2C cookie!" << std::endl; - return NULLPOINTER; - } - - i2cAddress = i2cCookie->getAddress(); - - i2cDeviceMapIter = i2cDeviceMap.find(i2cAddress); - if(i2cDeviceMapIter == i2cDeviceMap.end()) { - size_t maxReplyLen = i2cCookie->getMaxReplyLen(); - I2cInstance_t i2cInstance = {std::vector(maxReplyLen), 0}; - auto statusPair = i2cDeviceMap.emplace(i2cAddress, i2cInstance); - if (not statusPair.second) { - sif::error << "I2cComIF::initializeInterface: Failed to insert device with address " << - i2cAddress << "to I2C device " << "map" << std::endl; - return HasReturnvaluesIF::RETURN_FAILED; - } - return HasReturnvaluesIF::RETURN_OK; - } - - sif::error << "I2cComIF::initializeInterface: Device with address " << i2cAddress << - "already in use" << std::endl; - return HasReturnvaluesIF::RETURN_FAILED; -} - -ReturnValue_t I2cComIF::sendMessage(CookieIF *cookie, - const uint8_t *sendData, size_t sendLen) { - - ReturnValue_t result; - int fd; - std::string deviceFile; - - if(sendData == nullptr) { - sif::error << "I2cComIF::sendMessage: Send Data is nullptr" - << std::endl; - return HasReturnvaluesIF::RETURN_FAILED; - } - - if(sendLen == 0) { - return HasReturnvaluesIF::RETURN_OK; - } - - I2cCookie* i2cCookie = dynamic_cast(cookie); - if(i2cCookie == nullptr) { - sif::error << "I2cComIF::sendMessage: Invalid I2C Cookie!" << std::endl; - return NULLPOINTER; - } - - address_t i2cAddress = i2cCookie->getAddress(); - i2cDeviceMapIter = i2cDeviceMap.find(i2cAddress); - if (i2cDeviceMapIter == i2cDeviceMap.end()) { - sif::error << "I2cComIF::sendMessage: i2cAddress of Cookie not " - << "registered in i2cDeviceMap" << std::endl; - return HasReturnvaluesIF::RETURN_FAILED; - } - - deviceFile = i2cCookie->getDeviceFile(); - UnixFileGuard fileHelper(deviceFile, &fd, O_RDWR, "I2cComIF::sendMessage"); - if(fileHelper.getOpenResult() != HasReturnvaluesIF::RETURN_OK) { - return fileHelper.getOpenResult(); - } - result = openDevice(deviceFile, i2cAddress, &fd); - if (result != HasReturnvaluesIF::RETURN_OK){ - return result; - } - - if (write(fd, sendData, sendLen) != (int)sendLen) { - sif::error << "I2cComIF::sendMessage: Failed to send data to I2C " - "device with error code " << errno << ". Error description: " - << strerror(errno) << std::endl; - return HasReturnvaluesIF::RETURN_FAILED; - } - return HasReturnvaluesIF::RETURN_OK; -} - -ReturnValue_t I2cComIF::getSendSuccess(CookieIF *cookie) { - return HasReturnvaluesIF::RETURN_OK; -} - -ReturnValue_t I2cComIF::requestReceiveMessage(CookieIF *cookie, - size_t requestLen) { - ReturnValue_t result; - int fd; - std::string deviceFile; - - if (requestLen == 0) { - return HasReturnvaluesIF::RETURN_OK; - } - - I2cCookie* i2cCookie = dynamic_cast(cookie); - if(i2cCookie == nullptr) { - sif::error << "I2cComIF::requestReceiveMessage: Invalid I2C Cookie!" << std::endl; - i2cDeviceMapIter->second.replyLen = 0; - return NULLPOINTER; - } - - address_t i2cAddress = i2cCookie->getAddress(); - i2cDeviceMapIter = i2cDeviceMap.find(i2cAddress); - if (i2cDeviceMapIter == i2cDeviceMap.end()) { - sif::error << "I2cComIF::requestReceiveMessage: i2cAddress of Cookie not " - << "registered in i2cDeviceMap" << std::endl; - i2cDeviceMapIter->second.replyLen = 0; - return HasReturnvaluesIF::RETURN_FAILED; - } - - deviceFile = i2cCookie->getDeviceFile(); - UnixFileGuard fileHelper(deviceFile, &fd, O_RDWR, "I2cComIF::requestReceiveMessage"); - if(fileHelper.getOpenResult() != HasReturnvaluesIF::RETURN_OK) { - return fileHelper.getOpenResult(); - } - result = openDevice(deviceFile, i2cAddress, &fd); - if (result != HasReturnvaluesIF::RETURN_OK){ - i2cDeviceMapIter->second.replyLen = 0; - return result; - } - - uint8_t* replyBuffer = i2cDeviceMapIter->second.replyBuffer.data(); - - if (read(fd, replyBuffer, requestLen) != static_cast(requestLen)) { - sif::error << "I2cComIF::requestReceiveMessage: Reading from I2C " - << "device failed with error code " << errno <<". Description" - << " of error: " << strerror(errno) << std::endl; - i2cDeviceMapIter->second.replyLen = 0; - return HasReturnvaluesIF::RETURN_FAILED; - } - - i2cDeviceMapIter->second.replyLen = requestLen; - return HasReturnvaluesIF::RETURN_OK; -} - -ReturnValue_t I2cComIF::readReceivedMessage(CookieIF *cookie, - uint8_t **buffer, size_t* size) { - I2cCookie* i2cCookie = dynamic_cast(cookie); - if(i2cCookie == nullptr) { - sif::error << "I2cComIF::readReceivedMessage: Invalid I2C Cookie!" << std::endl; - return NULLPOINTER; - } - - address_t i2cAddress = i2cCookie->getAddress(); - i2cDeviceMapIter = i2cDeviceMap.find(i2cAddress); - if (i2cDeviceMapIter == i2cDeviceMap.end()) { - sif::error << "I2cComIF::readReceivedMessage: i2cAddress of Cookie not " - << "found in i2cDeviceMap" << std::endl; - return HasReturnvaluesIF::RETURN_FAILED; - } - *buffer = i2cDeviceMapIter->second.replyBuffer.data(); - *size = i2cDeviceMapIter->second.replyLen; - - return HasReturnvaluesIF::RETURN_OK; -} - -ReturnValue_t I2cComIF::openDevice(std::string deviceFile, - address_t i2cAddress, int* fileDescriptor) { - - if (ioctl(*fileDescriptor, I2C_SLAVE, i2cAddress) < 0) { -#if FSFW_VERBOSE_LEVEL >= 1 -#if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "I2cComIF: Specifying target device failed with error code " << errno << "." - << std::endl; - sif::warning << "Error description " << strerror(errno) << std::endl; -#else - sif::printWarning("I2cComIF: Specifying target device failed with error code %d.\n"); - sif::printWarning("Error description: %s\n", strerror(errno)); -#endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ -#endif /* FSFW_VERBOSE_LEVEL >= 1 */ - return HasReturnvaluesIF::RETURN_FAILED; - } - return HasReturnvaluesIF::RETURN_OK; -} diff --git a/linux/i2c/I2cComIF.h b/linux/i2c/I2cComIF.h deleted file mode 100644 index 3529bde7..00000000 --- a/linux/i2c/I2cComIF.h +++ /dev/null @@ -1,59 +0,0 @@ -#ifndef LINUX_I2C_I2COMIF_H_ -#define LINUX_I2C_I2COMIF_H_ - -#include "I2cCookie.h" -#include -#include - -#include -#include - -/** - * @brief This is the communication interface for i2c devices connected - * to a system running a linux OS. - * - * @author J. Meier - */ -class I2cComIF: public DeviceCommunicationIF, public SystemObject { -public: - I2cComIF(object_id_t objectId); - - virtual ~I2cComIF(); - - ReturnValue_t initializeInterface(CookieIF * cookie) override; - ReturnValue_t sendMessage(CookieIF *cookie,const uint8_t *sendData, - size_t sendLen) override; - ReturnValue_t getSendSuccess(CookieIF *cookie) override; - ReturnValue_t requestReceiveMessage(CookieIF *cookie, - size_t requestLen) override; - ReturnValue_t readReceivedMessage(CookieIF *cookie, uint8_t **buffer, - size_t *size) override; - -private: - - typedef struct I2cInstance { - std::vector replyBuffer; - size_t replyLen; - } I2cInstance_t; - - using I2cDeviceMap = std::unordered_map; - using I2cDeviceMapIter = I2cDeviceMap::iterator; - - /* In this map all i2c devices will be registered with their address and - * the appropriate file descriptor will be stored */ - I2cDeviceMap i2cDeviceMap; - I2cDeviceMapIter i2cDeviceMapIter; - - /** - * @brief This function opens an I2C device and binds the opened file - * to a specific I2C address. - * @param deviceFile The name of the device file. E.g. i2c-0 - * @param i2cAddress The address of the i2c slave device. - * @param fileDescriptor Pointer to device descriptor. - * @return RETURN_OK if successful, otherwise RETURN_FAILED. - */ - ReturnValue_t openDevice(std::string deviceFile, - address_t i2cAddress, int* fileDescriptor); -}; - -#endif /* LINUX_I2C_I2COMIF_H_ */ diff --git a/linux/i2c/I2cCookie.cpp b/linux/i2c/I2cCookie.cpp deleted file mode 100644 index fe0f3f92..00000000 --- a/linux/i2c/I2cCookie.cpp +++ /dev/null @@ -1,20 +0,0 @@ -#include "I2cCookie.h" - -I2cCookie::I2cCookie(address_t i2cAddress_, size_t maxReplyLen_, - std::string deviceFile_) : - i2cAddress(i2cAddress_), maxReplyLen(maxReplyLen_), deviceFile(deviceFile_) { -} - -address_t I2cCookie::getAddress() const { - return i2cAddress; -} - -size_t I2cCookie::getMaxReplyLen() const { - return maxReplyLen; -} - -std::string I2cCookie::getDeviceFile() const { - return deviceFile; -} - -I2cCookie::~I2cCookie() {} diff --git a/linux/i2c/I2cCookie.h b/linux/i2c/I2cCookie.h deleted file mode 100644 index c924eb4e..00000000 --- a/linux/i2c/I2cCookie.h +++ /dev/null @@ -1,37 +0,0 @@ -#ifndef LINUX_I2C_I2CCOOKIE_H_ -#define LINUX_I2C_I2CCOOKIE_H_ - -#include -#include - -/** - * @brief Cookie for the i2cDeviceComIF. - * - * @author J. Meier - */ -class I2cCookie: public CookieIF { -public: - - /** - * @brief Constructor for the I2C cookie. - * @param i2cAddress_ The i2c address of the target device. - * @param maxReplyLen The maximum expected length of a reply from the - * target device. - */ - I2cCookie(address_t i2cAddress_, size_t maxReplyLen_, - std::string deviceFile_); - - virtual ~I2cCookie(); - - address_t getAddress() const; - size_t getMaxReplyLen() const; - std::string getDeviceFile() const; - -private: - - address_t i2cAddress = 0; - size_t maxReplyLen = 0; - std::string deviceFile; -}; - -#endif /* LINUX_I2C_I2CCOOKIE_H_ */ From a91c24a3a746c86b0eb4f659ca88c7e13c860a79 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 1 Apr 2021 11:07:56 +0200 Subject: [PATCH 44/79] deleted folder which was moved --- linux/i2c/CMakeLists.txt | 6 ------ linux/spi/CMakeLists.txt | 0 2 files changed, 6 deletions(-) delete mode 100644 linux/i2c/CMakeLists.txt delete mode 100644 linux/spi/CMakeLists.txt diff --git a/linux/i2c/CMakeLists.txt b/linux/i2c/CMakeLists.txt deleted file mode 100644 index 45a7edcc..00000000 --- a/linux/i2c/CMakeLists.txt +++ /dev/null @@ -1,6 +0,0 @@ -target_sources(${TARGET_NAME} PUBLIC -) - - - - diff --git a/linux/spi/CMakeLists.txt b/linux/spi/CMakeLists.txt deleted file mode 100644 index e69de29b..00000000 From 30df0904a09f13826ceabe0a827229d245906db0 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 1 Apr 2021 13:31:10 +0200 Subject: [PATCH 45/79] updated default Q7S sysroot --- cmake/scripts/Q7S/win_path_helper_xilinx_tools.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cmake/scripts/Q7S/win_path_helper_xilinx_tools.sh b/cmake/scripts/Q7S/win_path_helper_xilinx_tools.sh index c9bcc54a..a8352331 100644 --- a/cmake/scripts/Q7S/win_path_helper_xilinx_tools.sh +++ b/cmake/scripts/Q7S/win_path_helper_xilinx_tools.sh @@ -2,4 +2,4 @@ export PATH=$PATH:"/c/Xilinx/SDK/2018.2/gnu/aarch32/nt/gcc-arm-linux-gnueabi/bin" export CROSS_COMPILE="arm-linux-gnueabihf" -export Q7S_SYSROOT="/c/Xilinx/SDK/2018.2/gnu/aarch32/nt/gcc-arm-linux-gnueabi/arm-linux-gnueabihf/libc" +export Q7S_SYSROOT="/c/Users/${USER}/Documents/EIVE/cortexa9hf-neon-xiphos-linux-gnueabi" From 79a66cee6a8062d53402dfd0e3f81582be489201 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 1 Apr 2021 14:06:56 +0200 Subject: [PATCH 46/79] added rpi acs board code to q7s --- bsp_q7s/ObjectFactory.cpp | 40 +++++++++++++++++++++++++++++++++++++++ linux/CMakeLists.txt | 2 -- 2 files changed, 40 insertions(+), 2 deletions(-) diff --git a/bsp_q7s/ObjectFactory.cpp b/bsp_q7s/ObjectFactory.cpp index 6b4e94e1..31ed8058 100644 --- a/bsp_q7s/ObjectFactory.cpp +++ b/bsp_q7s/ObjectFactory.cpp @@ -106,6 +106,46 @@ void ObjectFactory::produce(){ //pdu1handler->setModeNormal(); //pdu2handler->setModeNormal(); //acuhandler->setModeNormal(); + (void) p60dockhandler; + (void) pdu1handler; + (void) pdu2handler; + (void) acuhandler; + + GpioCookie* gpioCookieAcsBoard = new GpioCookie(); + gpio::createRpiGpioConfig(gpioCookieAcsBoard, gpioIds::MGM_0_LIS3_CS, gpio::MGM_0_BCM_PIN, + "MGM_0_LIS3", gpio::Direction::OUT, 1); + gpio::createRpiGpioConfig(gpioCookieAcsBoard, gpioIds::MGM_1_RM3100_CS, gpio::MGM_1_BCM_PIN, + "MGM_1_RM3100", gpio::Direction::OUT, 1); + gpio::createRpiGpioConfig(gpioCookieAcsBoard, gpioIds::MGM_2_LIS3_CS, gpio::MGM_2_BCM_PIN, + "MGM_2_LIS3", gpio::Direction::OUT, 1); + gpio::createRpiGpioConfig(gpioCookieAcsBoard, gpioIds::MGM_3_RM3100_CS, gpio::MGM_3_BCM_PIN, + "MGM_3_RM3100", gpio::Direction::OUT, 1); + gpio::createRpiGpioConfig(gpioCookieAcsBoard, gpioIds::GYRO_0_ADIS_CS, gpio::GYRO_0_BCM_PIN, + "GYRO_0_ADIS", gpio::Direction::OUT, 1); + gpio::createRpiGpioConfig(gpioCookieAcsBoard, gpioIds::GYRO_1_L3G_CS, gpio::GYRO_1_BCM_PIN, + "GYRO_1_L3G", gpio::Direction::OUT, 1); + gpio::createRpiGpioConfig(gpioCookieAcsBoard, gpioIds::GYRO_2_L3G_CS, gpio::GYRO_2_BCM_PIN, + "GYRO_2_L3G", gpio::Direction::OUT, 1); + gpioIF->addGpios(gpioCookieAcsBoard); + + std::string spiDev = "/dev/spidev0.0"; + SpiCookie* spiCookie = new SpiCookie(addresses::MGM_0_LIS3, gpioIds::MGM_0_LIS3_CS, spiDev, + MGMLIS3MDL::MAX_BUFFER_SIZE, spi::DEFAULT_LIS3_MODE, spi::DEFAULT_LIS3_SPEED); + auto mgmLis3Handler = new MGMHandlerLIS3MDL(objects::MGM_0_LIS3_HANDLER, + objects::SPI_COM_IF, spiCookie); + mgmLis3Handler->setStartUpImmediately(); + + spiCookie = new SpiCookie(addresses::MGM_1_RM3100, gpioIds::MGM_1_RM3100_CS, spiDev, + RM3100::MAX_BUFFER_SIZE, spi::DEFAULT_RM3100_MODE, spi::DEFAULT_RM3100_SPEED); + auto mgmRm3100Handler = new MGMHandlerRM3100(objects::MGM_1_RM3100_HANDLER, + objects::SPI_COM_IF, spiCookie); + mgmRm3100Handler->setStartUpImmediately(); + + spiCookie = new SpiCookie(addresses::GYRO_1_L3G, gpioIds::GYRO_1_L3G_CS, spiDev, + L3GD20H::MAX_BUFFER_SIZE, spi::DEFAULT_L3G_MODE, spi::DEFAULT_L3G_SPEED); + auto gyroL3gHandler = new GyroHandlerL3GD20H(objects::GYRO_1_L3G_HANDLER, objects::SPI_COM_IF, + spiCookie); + gyroL3gHandler->setStartUpImmediately(); #endif /* Temperature sensors */ Tmp1075Handler* tmp1075Handler_1 = new Tmp1075Handler( diff --git a/linux/CMakeLists.txt b/linux/CMakeLists.txt index 13748f41..dfc3b086 100644 --- a/linux/CMakeLists.txt +++ b/linux/CMakeLists.txt @@ -1,7 +1,5 @@ # add_subdirectory(gpio) -add_subdirectory(i2c) add_subdirectory(csp) -add_subdirectory(spi) add_subdirectory(utility) add_subdirectory(boardtest) From ff62b75029ed72401345c099f74f2e5742794e2f Mon Sep 17 00:00:00 2001 From: Martin Zietz Date: Thu, 1 Apr 2021 15:32:43 +0200 Subject: [PATCH 47/79] polling sequence table entries for acs devices --- bsp_q7s/ObjectFactory.cpp | 2 +- .../pollingSequenceFactory.cpp | 33 +++++++++++++++++++ 2 files changed, 34 insertions(+), 1 deletion(-) diff --git a/bsp_q7s/ObjectFactory.cpp b/bsp_q7s/ObjectFactory.cpp index 31ed8058..aa376dff 100644 --- a/bsp_q7s/ObjectFactory.cpp +++ b/bsp_q7s/ObjectFactory.cpp @@ -128,7 +128,7 @@ void ObjectFactory::produce(){ "GYRO_2_L3G", gpio::Direction::OUT, 1); gpioIF->addGpios(gpioCookieAcsBoard); - std::string spiDev = "/dev/spidev0.0"; + std::string spiDev = "/dev/spidev2.0"; SpiCookie* spiCookie = new SpiCookie(addresses::MGM_0_LIS3, gpioIds::MGM_0_LIS3_CS, spiDev, MGMLIS3MDL::MAX_BUFFER_SIZE, spi::DEFAULT_LIS3_MODE, spi::DEFAULT_LIS3_SPEED); auto mgmLis3Handler = new MGMHandlerLIS3MDL(objects::MGM_0_LIS3_HANDLER, diff --git a/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp b/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp index 04b1367b..00471f25 100644 --- a/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp +++ b/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp @@ -91,6 +91,39 @@ ReturnValue_t pst::gomspacePstInit(FixedTimeslotTaskIF *thisSequence){ thisSequence->addSlot(objects::ACU_HANDLER, length * 0.8, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0.2, + DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0.4, + DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0.6, + DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0.8, + DeviceHandlerIF::GET_READ); + + thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.2, + DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.4, + DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.6, + DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.8, + DeviceHandlerIF::GET_READ); + + thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.2, + DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.4, + DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.6, + DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.8, + DeviceHandlerIF::GET_READ); + if (thisSequence->checkSequence() != HasReturnvaluesIF::RETURN_OK) { sif::error << "Initialization of GomSpace PST failed" << std::endl; return HasReturnvaluesIF::RETURN_FAILED; From 330aba7ea565fb185fb4d9d2ce65478e6b747fe6 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 1 Apr 2021 15:14:50 +0200 Subject: [PATCH 48/79] compiling --- bsp_q7s/ObjectFactory.cpp | 46 +++++++++++++++++++--------- fsfw_hal | 2 +- linux/archive/gpio/gpioDefinitions.h | 6 ++++ 3 files changed, 38 insertions(+), 16 deletions(-) diff --git a/bsp_q7s/ObjectFactory.cpp b/bsp_q7s/ObjectFactory.cpp index aa376dff..9c61b6ee 100644 --- a/bsp_q7s/ObjectFactory.cpp +++ b/bsp_q7s/ObjectFactory.cpp @@ -5,6 +5,7 @@ #include #include #include +#include #include #include @@ -16,6 +17,10 @@ #include #include #include +#include +#include +#include + #include #include #include @@ -24,6 +29,7 @@ #include #include #include +#include #include #include @@ -78,6 +84,7 @@ void ObjectFactory::produce(){ new CspComIF(objects::CSP_COM_IF); new I2cComIF(objects::I2C_COM_IF); + auto gpioIF = new LinuxLibgpioIF(objects::GPIO_IF); #if TE0720 == 0 CspCookie* p60DockCspCookie = new CspCookie(P60Dock::MAX_REPLY_LENGTH, addresses::P60DOCK); @@ -112,20 +119,29 @@ void ObjectFactory::produce(){ (void) acuhandler; GpioCookie* gpioCookieAcsBoard = new GpioCookie(); - gpio::createRpiGpioConfig(gpioCookieAcsBoard, gpioIds::MGM_0_LIS3_CS, gpio::MGM_0_BCM_PIN, - "MGM_0_LIS3", gpio::Direction::OUT, 1); - gpio::createRpiGpioConfig(gpioCookieAcsBoard, gpioIds::MGM_1_RM3100_CS, gpio::MGM_1_BCM_PIN, - "MGM_1_RM3100", gpio::Direction::OUT, 1); - gpio::createRpiGpioConfig(gpioCookieAcsBoard, gpioIds::MGM_2_LIS3_CS, gpio::MGM_2_BCM_PIN, - "MGM_2_LIS3", gpio::Direction::OUT, 1); - gpio::createRpiGpioConfig(gpioCookieAcsBoard, gpioIds::MGM_3_RM3100_CS, gpio::MGM_3_BCM_PIN, - "MGM_3_RM3100", gpio::Direction::OUT, 1); - gpio::createRpiGpioConfig(gpioCookieAcsBoard, gpioIds::GYRO_0_ADIS_CS, gpio::GYRO_0_BCM_PIN, - "GYRO_0_ADIS", gpio::Direction::OUT, 1); - gpio::createRpiGpioConfig(gpioCookieAcsBoard, gpioIds::GYRO_1_L3G_CS, gpio::GYRO_1_BCM_PIN, - "GYRO_1_L3G", gpio::Direction::OUT, 1); - gpio::createRpiGpioConfig(gpioCookieAcsBoard, gpioIds::GYRO_2_L3G_CS, gpio::GYRO_2_BCM_PIN, - "GYRO_2_L3G", gpio::Direction::OUT, 1); + GpiodRegular gpioGyro1(std::string("gpiochip5"), 21, std::string("CS_GYRO_1_ADIS"), + gpio::OUT, gpio::HIGH); + gpioCookieAcsBoard->addGpio(gpioIds::GYRO_0_ADIS_CS, gpioGyro1); + GpiodRegular gpioGyro2(std::string("gpiochip5"), 7, std::string("CS_GYRO_2_L3G"), + gpio::OUT, gpio::HIGH); + gpioCookieAcsBoard->addGpio(gpioIds::GYRO_1_L3G_CS, gpioGyro2); + GpiodRegular gpioGyro3(std::string("gpiochip5"), 3, std::string("CS_GYRO_3_L3G"), + gpio::OUT, gpio::HIGH); + gpioCookieAcsBoard->addGpio(gpioIds::GYRO_2_L3G_CS, gpioGyro3); + + GpiodRegular gpioMgm0(std::string("gpiochip5"), 5, std::string("CS_MGM_0_LIS3_A"), + gpio::OUT, gpio::HIGH); + gpioCookieAcsBoard->addGpio(gpioIds::MGM_0_LIS3_CS, gpioMgm0); + GpiodRegular gpioMgm1(std::string("gpiochip5"), 17, std::string("CS_MGM_1_RM3100_A"), + gpio::OUT, gpio::HIGH); + gpioCookieAcsBoard->addGpio(gpioIds::MGM_1_RM3100_CS, gpioMgm1); + GpiodRegular gpioMgm2(std::string("gpiochip6"), 0, std::string("CS_MGM_2_LIS3_B"), + gpio::OUT, gpio::HIGH); + gpioCookieAcsBoard->addGpio(gpioIds::MGM_2_LIS3_CS, gpioMgm2); + GpiodRegular gpioMgm3(std::string("gpiochip5"), 23, std::string("CS_MGM_3_RM3100_B"), + gpio::OUT, gpio::HIGH); + gpioCookieAcsBoard->addGpio(gpioIds::MGM_3_RM3100_CS, gpioMgm3); + gpioIF->addGpios(gpioCookieAcsBoard); std::string spiDev = "/dev/spidev2.0"; @@ -158,7 +174,7 @@ void ObjectFactory::produce(){ tmp1075Handler_2->setStartUpImmediately(); GpioCookie* heaterGpiosCookie = new GpioCookie; - new LinuxLibgpioIF(objects::GPIO_IF); + #if TE0720 == 0 /* Pin H2-11 on stack connector */ GpiodRegular gpioConfigHeater0(std::string("gpiochip7"), 18, diff --git a/fsfw_hal b/fsfw_hal index 7a3190e5..feee39a6 160000 --- a/fsfw_hal +++ b/fsfw_hal @@ -1 +1 @@ -Subproject commit 7a3190e5b6980ad2addc5e8a76d21994b542f0e0 +Subproject commit feee39a6c759f699a07dcde4a97d4b5f779ec50b diff --git a/linux/archive/gpio/gpioDefinitions.h b/linux/archive/gpio/gpioDefinitions.h index 3b0f70fd..66c0b005 100644 --- a/linux/archive/gpio/gpioDefinitions.h +++ b/linux/archive/gpio/gpioDefinitions.h @@ -7,6 +7,12 @@ using gpioId_t = uint16_t; namespace gpio { + +enum Levels { + LOW = 0, + HIGH = 1 +}; + enum Direction { IN = 0, OUT = 1 From 53dafa70c3da4ec09fe3d5f99962079fda46d1a0 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 1 Apr 2021 15:22:16 +0200 Subject: [PATCH 49/79] one missing zeros --- fsfw | 2 +- fsfwconfig/objects/systemObjectList.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/fsfw b/fsfw index f2da3123..dea22059 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit f2da31239c43422f7254b8f4a26e663cffd8e3f3 +Subproject commit dea2205908f29cbb700ad85c2614da71b6efccfc diff --git a/fsfwconfig/objects/systemObjectList.h b/fsfwconfig/objects/systemObjectList.h index 459cbd77..43909e45 100644 --- a/fsfwconfig/objects/systemObjectList.h +++ b/fsfwconfig/objects/systemObjectList.h @@ -42,7 +42,7 @@ namespace objects { ACU_HANDLER = 0x44000004, TMP1075_HANDLER_1 = 0x44000005, TMP1075_HANDLER_2 = 0x44000006, - MGM_0_LIS3_HANDLER = 0x4400007, + MGM_0_LIS3_HANDLER = 0x44000007, MGM_1_RM3100_HANDLER = 0x44000008, MGM_2_LIS3_HANDLER = 0x44000009, MGM_3_RM3100_HANDLER = 0x44000010, From 6f49031e92595f325f5a1c2c8c84b7e3187bc74f Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 1 Apr 2021 15:42:51 +0200 Subject: [PATCH 50/79] some adaptions --- bsp_q7s/gpio/gpioCallbacks.cpp | 6 +++--- bsp_q7s/gpio/gpioCallbacks.h | 4 ++-- linux/boardtest/SpiTestClass.cpp | 10 +++++----- 3 files changed, 10 insertions(+), 10 deletions(-) diff --git a/bsp_q7s/gpio/gpioCallbacks.cpp b/bsp_q7s/gpio/gpioCallbacks.cpp index b85de9ab..b9af9b02 100644 --- a/bsp_q7s/gpio/gpioCallbacks.cpp +++ b/bsp_q7s/gpio/gpioCallbacks.cpp @@ -1,7 +1,7 @@ #include #include -#include -#include +#include +#include #include @@ -25,7 +25,7 @@ void initTcsBoardDecoder(GpioIF* gpioComIF) { * Initial values of the spi mux gpios can all be set to an arbitrary value expect for spi mux * bit 1. Setting spi mux bit 1 to high will pull all decoder outputs to high voltage level. */ - GpiodRegular* spiMuxBit1 = new GpiodRegular(std::string("gpiochip7"), 13, + GpiodRegular spiMuxBit1 = new GpiodRegular(std::string("gpiochip7"), 13, std::string("SPI Mux Bit 1"), gpio::OUT, 1); spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_1, spiMuxBit1); GpiodRegular* spiMuxBit2 = new GpiodRegular(std::string("gpiochip7"), 14, diff --git a/bsp_q7s/gpio/gpioCallbacks.h b/bsp_q7s/gpio/gpioCallbacks.h index 7654e548..845127fb 100644 --- a/bsp_q7s/gpio/gpioCallbacks.h +++ b/bsp_q7s/gpio/gpioCallbacks.h @@ -1,8 +1,8 @@ #ifndef LINUX_GPIO_GPIOCALLBACKS_H_ #define LINUX_GPIO_GPIOCALLBACKS_H_ -#include -#include +#include +#include namespace gpioCallbacks { diff --git a/linux/boardtest/SpiTestClass.cpp b/linux/boardtest/SpiTestClass.cpp index b9d1df55..cb5b996c 100644 --- a/linux/boardtest/SpiTestClass.cpp +++ b/linux/boardtest/SpiTestClass.cpp @@ -297,27 +297,27 @@ void SpiTestClass::acsInit() { { GpiodRegular gpio(rpiGpioName, mgm0Lis3ChipSelect, "MGM_0_LIS3", gpio::Direction::OUT, 1); - gpioCookie->addGpio(gpioIds::MGM_0_LIS3_CS, &gpio); + gpioCookie->addGpio(gpioIds::MGM_0_LIS3_CS, gpio); } { GpiodRegular gpio(rpiGpioName, mgm1Rm3100ChipSelect, "MGM_1_RM3100", gpio::Direction::OUT, 1); - gpioCookie->addGpio(gpioIds::MGM_1_RM3100_CS, &gpio); + gpioCookie->addGpio(gpioIds::MGM_1_RM3100_CS, gpio); } { GpiodRegular gpio(rpiGpioName, gyro0AdisChipSelect, "GYRO_0_ADIS", gpio::Direction::OUT, 1); - gpioCookie->addGpio(gpioIds::GYRO_0_ADIS_CS, &gpio); + gpioCookie->addGpio(gpioIds::GYRO_0_ADIS_CS, gpio); } { GpiodRegular gpio(rpiGpioName, gyro1L3gd20ChipSelect, "GYRO_1_L3G", gpio::Direction::OUT, 1); - gpioCookie->addGpio(gpioIds::GYRO_1_L3G_CS, &gpio); + gpioCookie->addGpio(gpioIds::GYRO_1_L3G_CS, gpio); } { GpiodRegular gpio(rpiGpioName, gyro2L3gd20ChipSelect, "GYRO_2_L3G", gpio::Direction::OUT, 1); - gpioCookie->addGpio(gpioIds::GYRO_2_L3G_CS, &gpio); + gpioCookie->addGpio(gpioIds::GYRO_2_L3G_CS, gpio); } { GpiodRegular gpio(rpiGpioName, mgm2Lis3mdlChipSelect, "MGM_2_LIS3", From c3f97dde30c8f03ea4a773b2e33ca2bc34c3b36c Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 1 Apr 2021 16:21:24 +0200 Subject: [PATCH 51/79] fixes --- bsp_q7s/ObjectFactory.cpp | 39 +++++++++-------- bsp_q7s/gpio/gpioCallbacks.cpp | 9 ++-- bsp_q7s/gpio/gpioCallbacks.h | 4 +- fsfw_hal | 2 +- .../pollingSequenceFactory.cpp | 42 +++++++++---------- linux/CMakeLists.txt | 2 +- 6 files changed, 51 insertions(+), 47 deletions(-) diff --git a/bsp_q7s/ObjectFactory.cpp b/bsp_q7s/ObjectFactory.cpp index b7222465..ac0c6353 100644 --- a/bsp_q7s/ObjectFactory.cpp +++ b/bsp_q7s/ObjectFactory.cpp @@ -33,9 +33,13 @@ #include #include +#include +#include + #include #include #include +#include #include #include @@ -94,8 +98,6 @@ void ObjectFactory::produce(){ new UartComIF(objects::UART_COM_IF); new SpiComIF(objects::SPI_COM_IF, gpioComIF); - auto gpioIF = new LinuxLibgpioIF(objects::GPIO_IF); - /* Temperature sensors */ Tmp1075Handler* tmp1075Handler_1 = new Tmp1075Handler( objects::TMP1075_HANDLER_1, objects::I2C_COM_IF, @@ -143,30 +145,31 @@ void ObjectFactory::produce(){ (void) acuhandler; GpioCookie* gpioCookieAcsBoard = new GpioCookie(); - GpiodRegular gpioGyro1(std::string("gpiochip5"), 21, std::string("CS_GYRO_1_ADIS"), + GpiodRegular* gpio = nullptr; + gpio = new GpiodRegular(std::string("gpiochip5"), 21, std::string("CS_GYRO_1_ADIS"), gpio::OUT, gpio::HIGH); - gpioCookieAcsBoard->addGpio(gpioIds::GYRO_0_ADIS_CS, gpioGyro1); - GpiodRegular gpioGyro2(std::string("gpiochip5"), 7, std::string("CS_GYRO_2_L3G"), + gpioCookieAcsBoard->addGpio(gpioIds::GYRO_0_ADIS_CS, gpio); + gpio = new GpiodRegular(std::string("gpiochip5"), 7, std::string("CS_GYRO_2_L3G"), gpio::OUT, gpio::HIGH); - gpioCookieAcsBoard->addGpio(gpioIds::GYRO_1_L3G_CS, gpioGyro2); - GpiodRegular gpioGyro3(std::string("gpiochip5"), 3, std::string("CS_GYRO_3_L3G"), + gpioCookieAcsBoard->addGpio(gpioIds::GYRO_1_L3G_CS, gpio); + gpio = new GpiodRegular(std::string("gpiochip5"), 3, std::string("CS_GYRO_3_L3G"), gpio::OUT, gpio::HIGH); - gpioCookieAcsBoard->addGpio(gpioIds::GYRO_2_L3G_CS, gpioGyro3); + gpioCookieAcsBoard->addGpio(gpioIds::GYRO_2_L3G_CS, gpio); - GpiodRegular gpioMgm0(std::string("gpiochip5"), 5, std::string("CS_MGM_0_LIS3_A"), + gpio = new GpiodRegular(std::string("gpiochip5"), 5, std::string("CS_MGM_0_LIS3_A"), gpio::OUT, gpio::HIGH); - gpioCookieAcsBoard->addGpio(gpioIds::MGM_0_LIS3_CS, gpioMgm0); - GpiodRegular gpioMgm1(std::string("gpiochip5"), 17, std::string("CS_MGM_1_RM3100_A"), + gpioCookieAcsBoard->addGpio(gpioIds::MGM_0_LIS3_CS, gpio); + gpio = new GpiodRegular(std::string("gpiochip5"), 17, std::string("CS_MGM_1_RM3100_A"), gpio::OUT, gpio::HIGH); - gpioCookieAcsBoard->addGpio(gpioIds::MGM_1_RM3100_CS, gpioMgm1); - GpiodRegular gpioMgm2(std::string("gpiochip6"), 0, std::string("CS_MGM_2_LIS3_B"), + gpioCookieAcsBoard->addGpio(gpioIds::MGM_1_RM3100_CS, gpio); + gpio = new GpiodRegular(std::string("gpiochip6"), 0, std::string("CS_MGM_2_LIS3_B"), gpio::OUT, gpio::HIGH); - gpioCookieAcsBoard->addGpio(gpioIds::MGM_2_LIS3_CS, gpioMgm2); - GpiodRegular gpioMgm3(std::string("gpiochip5"), 23, std::string("CS_MGM_3_RM3100_B"), + gpioCookieAcsBoard->addGpio(gpioIds::MGM_2_LIS3_CS, gpio); + gpio = new GpiodRegular(std::string("gpiochip5"), 23, std::string("CS_MGM_3_RM3100_B"), gpio::OUT, gpio::HIGH); - gpioCookieAcsBoard->addGpio(gpioIds::MGM_3_RM3100_CS, gpioMgm3); + gpioCookieAcsBoard->addGpio(gpioIds::MGM_3_RM3100_CS, gpio); - gpioIF->addGpios(gpioCookieAcsBoard); + gpioComIF->addGpios(gpioCookieAcsBoard); std::string spiDev = "/dev/spidev2.0"; SpiCookie* spiCookie = new SpiCookie(addresses::MGM_0_LIS3, gpioIds::MGM_0_LIS3_CS, spiDev, @@ -366,7 +369,7 @@ void ObjectFactory::produce(){ Max31865PT1000Handler* rtdIc16 = new Max31865PT1000Handler(objects::RTD_IC16, objects::SPI_COM_IF, spiRtdIc16, 0); Max31865PT1000Handler* rtdIc17 = new Max31865PT1000Handler(objects::RTD_IC17, objects::SPI_COM_IF, spiRtdIc17, 0); Max31865PT1000Handler* rtdIc18 = new Max31865PT1000Handler(objects::RTD_IC18, objects::SPI_COM_IF, spiRtdIc18, 0); - rtdIc10->setStartUpImmediately(); +// rtdIc10->setStartUpImmediately(); // rtdIc4->setStartUpImmediately(); #endif diff --git a/bsp_q7s/gpio/gpioCallbacks.cpp b/bsp_q7s/gpio/gpioCallbacks.cpp index b85de9ab..086e6469 100644 --- a/bsp_q7s/gpio/gpioCallbacks.cpp +++ b/bsp_q7s/gpio/gpioCallbacks.cpp @@ -1,7 +1,8 @@ -#include -#include -#include -#include +#include "gpioCallbacks.h" +#include + +#include +#include #include diff --git a/bsp_q7s/gpio/gpioCallbacks.h b/bsp_q7s/gpio/gpioCallbacks.h index 7654e548..845127fb 100644 --- a/bsp_q7s/gpio/gpioCallbacks.h +++ b/bsp_q7s/gpio/gpioCallbacks.h @@ -1,8 +1,8 @@ #ifndef LINUX_GPIO_GPIOCALLBACKS_H_ #define LINUX_GPIO_GPIOCALLBACKS_H_ -#include -#include +#include +#include namespace gpioCallbacks { diff --git a/fsfw_hal b/fsfw_hal index 7ffae254..c62cdbeb 160000 --- a/fsfw_hal +++ b/fsfw_hal @@ -1 +1 @@ -Subproject commit 7ffae254b1c2658c2b87566a7bb6856236c6e7e8 +Subproject commit c62cdbebcb521975043f1782692667faaf5a8aca diff --git a/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp b/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp index 5f1c8359..ce0b7490 100644 --- a/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp +++ b/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp @@ -182,27 +182,27 @@ ReturnValue_t pst::gomspacePstInit(FixedTimeslotTaskIF *thisSequence){ thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0.8, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0, - DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.2, - DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.4, - DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.6, - DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.8, - DeviceHandlerIF::GET_READ); - - thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0, - DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.2, - DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.4, - DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.6, - DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.8, - DeviceHandlerIF::GET_READ); +// thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0, +// DeviceHandlerIF::PERFORM_OPERATION); +// thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.2, +// DeviceHandlerIF::SEND_WRITE); +// thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.4, +// DeviceHandlerIF::GET_WRITE); +// thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.6, +// DeviceHandlerIF::SEND_READ); +// thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.8, +// DeviceHandlerIF::GET_READ); +// +// thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0, +// DeviceHandlerIF::PERFORM_OPERATION); +// thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.2, +// DeviceHandlerIF::SEND_WRITE); +// thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.4, +// DeviceHandlerIF::GET_WRITE); +// thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.6, +// DeviceHandlerIF::SEND_READ); +// thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.8, +// DeviceHandlerIF::GET_READ); if (thisSequence->checkSequence() != HasReturnvaluesIF::RETURN_OK) { sif::error << "Initialization of GomSpace PST failed" << std::endl; diff --git a/linux/CMakeLists.txt b/linux/CMakeLists.txt index d6824b0e..7e6d1f35 100644 --- a/linux/CMakeLists.txt +++ b/linux/CMakeLists.txt @@ -1,4 +1,4 @@ add_subdirectory(csp) +add_subdirectory(uart) add_subdirectory(utility) add_subdirectory(boardtest) - From 1134505457f69fe8b0df7e9f1ce0f735e67300a0 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 1 Apr 2021 16:33:30 +0200 Subject: [PATCH 52/79] now its compiling --- bsp_q7s/gpio/gpioCallbacks.cpp | 2 +- fsfw_hal | 2 +- fsfwconfig/OBSWConfig.h | 2 -- linux/boardtest/SpiTestClass.cpp | 19 ++++++++++--------- 4 files changed, 12 insertions(+), 13 deletions(-) diff --git a/bsp_q7s/gpio/gpioCallbacks.cpp b/bsp_q7s/gpio/gpioCallbacks.cpp index 5d7a639e..086e6469 100644 --- a/bsp_q7s/gpio/gpioCallbacks.cpp +++ b/bsp_q7s/gpio/gpioCallbacks.cpp @@ -26,7 +26,7 @@ void initTcsBoardDecoder(GpioIF* gpioComIF) { * Initial values of the spi mux gpios can all be set to an arbitrary value expect for spi mux * bit 1. Setting spi mux bit 1 to high will pull all decoder outputs to high voltage level. */ - GpiodRegular spiMuxBit1 = new GpiodRegular(std::string("gpiochip7"), 13, + GpiodRegular* spiMuxBit1 = new GpiodRegular(std::string("gpiochip7"), 13, std::string("SPI Mux Bit 1"), gpio::OUT, 1); spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_1, spiMuxBit1); GpiodRegular* spiMuxBit2 = new GpiodRegular(std::string("gpiochip7"), 14, diff --git a/fsfw_hal b/fsfw_hal index c62cdbeb..2fb50360 160000 --- a/fsfw_hal +++ b/fsfw_hal @@ -1 +1 @@ -Subproject commit c62cdbebcb521975043f1782692667faaf5a8aca +Subproject commit 2fb50360ef8910ed785d31cc4da098a77c26fd81 diff --git a/fsfwconfig/OBSWConfig.h b/fsfwconfig/OBSWConfig.h index 05ad0fe9..81e61653 100644 --- a/fsfwconfig/OBSWConfig.h +++ b/fsfwconfig/OBSWConfig.h @@ -31,8 +31,6 @@ debugging. */ /* Can be used to switch device to NORMAL mode immediately */ #define OBSW_SWITCH_TO_NORMAL_MODE_AFTER_STARTUP 1 -/* Can be used for low-level debugging of the SPI bus */ -#define FSFW_LINUX_SPI_WIRETAPPING 0 #ifdef __cplusplus diff --git a/linux/boardtest/SpiTestClass.cpp b/linux/boardtest/SpiTestClass.cpp index cb5b996c..ec6cc65c 100644 --- a/linux/boardtest/SpiTestClass.cpp +++ b/linux/boardtest/SpiTestClass.cpp @@ -294,40 +294,41 @@ void SpiTestClass::performL3gTest(uint8_t l3gId) { void SpiTestClass::acsInit() { GpioCookie* gpioCookie = new GpioCookie(); std::string rpiGpioName = "gpiochip0"; + GpiodRegular* gpio = nullptr; { - GpiodRegular gpio(rpiGpioName, mgm0Lis3ChipSelect, "MGM_0_LIS3", + gpio = new GpiodRegular(rpiGpioName, mgm0Lis3ChipSelect, "MGM_0_LIS3", gpio::Direction::OUT, 1); gpioCookie->addGpio(gpioIds::MGM_0_LIS3_CS, gpio); } { - GpiodRegular gpio(rpiGpioName, mgm1Rm3100ChipSelect, "MGM_1_RM3100", + gpio = new GpiodRegular(rpiGpioName, mgm1Rm3100ChipSelect, "MGM_1_RM3100", gpio::Direction::OUT, 1); gpioCookie->addGpio(gpioIds::MGM_1_RM3100_CS, gpio); } { - GpiodRegular gpio(rpiGpioName, gyro0AdisChipSelect, "GYRO_0_ADIS", + gpio = new GpiodRegular(rpiGpioName, gyro0AdisChipSelect, "GYRO_0_ADIS", gpio::Direction::OUT, 1); gpioCookie->addGpio(gpioIds::GYRO_0_ADIS_CS, gpio); } { - GpiodRegular gpio(rpiGpioName, gyro1L3gd20ChipSelect, "GYRO_1_L3G", + gpio = new GpiodRegular(rpiGpioName, gyro1L3gd20ChipSelect, "GYRO_1_L3G", gpio::Direction::OUT, 1); gpioCookie->addGpio(gpioIds::GYRO_1_L3G_CS, gpio); } { - GpiodRegular gpio(rpiGpioName, gyro2L3gd20ChipSelect, "GYRO_2_L3G", + gpio = new GpiodRegular(rpiGpioName, gyro2L3gd20ChipSelect, "GYRO_2_L3G", gpio::Direction::OUT, 1); gpioCookie->addGpio(gpioIds::GYRO_2_L3G_CS, gpio); } { - GpiodRegular gpio(rpiGpioName, mgm2Lis3mdlChipSelect, "MGM_2_LIS3", + gpio = new GpiodRegular(rpiGpioName, mgm2Lis3mdlChipSelect, "MGM_2_LIS3", gpio::Direction::OUT, 1); - gpioCookie->addGpio(gpioIds::MGM_2_LIS3_CS, &gpio); + gpioCookie->addGpio(gpioIds::MGM_2_LIS3_CS, gpio); } { - GpiodRegular gpio(rpiGpioName, mgm3Rm3100ChipSelect, "MGM_3_RM3100", + gpio = new GpiodRegular(rpiGpioName, mgm3Rm3100ChipSelect, "MGM_3_RM3100", gpio::Direction::OUT, 1); - gpioCookie->addGpio(gpioIds::MGM_3_RM3100_CS, &gpio); + gpioCookie->addGpio(gpioIds::MGM_3_RM3100_CS, gpio); } if(gpioIF != nullptr) { gpioIF->addGpios(gpioCookie); From 5b2c53cfd4e8ef2898e9ee2e58c341c66cfe3034 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 1 Apr 2021 17:06:35 +0200 Subject: [PATCH 53/79] small form improvements --- bsp_q7s/ObjectFactory.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/bsp_q7s/ObjectFactory.cpp b/bsp_q7s/ObjectFactory.cpp index ac0c6353..bbaa5e7c 100644 --- a/bsp_q7s/ObjectFactory.cpp +++ b/bsp_q7s/ObjectFactory.cpp @@ -159,12 +159,15 @@ void ObjectFactory::produce(){ gpio = new GpiodRegular(std::string("gpiochip5"), 5, std::string("CS_MGM_0_LIS3_A"), gpio::OUT, gpio::HIGH); gpioCookieAcsBoard->addGpio(gpioIds::MGM_0_LIS3_CS, gpio); + gpio = new GpiodRegular(std::string("gpiochip5"), 17, std::string("CS_MGM_1_RM3100_A"), gpio::OUT, gpio::HIGH); gpioCookieAcsBoard->addGpio(gpioIds::MGM_1_RM3100_CS, gpio); + gpio = new GpiodRegular(std::string("gpiochip6"), 0, std::string("CS_MGM_2_LIS3_B"), gpio::OUT, gpio::HIGH); gpioCookieAcsBoard->addGpio(gpioIds::MGM_2_LIS3_CS, gpio); + gpio = new GpiodRegular(std::string("gpiochip5"), 23, std::string("CS_MGM_3_RM3100_B"), gpio::OUT, gpio::HIGH); gpioCookieAcsBoard->addGpio(gpioIds::MGM_3_RM3100_CS, gpio); @@ -371,7 +374,7 @@ void ObjectFactory::produce(){ Max31865PT1000Handler* rtdIc18 = new Max31865PT1000Handler(objects::RTD_IC18, objects::SPI_COM_IF, spiRtdIc18, 0); // rtdIc10->setStartUpImmediately(); // rtdIc4->setStartUpImmediately(); -#endif +#endif /* TE0720 == 0 */ new UdpTmTcBridge(objects::UDP_BRIDGE, objects::CCSDS_PACKET_DISTRIBUTOR, From ce33a710e9ed5ef8371afcc1bafae1035c571ce1 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 1 Apr 2021 17:19:12 +0200 Subject: [PATCH 54/79] pushed stuff --- bsp_q7s/ObjectFactory.cpp | 2 + fsfwconfig/OBSWConfig.h | 13 +++-- .../pollingSequenceFactory.cpp | 57 ++++++++++++------- 3 files changed, 45 insertions(+), 27 deletions(-) diff --git a/bsp_q7s/ObjectFactory.cpp b/bsp_q7s/ObjectFactory.cpp index bbaa5e7c..ab32ec9a 100644 --- a/bsp_q7s/ObjectFactory.cpp +++ b/bsp_q7s/ObjectFactory.cpp @@ -144,6 +144,7 @@ void ObjectFactory::produce(){ (void) pdu2handler; (void) acuhandler; +#if OBSW_ADD_ACS_BOARD == 1 GpioCookie* gpioCookieAcsBoard = new GpioCookie(); GpiodRegular* gpio = nullptr; gpio = new GpiodRegular(std::string("gpiochip5"), 21, std::string("CS_GYRO_1_ADIS"), @@ -192,6 +193,7 @@ void ObjectFactory::produce(){ auto gyroL3gHandler = new GyroHandlerL3GD20H(objects::GYRO_1_L3G_HANDLER, objects::SPI_COM_IF, spiCookie); gyroL3gHandler->setStartUpImmediately(); +#endif /* Pin H2-11 on stack connector */ GpiodRegular* gpioConfigHeater0 = new GpiodRegular(std::string("gpiochip7"), 6, diff --git a/fsfwconfig/OBSWConfig.h b/fsfwconfig/OBSWConfig.h index 81e61653..a41757e1 100644 --- a/fsfwconfig/OBSWConfig.h +++ b/fsfwconfig/OBSWConfig.h @@ -20,12 +20,15 @@ debugging. */ #define TEST_LIBGPIOD 0 #define TE0720 0 +/* Add code for ACS board */ +#define OBSW_ADD_ACS_BOARD 1 + +#define P60DOCK_DEBUG 0 +#define PDU1_DEBUG 0 +#define PDU2_DEBUG 0 +#define ACU_DEBUG 0 +#define SYRLINKS_DEBUG 0 -#define P60DOCK_DEBUG 0 -#define PDU1_DEBUG 0 -#define PDU2_DEBUG 0 -#define ACU_DEBUG 0 -#define SYRLINKS_DEBUG 0 #include "OBSWVersion.h" diff --git a/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp b/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp index ce0b7490..ef11f41e 100644 --- a/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp +++ b/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp @@ -1,5 +1,5 @@ #include "pollingSequenceFactory.h" - +#include #include #include #include @@ -171,6 +171,7 @@ ReturnValue_t pst::gomspacePstInit(FixedTimeslotTaskIF *thisSequence){ thisSequence->addSlot(objects::ACU_HANDLER, length * 0.8, DeviceHandlerIF::GET_READ); +#if OBSW_ADD_ACS_BOARD == 1 thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0.2, @@ -182,27 +183,39 @@ ReturnValue_t pst::gomspacePstInit(FixedTimeslotTaskIF *thisSequence){ thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0.8, DeviceHandlerIF::GET_READ); -// thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0, -// DeviceHandlerIF::PERFORM_OPERATION); -// thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.2, -// DeviceHandlerIF::SEND_WRITE); -// thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.4, -// DeviceHandlerIF::GET_WRITE); -// thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.6, -// DeviceHandlerIF::SEND_READ); -// thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.8, -// DeviceHandlerIF::GET_READ); -// -// thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0, -// DeviceHandlerIF::PERFORM_OPERATION); -// thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.2, -// DeviceHandlerIF::SEND_WRITE); -// thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.4, -// DeviceHandlerIF::GET_WRITE); -// thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.6, -// DeviceHandlerIF::SEND_READ); -// thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.8, -// DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.2, + DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.4, + DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.6, + DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.8, + DeviceHandlerIF::GET_READ); + + thisSequence->addSlot(objects::MGM_2_LIS3_HANDLER, length * 0, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::MGM_2_LIS3_HANDLER, length * 0.2, + DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::MGM_2_LIS3_HANDLER, length * 0.4, + DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::MGM_2_LIS3_HANDLER, length * 0.6, + DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::MGM_2_LIS3_HANDLER, length * 0.8, + DeviceHandlerIF::GET_READ); + + thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.2, + DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.4, + DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.6, + DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.8, + DeviceHandlerIF::GET_READ); +#endif if (thisSequence->checkSequence() != HasReturnvaluesIF::RETURN_OK) { sif::error << "Initialization of GomSpace PST failed" << std::endl; From fca78108a25bc2ff3bcf940e0cde5707dea5e207 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 2 Apr 2021 13:25:37 +0200 Subject: [PATCH 55/79] added device handler --- bsp_q7s/ObjectFactory.cpp | 6 ++ .../pollingSequenceFactory.cpp | 62 +++++++++---------- 2 files changed, 37 insertions(+), 31 deletions(-) diff --git a/bsp_q7s/ObjectFactory.cpp b/bsp_q7s/ObjectFactory.cpp index ab32ec9a..47cc1934 100644 --- a/bsp_q7s/ObjectFactory.cpp +++ b/bsp_q7s/ObjectFactory.cpp @@ -182,6 +182,12 @@ void ObjectFactory::produce(){ objects::SPI_COM_IF, spiCookie); mgmLis3Handler->setStartUpImmediately(); + spiCookie = new SpiCookie(addresses::MGM_2_LIS3, gpioIds::MGM_2_LIS3_CS, spiDev, + MGMLIS3MDL::MAX_BUFFER_SIZE, spi::DEFAULT_LIS3_MODE, spi::DEFAULT_LIS3_SPEED); + auto mgmLis3Handler2 = new MGMHandlerLIS3MDL(objects::MGM_0_LIS3_HANDLER, + objects::SPI_COM_IF, spiCookie); + mgmLis3Handler2->setStartUpImmediately(); + spiCookie = new SpiCookie(addresses::MGM_1_RM3100, gpioIds::MGM_1_RM3100_CS, spiDev, RM3100::MAX_BUFFER_SIZE, spi::DEFAULT_RM3100_MODE, spi::DEFAULT_RM3100_SPEED); auto mgmRm3100Handler = new MGMHandlerRM3100(objects::MGM_1_RM3100_HANDLER, diff --git a/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp b/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp index ef11f41e..63a21081 100644 --- a/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp +++ b/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp @@ -172,27 +172,27 @@ ReturnValue_t pst::gomspacePstInit(FixedTimeslotTaskIF *thisSequence){ length * 0.8, DeviceHandlerIF::GET_READ); #if OBSW_ADD_ACS_BOARD == 1 - thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0, - DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0.2, - DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0.4, - DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0.6, - DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0.8, - DeviceHandlerIF::GET_READ); - - thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0, - DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.2, - DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.4, - DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.6, - DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.8, - DeviceHandlerIF::GET_READ); +// thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0, +// DeviceHandlerIF::PERFORM_OPERATION); +// thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0.2, +// DeviceHandlerIF::SEND_WRITE); +// thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0.4, +// DeviceHandlerIF::GET_WRITE); +// thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0.6, +// DeviceHandlerIF::SEND_READ); +// thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0.8, +// DeviceHandlerIF::GET_READ); +// +// thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0, +// DeviceHandlerIF::PERFORM_OPERATION); +// thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.2, +// DeviceHandlerIF::SEND_WRITE); +// thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.4, +// DeviceHandlerIF::GET_WRITE); +// thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.6, +// DeviceHandlerIF::SEND_READ); +// thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.8, +// DeviceHandlerIF::GET_READ); thisSequence->addSlot(objects::MGM_2_LIS3_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); @@ -205,16 +205,16 @@ ReturnValue_t pst::gomspacePstInit(FixedTimeslotTaskIF *thisSequence){ thisSequence->addSlot(objects::MGM_2_LIS3_HANDLER, length * 0.8, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0, - DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.2, - DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.4, - DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.6, - DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.8, - DeviceHandlerIF::GET_READ); +// thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0, +// DeviceHandlerIF::PERFORM_OPERATION); +// thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.2, +// DeviceHandlerIF::SEND_WRITE); +// thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.4, +// DeviceHandlerIF::GET_WRITE); +// thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.6, +// DeviceHandlerIF::SEND_READ); +// thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.8, +// DeviceHandlerIF::GET_READ); #endif if (thisSequence->checkSequence() != HasReturnvaluesIF::RETURN_OK) { From 08351bcda255f247934678459570d0da73aa1376 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 2 Apr 2021 15:14:08 +0200 Subject: [PATCH 56/79] added more spi test code, preprocessor defines and various bugfixes --- bsp_q7s/InitMission.cpp | 18 +++- bsp_q7s/ObjectFactory.cpp | 12 ++- bsp_q7s/boardconfig/q7s_config.h | 11 +++ fsfw_hal | 2 +- fsfwconfig/OBSWConfig.h | 4 +- fsfwconfig/objects/systemObjectList.h | 2 +- linux/boardtest/SpiTestClass.cpp | 129 ++++++++++++++++---------- linux/boardtest/SpiTestClass.h | 11 +++ mission/devices/MGMHandlerLIS3MDL.cpp | 4 +- 9 files changed, 136 insertions(+), 57 deletions(-) create mode 100644 bsp_q7s/boardconfig/q7s_config.h diff --git a/bsp_q7s/InitMission.cpp b/bsp_q7s/InitMission.cpp index c776ead0..3fe0ba0c 100644 --- a/bsp_q7s/InitMission.cpp +++ b/bsp_q7s/InitMission.cpp @@ -137,6 +137,7 @@ void initmission::initTasks() { //TODO: Add handling of missed deadlines /* Polling Sequence Table Default */ +#if Q7S_ADD_SPI_TEST == 0 FixedTimeslotTaskIF * pollingSequenceTableTaskDefault = factory->createFixedTimeslotTask( "PST_TASK_DEFAULT", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE * 4, 3.0, missedDeadlineFunc); @@ -144,6 +145,7 @@ void initmission::initTasks() { if (result != HasReturnvaluesIF::RETURN_OK) { sif::error << "InitMission::initTasks: Creating PST failed!" << std::endl; } +#endif #if TE0720 == 0 FixedTimeslotTaskIF* gomSpacePstTask = factory-> @@ -155,13 +157,20 @@ void initmission::initTasks() { } #endif - PeriodicTaskIF* testTask = factory->createPeriodicTask( - "GPIOD_TEST", 60, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1, missedDeadlineFunc); #if OBSW_ADD_TEST_CODE == 1 + PeriodicTaskIF* testTask = factory->createPeriodicTask( + "TEST_TASK", 60, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1, missedDeadlineFunc); result = testTask->addComponent(objects::TEST_TASK); if(result != HasReturnvaluesIF::RETURN_OK) { initmission::printAddObjectError("TEST_TASK", objects::TEST_TASK); } + +#if Q7S_ADD_SPI_TEST == 1 + result = testTask->addComponent(objects::SPI_TEST); + if(result != HasReturnvaluesIF::RETURN_OK) { + initmission::printAddObjectError("SPI_TEST", objects::SPI_TEST); + } +#endif #endif /* OBSW_ADD_TEST_CODE == 1 */ #if TE0720 == 1 && TEST_LIBGPIOD == 1 result = testTask->addComponent(objects::LIBGPIOD_TEST); @@ -178,7 +187,10 @@ void initmission::initTasks() { #if TE0720 == 0 gomSpacePstTask->startTask(); #endif + +#if Q7S_ADD_SPI_TEST == 0 pollingSequenceTableTaskDefault->startTask(); +#endif pusVerification->startTask(); pusEvents->startTask(); @@ -186,6 +198,8 @@ void initmission::initTasks() { pusMedPrio->startTask(); pusLowPrio->startTask(); +#if OBSW_ADD_TEST_CODE == 1 testTask->startTask(); +#endif sif::info << "Tasks started.." << std::endl; } diff --git a/bsp_q7s/ObjectFactory.cpp b/bsp_q7s/ObjectFactory.cpp index 47cc1934..fed5734c 100644 --- a/bsp_q7s/ObjectFactory.cpp +++ b/bsp_q7s/ObjectFactory.cpp @@ -51,6 +51,7 @@ /* UDP server includes */ #include #include +#include #if TEST_LIBGPIOD == 1 #include @@ -96,7 +97,9 @@ void ObjectFactory::produce(){ new CspComIF(objects::CSP_COM_IF); new I2cComIF(objects::I2C_COM_IF); new UartComIF(objects::UART_COM_IF); +#if Q7S_ADD_SPI_TEST == 0 new SpiComIF(objects::SPI_COM_IF, gpioComIF); +#endif /* Temperature sensors */ Tmp1075Handler* tmp1075Handler_1 = new Tmp1075Handler( @@ -184,7 +187,7 @@ void ObjectFactory::produce(){ spiCookie = new SpiCookie(addresses::MGM_2_LIS3, gpioIds::MGM_2_LIS3_CS, spiDev, MGMLIS3MDL::MAX_BUFFER_SIZE, spi::DEFAULT_LIS3_MODE, spi::DEFAULT_LIS3_SPEED); - auto mgmLis3Handler2 = new MGMHandlerLIS3MDL(objects::MGM_0_LIS3_HANDLER, + auto mgmLis3Handler2 = new MGMHandlerLIS3MDL(objects::MGM_2_LIS3_HANDLER, objects::SPI_COM_IF, spiCookie); mgmLis3Handler2->setStartUpImmediately(); @@ -261,6 +264,7 @@ void ObjectFactory::produce(){ objects::UART_COM_IF, syrlinksUartCookie); syrlinksHkHandler->setModeNormal(); +#if Q7S_ADD_SPI_TEST == 0 GpioCookie* rtdGpioCookie = new GpioCookie; gpioCallbacks::initTcsBoardDecoder(gpioComIF); @@ -382,6 +386,8 @@ void ObjectFactory::produce(){ Max31865PT1000Handler* rtdIc18 = new Max31865PT1000Handler(objects::RTD_IC18, objects::SPI_COM_IF, spiRtdIc18, 0); // rtdIc10->setStartUpImmediately(); // rtdIc4->setStartUpImmediately(); +#endif /* Q7S_ADD_SPI_TEST == 0 */ + #endif /* TE0720 == 0 */ new UdpTmTcBridge(objects::UDP_BRIDGE, @@ -404,4 +410,8 @@ void ObjectFactory::produce(){ new HeaterHandler(objects::HEATER_HANDLER, objects::GPIO_IF, heaterGpiosCookie, objects::PCDU_HANDLER, pcduSwitches::TCS_BOARD_8V_HEATER_IN); #endif + +#if Q7S_ADD_SPI_TEST == 1 + new SpiTestClass(objects::SPI_TEST, gpioComIF); +#endif } diff --git a/bsp_q7s/boardconfig/q7s_config.h b/bsp_q7s/boardconfig/q7s_config.h new file mode 100644 index 00000000..d4b821c1 --- /dev/null +++ b/bsp_q7s/boardconfig/q7s_config.h @@ -0,0 +1,11 @@ +#ifndef BSP_Q7S_BOARDCONFIG_Q7S_CONFIG_H_ +#define BSP_Q7S_BOARDCONFIG_Q7S_CONFIG_H_ + +/* Only one of those 2 should be enabled! */ +/* Add code for ACS board */ +#define OBSW_ADD_ACS_BOARD 0 +#define Q7S_ADD_SPI_TEST 1 + + + +#endif /* BSP_Q7S_BOARDCONFIG_Q7S_CONFIG_H_ */ diff --git a/fsfw_hal b/fsfw_hal index 2fb50360..94fcbd58 160000 --- a/fsfw_hal +++ b/fsfw_hal @@ -1 +1 @@ -Subproject commit 2fb50360ef8910ed785d31cc4da098a77c26fd81 +Subproject commit 94fcbd587ea9eac76fbe6cbd85e1559c42235ce9 diff --git a/fsfwconfig/OBSWConfig.h b/fsfwconfig/OBSWConfig.h index a41757e1..b650597a 100644 --- a/fsfwconfig/OBSWConfig.h +++ b/fsfwconfig/OBSWConfig.h @@ -8,6 +8,8 @@ #ifdef RASPBERRY_PI #include +#elif defined(XIPHOS_Q7S) +#include #endif #include "commonConfig.h" #include "OBSWVersion.h" @@ -20,8 +22,6 @@ debugging. */ #define TEST_LIBGPIOD 0 #define TE0720 0 -/* Add code for ACS board */ -#define OBSW_ADD_ACS_BOARD 1 #define P60DOCK_DEBUG 0 #define PDU1_DEBUG 0 diff --git a/fsfwconfig/objects/systemObjectList.h b/fsfwconfig/objects/systemObjectList.h index 2d1fd82a..44d58a79 100644 --- a/fsfwconfig/objects/systemObjectList.h +++ b/fsfwconfig/objects/systemObjectList.h @@ -54,7 +54,7 @@ namespace objects { /* Custom device handler */ PCDU_HANDLER = 0x44001000, SOLAR_ARRAY_DEPL_HANDLER = 0x44001001, - SYRLINKS_HK_HANDLER = 0x44000009, + SYRLINKS_HK_HANDLER = 0x44001002, /* 0x54 ('T') for thermal objects */ HEATER_HANDLER = 0x54000003, diff --git a/linux/boardtest/SpiTestClass.cpp b/linux/boardtest/SpiTestClass.cpp index ec6cc65c..b46cef4b 100644 --- a/linux/boardtest/SpiTestClass.cpp +++ b/linux/boardtest/SpiTestClass.cpp @@ -21,11 +21,11 @@ SpiTestClass::SpiTestClass(object_id_t objectId, GpioIF* gpioIF): TestTask(objectId), - gpioIF(gpioIF) { +gpioIF(gpioIF) { if(gpioIF == nullptr) { sif::error << "SpiTestClass::SpiTestClass: Invalid GPIO ComIF!" << std::endl; } - testMode = TestModes::GYRO_L3GD20H; + testMode = TestModes::MGM_LIS3MDL; spiTransferStruct.rx_buf = reinterpret_cast<__u64>(recvBuffer.data()); spiTransferStruct.tx_buf = reinterpret_cast<__u64>(sendBuffer.data()); } @@ -36,11 +36,11 @@ ReturnValue_t SpiTestClass::performOneShotAction() { break; } case(TestModes::MGM_LIS3MDL): { - performLis3MdlTest(mgm0Lis3ChipSelect); + performLis3MdlTest(mgm2Lis3mdlChipSelect); break; } case(TestModes::MGM_RM3100): { - performRm3100Test(mgm1Rm3100ChipSelect); + performRm3100Test(mgm3Rm3100ChipSelect); break; } case(TestModes::GYRO_L3GD20H): { @@ -78,7 +78,7 @@ void SpiTestClass::performRm3100Test(uint8_t mgmId) { #ifdef RASPBERRY_PI std::string deviceName = "/dev/spidev0.0"; #else - std::string deviceName = "placeholder"; + std::string deviceName = "/dev/spidev2.0"; #endif int fileDescriptor = 0; @@ -160,13 +160,14 @@ void SpiTestClass::performLis3MdlTest(uint8_t lis3Id) { acsInit(); /* Adapt accordingly */ - if(lis3Id != mgm0Lis3ChipSelect and lis3Id != mgm2Lis3mdlChipSelect) { + if(lis3Id != mgm0Lis3mdlChipSelect and lis3Id != mgm2Lis3mdlChipSelect) { sif::warning << "SpiTestClass::performLis3MdlTest: Invalid MGM ID!" << std::endl; } gpioId_t currentGpioId = 0; uint8_t chipSelectPin = lis3Id; uint8_t whoAmIReg = 0b0000'1111; - if(chipSelectPin == mgm0Lis3ChipSelect) { + uint8_t whoAmIRegExpectedVal = 0b0011'1101; + if(chipSelectPin == mgm0Lis3mdlChipSelect) { currentGpioId = gpioIds::MGM_0_LIS3_CS; } else { @@ -177,7 +178,7 @@ void SpiTestClass::performLis3MdlTest(uint8_t lis3Id) { #ifdef RASPBERRY_PI std::string deviceName = "/dev/spidev0.0"; #else - std::string deviceName = "placeholder"; + std::string deviceName = "/dev/spidev2.0"; #endif int fileDescriptor = 0; @@ -189,10 +190,15 @@ void SpiTestClass::performLis3MdlTest(uint8_t lis3Id) { return; } setSpiSpeedAndMode(fileDescriptor, spiMode, spiSpeed); + spiTransferStruct.delay_usecs = 0; uint8_t whoAmIRegVal = readStmRegister(fileDescriptor, currentGpioId, whoAmIReg, false); sif::info << "SpiTestClass::performLis3MdlTest: WHO AM I register 0b" << std::bitset<8>(whoAmIRegVal) << std::endl; + if(whoAmIRegVal != whoAmIRegExpectedVal) { + sif::warning << "SpiTestClass::performLis3MdlTest: WHO AM I register invalid!" + << std::endl; + } } @@ -223,7 +229,7 @@ void SpiTestClass::performL3gTest(uint8_t l3gId) { #ifdef RASPBERRY_PI std::string deviceName = "/dev/spidev0.0"; #else - std::string deviceName = "placeholder"; + std::string deviceName = "/dev/spidev2.0"; #endif int fileDescriptor = 0; @@ -293,46 +299,73 @@ void SpiTestClass::performL3gTest(uint8_t l3gId) { void SpiTestClass::acsInit() { GpioCookie* gpioCookie = new GpioCookie(); - std::string rpiGpioName = "gpiochip0"; GpiodRegular* gpio = nullptr; - { - gpio = new GpiodRegular(rpiGpioName, mgm0Lis3ChipSelect, "MGM_0_LIS3", - gpio::Direction::OUT, 1); - gpioCookie->addGpio(gpioIds::MGM_0_LIS3_CS, gpio); - } - { - gpio = new GpiodRegular(rpiGpioName, mgm1Rm3100ChipSelect, "MGM_1_RM3100", - gpio::Direction::OUT, 1); - gpioCookie->addGpio(gpioIds::MGM_1_RM3100_CS, gpio); - } - { - gpio = new GpiodRegular(rpiGpioName, gyro0AdisChipSelect, "GYRO_0_ADIS", - gpio::Direction::OUT, 1); - gpioCookie->addGpio(gpioIds::GYRO_0_ADIS_CS, gpio); - } - { - gpio = new GpiodRegular(rpiGpioName, gyro1L3gd20ChipSelect, "GYRO_1_L3G", - gpio::Direction::OUT, 1); - gpioCookie->addGpio(gpioIds::GYRO_1_L3G_CS, gpio); - } - { - gpio = new GpiodRegular(rpiGpioName, gyro2L3gd20ChipSelect, "GYRO_2_L3G", - gpio::Direction::OUT, 1); - gpioCookie->addGpio(gpioIds::GYRO_2_L3G_CS, gpio); - } - { - gpio = new GpiodRegular(rpiGpioName, mgm2Lis3mdlChipSelect, "MGM_2_LIS3", - gpio::Direction::OUT, 1); - gpioCookie->addGpio(gpioIds::MGM_2_LIS3_CS, gpio); - } - { - gpio = new GpiodRegular(rpiGpioName, mgm3Rm3100ChipSelect, "MGM_3_RM3100", - gpio::Direction::OUT, 1); - gpioCookie->addGpio(gpioIds::MGM_3_RM3100_CS, gpio); - } - if(gpioIF != nullptr) { - gpioIF->addGpios(gpioCookie); - } +#ifdef RASPBERRY_PI + std::string rpiGpioName = "gpiochip0"; + gpio = new GpiodRegular(rpiGpioName, mgm0Lis3mdlChipSelect, "MGM_0_LIS3", + gpio::Direction::OUT, 1); + gpioCookie->addGpio(gpioIds::MGM_0_LIS3_CS, gpio); + + gpio = new GpiodRegular(rpiGpioName, mgm1Rm3100ChipSelect, "MGM_1_RM3100", + gpio::Direction::OUT, 1); + gpioCookie->addGpio(gpioIds::MGM_1_RM3100_CS, gpio); + + gpio = new GpiodRegular(rpiGpioName, gyro0AdisChipSelect, "GYRO_0_ADIS", + gpio::Direction::OUT, 1); + gpioCookie->addGpio(gpioIds::GYRO_0_ADIS_CS, gpio); + + gpio = new GpiodRegular(rpiGpioName, gyro1L3gd20ChipSelect, "GYRO_1_L3G", + gpio::Direction::OUT, 1); + gpioCookie->addGpio(gpioIds::GYRO_1_L3G_CS, gpio); + + gpio = new GpiodRegular(rpiGpioName, gyro2L3gd20ChipSelect, "GYRO_2_L3G", + gpio::Direction::OUT, 1); + gpioCookie->addGpio(gpioIds::GYRO_2_L3G_CS, gpio); + + gpio = new GpiodRegular(rpiGpioName, mgm2Lis3mdlChipSelect, "MGM_2_LIS3", + gpio::Direction::OUT, 1); + gpioCookie->addGpio(gpioIds::MGM_2_LIS3_CS, gpio); + + gpio = new GpiodRegular(rpiGpioName, mgm3Rm3100ChipSelect, "MGM_3_RM3100", + gpio::Direction::OUT, 1); + gpioCookie->addGpio(gpioIds::MGM_3_RM3100_CS, gpio); +} +#elif defined(XIPHOS_Q7S) + std::string q7sGpioName5 = "gpiochip5"; + std::string q7sGpioName6 = "gpiochip6"; + + gpio = new GpiodRegular(q7sGpioName5, mgm0Lis3mdlChipSelect, "MGM_0_LIS3", + gpio::Direction::OUT, gpio::HIGH); + gpioCookie->addGpio(gpioIds::MGM_0_LIS3_CS, gpio); + + gpio = new GpiodRegular(q7sGpioName5, mgm1Rm3100ChipSelect, "MGM_1_RM3100", + gpio::Direction::OUT, gpio::HIGH); + gpioCookie->addGpio(gpioIds::MGM_1_RM3100_CS, gpio); + + gpio = new GpiodRegular(q7sGpioName5, gyro0AdisChipSelect, "GYRO_0_ADIS", + gpio::Direction::OUT, gpio::HIGH); + gpioCookie->addGpio(gpioIds::GYRO_0_ADIS_CS, gpio); + + gpio = new GpiodRegular(q7sGpioName5, gyro1L3gd20ChipSelect, "GYRO_1_L3G", + gpio::Direction::OUT, gpio::HIGH); + gpioCookie->addGpio(gpioIds::GYRO_1_L3G_CS, gpio); + + gpio = new GpiodRegular(q7sGpioName5, gyro2L3gd20ChipSelect, "GYRO_2_L3G", + gpio::Direction::OUT, gpio::HIGH); + gpioCookie->addGpio(gpioIds::GYRO_2_L3G_CS, gpio); + + gpio = new GpiodRegular(q7sGpioName6, mgm2Lis3mdlChipSelect, "MGM_2_LIS3", + gpio::Direction::OUT, gpio::HIGH); + gpioCookie->addGpio(gpioIds::MGM_2_LIS3_CS, gpio); + + gpio = new GpiodRegular(q7sGpioName5, mgm3Rm3100ChipSelect, "MGM_3_RM3100", + gpio::Direction::OUT, gpio::HIGH); + gpioCookie->addGpio(gpioIds::MGM_3_RM3100_CS, gpio); +#endif +if(gpioIF != nullptr) { + gpioIF->addGpios(gpioCookie); +} + } void SpiTestClass::setSpiSpeedAndMode(int spiFd, spi::SpiModes mode, uint32_t speed) { diff --git a/linux/boardtest/SpiTestClass.h b/linux/boardtest/SpiTestClass.h index f92799b5..c24a5156 100644 --- a/linux/boardtest/SpiTestClass.h +++ b/linux/boardtest/SpiTestClass.h @@ -38,6 +38,7 @@ private: void acsInit(); /* ACS board specific variables */ +#ifdef RASPBERRY_PI uint8_t mgm0Lis3ChipSelect = 0; uint8_t mgm1Rm3100ChipSelect = 1; uint8_t gyro0AdisChipSelect = 5; @@ -45,6 +46,16 @@ private: uint8_t gyro2L3gd20ChipSelect = 4; uint8_t mgm2Lis3mdlChipSelect = 17; uint8_t mgm3Rm3100ChipSelect = 27; +#elif defined(XIPHOS_Q7S) + uint8_t mgm0Lis3mdlChipSelect = 5; + uint8_t mgm1Rm3100ChipSelect = 17; + uint8_t gyro0AdisResetLin = 20; + uint8_t gyro0AdisChipSelect = 21; + uint8_t gyro1L3gd20ChipSelect = 7; + uint8_t gyro2L3gd20ChipSelect = 3; + uint8_t mgm2Lis3mdlChipSelect = 0; + uint8_t mgm3Rm3100ChipSelect = 23; +#endif static constexpr uint8_t STM_READ_MASK = 0b1000'0000; static constexpr uint8_t RM3100_READ_MASK = STM_READ_MASK; diff --git a/mission/devices/MGMHandlerLIS3MDL.cpp b/mission/devices/MGMHandlerLIS3MDL.cpp index 17854de7..15f6e325 100644 --- a/mission/devices/MGMHandlerLIS3MDL.cpp +++ b/mission/devices/MGMHandlerLIS3MDL.cpp @@ -33,8 +33,8 @@ void MGMHandlerLIS3MDL::doStartUp() { /* Will be set by checking device ID (WHO AM I register) */ if(commandExecuted) { commandExecuted = false; + internalState = InternalState::STATE_SETUP; } - internalState = InternalState::STATE_SETUP; break; } case(InternalState::STATE_SETUP): { @@ -463,7 +463,7 @@ void MGMHandlerLIS3MDL::doTransition(Mode_t modeFrom, Submode_t subModeFrom) { } uint32_t MGMHandlerLIS3MDL::getTransitionDelayMs(Mode_t from, Mode_t to) { - return 10000; + return 20000; } void MGMHandlerLIS3MDL::modeChanged(void) { From 1935a15800902cae22e3bcdcdfe9aeb760ade410 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 2 Apr 2021 15:16:41 +0200 Subject: [PATCH 57/79] hal update --- fsfw_hal | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/fsfw_hal b/fsfw_hal index 94fcbd58..c47d3996 160000 --- a/fsfw_hal +++ b/fsfw_hal @@ -1 +1 @@ -Subproject commit 94fcbd587ea9eac76fbe6cbd85e1559c42235ce9 +Subproject commit c47d39964fcdc08f6ab93a5e6b6e3b63d4a21abb From e98e04a94077c4275d66673a521fedb74f84195e Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 2 Apr 2021 15:26:57 +0200 Subject: [PATCH 58/79] minor formatting stuff --- linux/boardtest/SpiTestClass.cpp | 4 ++-- linux/boardtest/SpiTestClass.h | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/linux/boardtest/SpiTestClass.cpp b/linux/boardtest/SpiTestClass.cpp index b46cef4b..8ad03b7d 100644 --- a/linux/boardtest/SpiTestClass.cpp +++ b/linux/boardtest/SpiTestClass.cpp @@ -25,7 +25,7 @@ gpioIF(gpioIF) { if(gpioIF == nullptr) { sif::error << "SpiTestClass::SpiTestClass: Invalid GPIO ComIF!" << std::endl; } - testMode = TestModes::MGM_LIS3MDL; + testMode = TestModes::GYRO_L3GD20H; spiTransferStruct.rx_buf = reinterpret_cast<__u64>(recvBuffer.data()); spiTransferStruct.tx_buf = reinterpret_cast<__u64>(sendBuffer.data()); } @@ -266,7 +266,7 @@ void SpiTestClass::performL3gTest(uint8_t l3gId) { for(uint8_t idx = 0; idx < sizeof(readRegs); idx++) { if(readRegs[idx] != commandRegs[0]) { sif::warning << "SpiTestClass::performL3gTest: Read control register" << - static_cast(idx + 1) << "not equal to configured value" << std::endl; + static_cast(idx + 1) << " not equal to configured value" << std::endl; } } } diff --git a/linux/boardtest/SpiTestClass.h b/linux/boardtest/SpiTestClass.h index c24a5156..9c6305f6 100644 --- a/linux/boardtest/SpiTestClass.h +++ b/linux/boardtest/SpiTestClass.h @@ -49,9 +49,9 @@ private: #elif defined(XIPHOS_Q7S) uint8_t mgm0Lis3mdlChipSelect = 5; uint8_t mgm1Rm3100ChipSelect = 17; - uint8_t gyro0AdisResetLin = 20; + uint8_t gyro0AdisResetLine = 20; uint8_t gyro0AdisChipSelect = 21; - uint8_t gyro1L3gd20ChipSelect = 7; + uint8_t gyro1L3gd20ChipSelect = 10; uint8_t gyro2L3gd20ChipSelect = 3; uint8_t mgm2Lis3mdlChipSelect = 0; uint8_t mgm3Rm3100ChipSelect = 23; From e43266490d93a7a26294f17a75af9697ee273ea8 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 2 Apr 2021 16:44:25 +0200 Subject: [PATCH 59/79] non block almostr eworking --- linux/boardtest/SpiTestClass.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/linux/boardtest/SpiTestClass.cpp b/linux/boardtest/SpiTestClass.cpp index 8ad03b7d..dc7ca931 100644 --- a/linux/boardtest/SpiTestClass.cpp +++ b/linux/boardtest/SpiTestClass.cpp @@ -265,7 +265,7 @@ void SpiTestClass::performL3gTest(uint8_t l3gId) { sizeof(readRegs)); for(uint8_t idx = 0; idx < sizeof(readRegs); idx++) { if(readRegs[idx] != commandRegs[0]) { - sif::warning << "SpiTestClass::performL3gTest: Read control register" << + sif::warning << "SpiTestClass::performL3gTest: Read control register " << static_cast(idx + 1) << " not equal to configured value" << std::endl; } } From 43a3bcbf0a257802821ddb1bc53da43a7a27e918 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Sat, 10 Apr 2021 21:59:19 +0200 Subject: [PATCH 60/79] fsfw and fsfw_hal update --- fsfw | 2 +- fsfw_hal | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/fsfw b/fsfw index dea22059..720ce596 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit dea2205908f29cbb700ad85c2614da71b6efccfc +Subproject commit 720ce596807e0e60629725bc2730ab0fcf3dca01 diff --git a/fsfw_hal b/fsfw_hal index c47d3996..a12f0363 160000 --- a/fsfw_hal +++ b/fsfw_hal @@ -1 +1 @@ -Subproject commit c47d39964fcdc08f6ab93a5e6b6e3b63d4a21abb +Subproject commit a12f036339ab2f6716fae4ba95e3205f0b827271 From f2c7bfc94299d5b87af0dfb0a0c27e41490f4c68 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Sat, 10 Apr 2021 22:22:39 +0200 Subject: [PATCH 61/79] resolved merge conflicts --- bsp_rpi/InitMission.cpp | 58 +------------------------------- fsfw_hal | 2 +- linux/boardtest/SpiTestClass.cpp | 8 ++--- linux/boardtest/SpiTestClass.h | 2 +- 4 files changed, 6 insertions(+), 64 deletions(-) diff --git a/bsp_rpi/InitMission.cpp b/bsp_rpi/InitMission.cpp index 091f6bbd..40c38e6c 100644 --- a/bsp_rpi/InitMission.cpp +++ b/bsp_rpi/InitMission.cpp @@ -3,13 +3,9 @@ #include #include -<<<<<<< HEAD -#include +#include -======= ->>>>>>> develop #include - #include #include #include @@ -17,10 +13,6 @@ #include #include #include -<<<<<<< HEAD -======= -#include ->>>>>>> develop #include @@ -124,8 +116,6 @@ void initmission::initTasks() { result = pusMedPrio->addComponent(objects::PUS_SERVICE_20_PARAMETERS); if(result != HasReturnvaluesIF::RETURN_OK) { initmission::printAddObjectError("PUS20", objects::PUS_SERVICE_20_PARAMETERS); -<<<<<<< HEAD -======= } PeriodicTaskIF* pusLowPrio = factory->createPeriodicTask( @@ -135,24 +125,6 @@ void initmission::initTasks() { initmission::printAddObjectError("PUS17", objects::PUS_SERVICE_17_TEST); } -#if RPI_TEST_ACS_BOARD == 1 - FixedTimeslotTaskIF* acsTask = factory->createFixedTimeslotTask( - "ACS_PST", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE * 2, 1.0, missedDeadlineFunc); - result = pst::pollingSequenceAcsTest(acsTask); - if(result != HasReturnvaluesIF::RETURN_OK) { - sif::warning << "initmission::initTasks: ACS PST initialization failed!" << std::endl; ->>>>>>> develop - } -#endif /* RPI_TEST_ACS_BOARD == 1 */ - -<<<<<<< HEAD - PeriodicTaskIF* pusLowPrio = factory->createPeriodicTask( - "PUS_LOW_PRIO", 30, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.6, missedDeadlineFunc); - result = pusLowPrio->addComponent(objects::PUS_SERVICE_17_TEST); - if(result != HasReturnvaluesIF::RETURN_OK) { - initmission::printAddObjectError("PUS17", objects::PUS_SERVICE_17_TEST); - } - #if RPI_TEST_ACS_BOARD == 1 FixedTimeslotTaskIF* acsTask = factory->createFixedTimeslotTask( "ACS_PST", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE * 2, 2.0, missedDeadlineFunc); @@ -188,34 +160,6 @@ void initmission::initTasks() { udpBridgeTask->startTask(); udpPollingTask->startTask(); -======= - PeriodicTaskIF* testTask = factory->createPeriodicTask( - "TEST_TASK", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, missedDeadlineFunc); -#if OBSW_ADD_TEST_CODE == 1 - result = testTask->addComponent(objects::TEST_TASK); - if(result != HasReturnvaluesIF::RETURN_OK) { - initmission::printAddObjectError("TEST_TASK", objects::TEST_TASK); - } -#endif /* OBSW_ADD_TEST_CODE == 1 */ -#if RPI_ADD_SPI_TEST == 1 - result = testTask->addComponent(objects::SPI_TEST); - if(result != HasReturnvaluesIF::RETURN_OK) { - initmission::printAddObjectError("SPI_TEST", objects::SPI_TEST); - } -#endif /* RPI_ADD_SPI_TEST == 1 */ -#if RPI_ADD_GPIO_TEST == 1 - result = testTask->addComponent(objects::LIBGPIOD_TEST); - if(result != HasReturnvaluesIF::RETURN_OK) { - initmission::printAddObjectError("GPIOD_TEST", objects::LIBGPIOD_TEST); - } -#endif /* RPI_ADD_GPIO_TEST == 1 */ - - sif::info << "Starting tasks.." << std::endl; - tmTcDistributor->startTask(); - udpBridgeTask->startTask(); - udpPollingTask->startTask(); - ->>>>>>> develop pusVerification->startTask(); pusEvents->startTask(); pusHighPrio->startTask(); diff --git a/fsfw_hal b/fsfw_hal index a12f0363..14fe3257 160000 --- a/fsfw_hal +++ b/fsfw_hal @@ -1 +1 @@ -Subproject commit a12f036339ab2f6716fae4ba95e3205f0b827271 +Subproject commit 14fe32572d62db9d19707dc1f9bb6fecb1993b73 diff --git a/linux/boardtest/SpiTestClass.cpp b/linux/boardtest/SpiTestClass.cpp index dc7ca931..387c7eb5 100644 --- a/linux/boardtest/SpiTestClass.cpp +++ b/linux/boardtest/SpiTestClass.cpp @@ -329,7 +329,6 @@ void SpiTestClass::acsInit() { gpio = new GpiodRegular(rpiGpioName, mgm3Rm3100ChipSelect, "MGM_3_RM3100", gpio::Direction::OUT, 1); gpioCookie->addGpio(gpioIds::MGM_3_RM3100_CS, gpio); -} #elif defined(XIPHOS_Q7S) std::string q7sGpioName5 = "gpiochip5"; std::string q7sGpioName6 = "gpiochip6"; @@ -362,10 +361,9 @@ void SpiTestClass::acsInit() { gpio::Direction::OUT, gpio::HIGH); gpioCookie->addGpio(gpioIds::MGM_3_RM3100_CS, gpio); #endif -if(gpioIF != nullptr) { - gpioIF->addGpios(gpioCookie); -} - + if(gpioIF != nullptr) { + gpioIF->addGpios(gpioCookie); + } } void SpiTestClass::setSpiSpeedAndMode(int spiFd, spi::SpiModes mode, uint32_t speed) { diff --git a/linux/boardtest/SpiTestClass.h b/linux/boardtest/SpiTestClass.h index 9c6305f6..f93eb9c2 100644 --- a/linux/boardtest/SpiTestClass.h +++ b/linux/boardtest/SpiTestClass.h @@ -39,7 +39,7 @@ private: /* ACS board specific variables */ #ifdef RASPBERRY_PI - uint8_t mgm0Lis3ChipSelect = 0; + uint8_t mgm0Lis3mdlChipSelect = 0; uint8_t mgm1Rm3100ChipSelect = 1; uint8_t gyro0AdisChipSelect = 5; uint8_t gyro1L3gd20ChipSelect = 6; From 3de0c7207327387f1027d58e03b7fc75641bbd18 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Sun, 11 Apr 2021 12:25:23 +0200 Subject: [PATCH 62/79] common versioning file --- common/config/OBSWVersion.h | 10 ++++++++++ fsfwconfig/OBSWVersion.h | 13 ------------- tmtc | 2 +- 3 files changed, 11 insertions(+), 14 deletions(-) create mode 100644 common/config/OBSWVersion.h delete mode 100644 fsfwconfig/OBSWVersion.h diff --git a/common/config/OBSWVersion.h b/common/config/OBSWVersion.h new file mode 100644 index 00000000..548363f2 --- /dev/null +++ b/common/config/OBSWVersion.h @@ -0,0 +1,10 @@ +#ifndef COMMON_CONFIG_OBSWVERSION_H_ +#define COMMON_CONFIG_OBSWVERSION_H_ + +const char* const SW_NAME = "eive"; + +#define SW_VERSION 1 +#define SW_SUBVERSION 1 +#define SW_SUBSUBVERSION 0 + +#endif /* COMMON_CONFIG_OBSWVERSION_H_ */ diff --git a/fsfwconfig/OBSWVersion.h b/fsfwconfig/OBSWVersion.h deleted file mode 100644 index fd76332e..00000000 --- a/fsfwconfig/OBSWVersion.h +++ /dev/null @@ -1,13 +0,0 @@ -#ifndef FSFWCONFIG_OBSWVERSION_H_ -#define FSFWCONFIG_OBSWVERSION_H_ - -//! TODO: Think of a cool name for the software releases. -const char* const SW_NAME = "eive"; - -#define SW_VERSION 1 -#define SW_SUBVERSION 0 -#define SW_SUBSUBVERSION 0 - - - -#endif /* FSFWCONFIG_OBSWVERSION_H_ */ diff --git a/tmtc b/tmtc index 74c61842..2e84c822 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 74c61842c87e6a25751904116fdc82dd61a14333 +Subproject commit 2e84c822c8ce5c589793b7ec784c9860f527a2f4 From 697a6016811ecca9cd1a8d22714a242f5a68f8c1 Mon Sep 17 00:00:00 2001 From: "Jakob.Meier" Date: Sun, 11 Apr 2021 15:18:55 +0200 Subject: [PATCH 63/79] spi chipselects changes --- bsp_q7s/ObjectFactory.cpp | 4 ++-- fsfw | 2 +- tmtc | 2 +- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/bsp_q7s/ObjectFactory.cpp b/bsp_q7s/ObjectFactory.cpp index fed5734c..6df0cf30 100644 --- a/bsp_q7s/ObjectFactory.cpp +++ b/bsp_q7s/ObjectFactory.cpp @@ -150,7 +150,7 @@ void ObjectFactory::produce(){ #if OBSW_ADD_ACS_BOARD == 1 GpioCookie* gpioCookieAcsBoard = new GpioCookie(); GpiodRegular* gpio = nullptr; - gpio = new GpiodRegular(std::string("gpiochip5"), 21, std::string("CS_GYRO_1_ADIS"), + gpio = new GpiodRegular(std::string("gpiochip5"), 19, std::string("CS_GYRO_1_ADIS"), gpio::OUT, gpio::HIGH); gpioCookieAcsBoard->addGpio(gpioIds::GYRO_0_ADIS_CS, gpio); gpio = new GpiodRegular(std::string("gpiochip5"), 7, std::string("CS_GYRO_2_L3G"), @@ -172,7 +172,7 @@ void ObjectFactory::produce(){ gpio::OUT, gpio::HIGH); gpioCookieAcsBoard->addGpio(gpioIds::MGM_2_LIS3_CS, gpio); - gpio = new GpiodRegular(std::string("gpiochip5"), 23, std::string("CS_MGM_3_RM3100_B"), + gpio = new GpiodRegular(std::string("gpiochip5"), 10, std::string("CS_MGM_3_RM3100_B"), gpio::OUT, gpio::HIGH); gpioCookieAcsBoard->addGpio(gpioIds::MGM_3_RM3100_CS, gpio); diff --git a/fsfw b/fsfw index dea22059..42720e6f 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit dea2205908f29cbb700ad85c2614da71b6efccfc +Subproject commit 42720e6f7d64bdd9a1ac0cea5846c9a8cedea0ff diff --git a/tmtc b/tmtc index 74c61842..73105138 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 74c61842c87e6a25751904116fdc82dd61a14333 +Subproject commit 73105138050b5661a6cff76e1d64af40981f9c7f From 7d1d41bfaaed3f1ea765b6d6fe163200238314d1 Mon Sep 17 00:00:00 2001 From: "Jakob.Meier" Date: Mon, 12 Apr 2021 10:22:13 +0200 Subject: [PATCH 64/79] cs gyro 1 change --- bsp_q7s/ObjectFactory.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/bsp_q7s/ObjectFactory.cpp b/bsp_q7s/ObjectFactory.cpp index 6df0cf30..85e94fa6 100644 --- a/bsp_q7s/ObjectFactory.cpp +++ b/bsp_q7s/ObjectFactory.cpp @@ -150,7 +150,7 @@ void ObjectFactory::produce(){ #if OBSW_ADD_ACS_BOARD == 1 GpioCookie* gpioCookieAcsBoard = new GpioCookie(); GpiodRegular* gpio = nullptr; - gpio = new GpiodRegular(std::string("gpiochip5"), 19, std::string("CS_GYRO_1_ADIS"), + gpio = new GpiodRegular(std::string("gpiochip5"), 1, std::string("CS_GYRO_1_ADIS"), gpio::OUT, gpio::HIGH); gpioCookieAcsBoard->addGpio(gpioIds::GYRO_0_ADIS_CS, gpio); gpio = new GpiodRegular(std::string("gpiochip5"), 7, std::string("CS_GYRO_2_L3G"), From 1fc9fc27515186436713b7805ae0d8c69505452e Mon Sep 17 00:00:00 2001 From: Martin Zietz Date: Sat, 24 Apr 2021 13:01:49 +0200 Subject: [PATCH 65/79] mgt debugging --- bsp_q7s/ObjectFactory.cpp | 1 - fsfw_hal | 1 + tmtc | 2 +- 3 files changed, 2 insertions(+), 2 deletions(-) create mode 160000 fsfw_hal diff --git a/bsp_q7s/ObjectFactory.cpp b/bsp_q7s/ObjectFactory.cpp index 4d063238..4be4fce5 100644 --- a/bsp_q7s/ObjectFactory.cpp +++ b/bsp_q7s/ObjectFactory.cpp @@ -22,7 +22,6 @@ #include #include -#include #include #include #include diff --git a/fsfw_hal b/fsfw_hal new file mode 160000 index 00000000..7a3190e5 --- /dev/null +++ b/fsfw_hal @@ -0,0 +1 @@ +Subproject commit 7a3190e5b6980ad2addc5e8a76d21994b542f0e0 diff --git a/tmtc b/tmtc index f40b70f6..3e466f06 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit f40b70f66eba176d3c36533a779e4e0ed13ae701 +Subproject commit 3e466f06ef7737f2f1bab8c3d68feb633da76dbc From 2c40bf86fbfc67d1634c1db5dbd6b78bc1b5c117 Mon Sep 17 00:00:00 2001 From: Martin Zietz Date: Sat, 24 Apr 2021 14:55:15 +0200 Subject: [PATCH 66/79] typo fix --- fsfw | 2 +- mission/devices/IMTQHandler.cpp | 2 +- tmtc | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/fsfw b/fsfw index 83d0db82..18a9729c 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit 83d0db824289b28dbad81cce0c80276c4fc839c8 +Subproject commit 18a9729c75875f8bee674f03dd93a5eeeb657a66 diff --git a/mission/devices/IMTQHandler.cpp b/mission/devices/IMTQHandler.cpp index 88fd00ba..0c1b1d1e 100644 --- a/mission/devices/IMTQHandler.cpp +++ b/mission/devices/IMTQHandler.cpp @@ -165,7 +165,7 @@ void IMTQHandler::fillEngHkDataset(const uint8_t* packet) { offset += 2; engHkDataset.mcuTemperature = (*(packet + offset + 1) | *(packet + offset)); -#if OBSW_VERBOSE_LEVEL >= 1 && IMTQ_DEBUG == 1 +#if OBSW_VERBOSE_LEVEL >= 1 && IMQT_DEBUG == 1 sif::info << "IMTQ digital voltage: " << engHkDataset.digitalVoltageMv << " mV" << std::endl; sif::info << "IMTQ analog voltage: " << engHkDataset.analogVoltageMv << " mV" << std::endl; sif::info << "IMTQ digital current: " << engHkDataset.digitalCurrentA << " A" << std::endl; diff --git a/tmtc b/tmtc index 3e466f06..79e897b0 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 3e466f06ef7737f2f1bab8c3d68feb633da76dbc +Subproject commit 79e897b0353acacf0f986f22f57e9cd8cf30a0da From 1ad89a0d16a0bb3a8bc45f6004813f0f5e0a7dcd Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Sat, 24 Apr 2021 22:51:04 +0200 Subject: [PATCH 67/79] updated fsfw and tmtc submodule --- fsfw | 2 +- tmtc | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/fsfw b/fsfw index 42720e6f..cac9a0ee 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit 42720e6f7d64bdd9a1ac0cea5846c9a8cedea0ff +Subproject commit cac9a0eecdc3ab77825a1d36e17e7ed1871f55ca diff --git a/tmtc b/tmtc index 73105138..3c343f75 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 73105138050b5661a6cff76e1d64af40981f9c7f +Subproject commit 3c343f751f4a098468150240856378ec274cc025 From 634ed99a54fc9c8d491804e661529abab58c3c64 Mon Sep 17 00:00:00 2001 From: "Jakob.Meier" Date: Sat, 24 Apr 2021 22:55:26 +0200 Subject: [PATCH 68/79] issue with poolManager.subscribe in max handler --- bsp_q7s/ObjectFactory.cpp | 11 +++++------ fsfw | 2 +- fsfw_hal | 2 +- fsfwconfig/FSFWConfig.h | 2 ++ 4 files changed, 9 insertions(+), 8 deletions(-) diff --git a/bsp_q7s/ObjectFactory.cpp b/bsp_q7s/ObjectFactory.cpp index 4be4fce5..fc9a199f 100644 --- a/bsp_q7s/ObjectFactory.cpp +++ b/bsp_q7s/ObjectFactory.cpp @@ -42,14 +42,14 @@ #include #include #include -#include +#include +#include #include #include #include #include #include -#include #if TEST_LIBGPIOD == 1 #include @@ -328,10 +328,9 @@ void ObjectFactory::produce(){ #endif - new TmTcUnixUdpBridge(objects::UDP_BRIDGE, - objects::CCSDS_PACKET_DISTRIBUTOR, - objects::TM_STORE, objects::TC_STORE); - new TcUnixUdpPollingTask(objects::UDP_POLLING_TASK, objects::UDP_BRIDGE); + new UdpTmTcBridge(objects::UDP_BRIDGE, objects::CCSDS_PACKET_DISTRIBUTOR, objects::TM_STORE, + objects::TC_STORE); + new UdpTcPollingTask(objects::UDP_POLLING_TASK, objects::UDP_BRIDGE); #if TE0720 == 1 && TEST_LIBGPIOD == 1 /* Configure MIO0 as input */ diff --git a/fsfw b/fsfw index 18a9729c..52b549b9 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit 18a9729c75875f8bee674f03dd93a5eeeb657a66 +Subproject commit 52b549b97c36350a0c43b9fb3563802e670440da diff --git a/fsfw_hal b/fsfw_hal index 7a3190e5..14fe3257 160000 --- a/fsfw_hal +++ b/fsfw_hal @@ -1 +1 @@ -Subproject commit 7a3190e5b6980ad2addc5e8a76d21994b542f0e0 +Subproject commit 14fe32572d62db9d19707dc1f9bb6fecb1993b73 diff --git a/fsfwconfig/FSFWConfig.h b/fsfwconfig/FSFWConfig.h index e3def8fe..1d82a733 100644 --- a/fsfwconfig/FSFWConfig.h +++ b/fsfwconfig/FSFWConfig.h @@ -43,6 +43,8 @@ //! Specify whether a special mode store is used for Subsystem components. #define FSFW_USE_MODESTORE 0 +#define FSFW_USE_REALTIME_FOR_LINUX 1 + namespace fsfwconfig { //! Default timestamp size. The default timestamp will be an eight byte CDC //! short timestamp. From 3befba560cc8b6471c234aba72d09ba242ee576c Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Sat, 24 Apr 2021 23:04:17 +0200 Subject: [PATCH 69/79] adaptions for new fsfw, using pus c now --- bsp_q7s/ObjectFactory.cpp | 2 +- fsfwconfig/FSFWConfig.h | 9 ++++++++- mission/utility/TmFunnel.cpp | 4 ++-- 3 files changed, 11 insertions(+), 4 deletions(-) diff --git a/bsp_q7s/ObjectFactory.cpp b/bsp_q7s/ObjectFactory.cpp index 85e94fa6..07b54049 100644 --- a/bsp_q7s/ObjectFactory.cpp +++ b/bsp_q7s/ObjectFactory.cpp @@ -71,7 +71,7 @@ void Factory::setStaticFrameworkObjectIds() { LocalDataPoolManager::defaultHkDestination = objects::PUS_SERVICE_3_HOUSEKEEPING; VerificationReporter::messageReceiver = objects::PUS_SERVICE_1_VERIFICATION; - TmPacketStored::timeStamperId = objects::TIME_STAMPER; + TmPacketBase::timeStamperId = objects::TIME_STAMPER; } diff --git a/fsfwconfig/FSFWConfig.h b/fsfwconfig/FSFWConfig.h index e3def8fe..f5857d05 100644 --- a/fsfwconfig/FSFWConfig.h +++ b/fsfwconfig/FSFWConfig.h @@ -43,10 +43,17 @@ //! Specify whether a special mode store is used for Subsystem components. #define FSFW_USE_MODESTORE 0 +//! Defines if the real time scheduler for linux should be used. +//! If set to 0, this will also disable priority settings for linux +//! as most systems will not allow to set nice values without privileges +//! For embedded linux system set this to 1. +//! If set to 1 the binary needs "cap_sys_nice=eip" privileges to run +#define FSFW_USE_REALTIME_FOR_LINUX 1 + namespace fsfwconfig { //! Default timestamp size. The default timestamp will be an eight byte CDC //! short timestamp. -static constexpr uint8_t FSFW_MISSION_TIMESTAMP_SIZE = 8; +static constexpr uint8_t FSFW_MISSION_TIMESTAMP_SIZE = 7; //! Configure the allocated pool sizes for the event manager. static constexpr size_t FSFW_EVENTMGMR_MATCHTREE_NODES = 240; diff --git a/mission/utility/TmFunnel.cpp b/mission/utility/TmFunnel.cpp index 263aff8d..a567cbd9 100644 --- a/mission/utility/TmFunnel.cpp +++ b/mission/utility/TmFunnel.cpp @@ -1,7 +1,7 @@ #include -#include #include #include +#include #include object_id_t TmFunnel::downlinkDestination = objects::NO_OBJECT; @@ -50,7 +50,7 @@ ReturnValue_t TmFunnel::handlePacket(TmTcMessage* message) { if(result != HasReturnvaluesIF::RETURN_OK){ return result; } - TmPacketBase packet(packetData); + TmPacketPusC packet(packetData); packet.setPacketSequenceCount(this->sourceSequenceCount); sourceSequenceCount++; sourceSequenceCount = sourceSequenceCount % From 9ab9b2fdeb28ade76706072bbc8c3ac045a317d3 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Sat, 24 Apr 2021 23:17:45 +0200 Subject: [PATCH 70/79] added dns name --- README.md | 6 ++++++ bsp_q7s/boardconfig/q7s_config.h | 2 +- tmtc | 2 +- 3 files changed, 8 insertions(+), 2 deletions(-) diff --git a/README.md b/README.md index f0c749be..38df4443 100644 --- a/README.md +++ b/README.md @@ -198,6 +198,12 @@ IP address and path settings differ from machine to machine. Open SSH connection to flatsat PC: +```sh +ssh eive@flatsat.eive.absatvirt.lw +``` + +or + ```sh ssh eive@2001:7c0:2018:1099:babe:0:e1fe:f1a5 ``` diff --git a/bsp_q7s/boardconfig/q7s_config.h b/bsp_q7s/boardconfig/q7s_config.h index d4b821c1..31c22046 100644 --- a/bsp_q7s/boardconfig/q7s_config.h +++ b/bsp_q7s/boardconfig/q7s_config.h @@ -4,7 +4,7 @@ /* Only one of those 2 should be enabled! */ /* Add code for ACS board */ #define OBSW_ADD_ACS_BOARD 0 -#define Q7S_ADD_SPI_TEST 1 +#define Q7S_ADD_SPI_TEST 0 diff --git a/tmtc b/tmtc index 3c343f75..7cc06ef0 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 3c343f751f4a098468150240856378ec274cc025 +Subproject commit 7cc06ef0e0882d286bab8156ca756e0211e5ebae From fa192a353ba81bacdb0cc20135a903715ab5dbaf Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Sat, 24 Apr 2021 23:41:27 +0200 Subject: [PATCH 71/79] everything seems to work now --- bsp_q7s/ObjectFactory.cpp | 17 +++++++++++++++++ fsfwconfig/FSFWConfig.h | 3 +-- 2 files changed, 18 insertions(+), 2 deletions(-) diff --git a/bsp_q7s/ObjectFactory.cpp b/bsp_q7s/ObjectFactory.cpp index 07b54049..caa98bfd 100644 --- a/bsp_q7s/ObjectFactory.cpp +++ b/bsp_q7s/ObjectFactory.cpp @@ -386,6 +386,23 @@ void ObjectFactory::produce(){ Max31865PT1000Handler* rtdIc18 = new Max31865PT1000Handler(objects::RTD_IC18, objects::SPI_COM_IF, spiRtdIc18, 0); // rtdIc10->setStartUpImmediately(); // rtdIc4->setStartUpImmediately(); + (void) rtdIc3; + (void) rtdIc4; + (void) rtdIc5; + (void) rtdIc6; + (void) rtdIc7; + (void) rtdIc8; + (void) rtdIc9; + (void) rtdIc10; + (void) rtdIc11; + (void) rtdIc12; + (void) rtdIc13; + (void) rtdIc14; + (void) rtdIc15; + (void) rtdIc16; + (void) rtdIc17; + (void) rtdIc18; + #endif /* Q7S_ADD_SPI_TEST == 0 */ #endif /* TE0720 == 0 */ diff --git a/fsfwconfig/FSFWConfig.h b/fsfwconfig/FSFWConfig.h index f5857d05..097f8aaf 100644 --- a/fsfwconfig/FSFWConfig.h +++ b/fsfwconfig/FSFWConfig.h @@ -17,8 +17,7 @@ #define FSFW_DISABLE_PRINTOUT 0 #endif -//! Can be used to disable the ANSI color sequences for C stdio. -#define FSFW_COLORED_OUTPUT 1 +#define FSFW_USE_PUS_C_TELEMETRY 1 //! Can be used to disable the ANSI color sequences for C stdio. #define FSFW_COLORED_OUTPUT 1 From e752e364800e34bdb8d8354ec61796b78629e5da Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Sun, 25 Apr 2021 00:00:17 +0200 Subject: [PATCH 72/79] fsfw update --- fsfw | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/fsfw b/fsfw index cac9a0ee..f2ab07c7 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit cac9a0eecdc3ab77825a1d36e17e7ed1871f55ca +Subproject commit f2ab07c78242d8211aebf9e0d6911d386dbc4ec5 From edfebc8e06b942248cf5c14e772e1a47b93de91a Mon Sep 17 00:00:00 2001 From: "Jakob.Meier" Date: Sun, 25 Apr 2021 09:24:41 +0200 Subject: [PATCH 73/79] deleted faulty header includes --- bsp_q7s/ObjectFactory.cpp | 3 --- fsfw | 2 +- 2 files changed, 1 insertion(+), 4 deletions(-) diff --git a/bsp_q7s/ObjectFactory.cpp b/bsp_q7s/ObjectFactory.cpp index fc9a199f..4b4c12d9 100644 --- a/bsp_q7s/ObjectFactory.cpp +++ b/bsp_q7s/ObjectFactory.cpp @@ -40,15 +40,12 @@ #include #include #include -#include #include -#include #include #include #include #include -#include #include #if TEST_LIBGPIOD == 1 diff --git a/fsfw b/fsfw index 52b549b9..ff33a127 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit 52b549b97c36350a0c43b9fb3563802e670440da +Subproject commit ff33a1274daf1af83832501036f2adbb807ba690 From dec95f321701bac86363960ca561b7cd15f4551b Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Sun, 25 Apr 2021 11:10:05 +0200 Subject: [PATCH 74/79] added modgen submodule --- .gitmodules | 3 +++ fsfw | 2 +- generators/modgen | 1 + 3 files changed, 5 insertions(+), 1 deletion(-) create mode 160000 generators/modgen diff --git a/.gitmodules b/.gitmodules index 4a973500..6f538287 100644 --- a/.gitmodules +++ b/.gitmodules @@ -16,3 +16,6 @@ [submodule "fsfw_hal"] path = fsfw_hal url = https://egit.irs.uni-stuttgart.de/fsfw/fsfw_hal.git +[submodule "generators/modgen"] + path = generators/modgen + url = https://git.ksat-stuttgart.de/source/modgen.git diff --git a/fsfw b/fsfw index f2ab07c7..5273ffa7 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit f2ab07c78242d8211aebf9e0d6911d386dbc4ec5 +Subproject commit 5273ffa721dd83634ebbcc37c4646752f0bea20f diff --git a/generators/modgen b/generators/modgen new file mode 160000 index 00000000..5ed4a2ae --- /dev/null +++ b/generators/modgen @@ -0,0 +1 @@ +Subproject commit 5ed4a2ae59e90c3763616bdaf41eb3317e849100 From 2e4a8e1f948b8fcd34b61446be78828fae3590a9 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Sun, 25 Apr 2021 11:32:21 +0200 Subject: [PATCH 75/79] tmtc and obj factory update --- bsp_q7s/ObjectFactory.cpp | 2 +- tmtc | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/bsp_q7s/ObjectFactory.cpp b/bsp_q7s/ObjectFactory.cpp index e905393a..fc86c1ea 100644 --- a/bsp_q7s/ObjectFactory.cpp +++ b/bsp_q7s/ObjectFactory.cpp @@ -404,7 +404,7 @@ void ObjectFactory::produce(){ (void) rtdIc17; (void) rtdIc18; -#endif /* Q7S_ADD_RTS_DEVICES == 1 */ +#endif /* Q7S_ADD_RTD_DEVICES == 1 */ I2cCookie* imtqI2cCookie = new I2cCookie(addresses::IMTQ, IMTQ::MAX_REPLY_SIZE, std::string("/dev/i2c-0")); diff --git a/tmtc b/tmtc index 7cc06ef0..3b5d92f9 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 7cc06ef0e0882d286bab8156ca756e0211e5ebae +Subproject commit 3b5d92f9083392d8dd040470ae56fa610d0de8ad From 2f766f012d7a258b2c3a441b532c133262a69acc Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Sun, 25 Apr 2021 11:32:49 +0200 Subject: [PATCH 76/79] tmtc update --- tmtc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tmtc b/tmtc index 3b5d92f9..7cc06ef0 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 3b5d92f9083392d8dd040470ae56fa610d0de8ad +Subproject commit 7cc06ef0e0882d286bab8156ca756e0211e5ebae From a49638724a702892f9253b74901ebc761999f995 Mon Sep 17 00:00:00 2001 From: "Jakob.Meier" Date: Sun, 25 Apr 2021 12:23:34 +0200 Subject: [PATCH 77/79] tmtc update --- tmtc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tmtc b/tmtc index 2e84c822..986f88e2 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 2e84c822c8ce5c589793b7ec784c9860f527a2f4 +Subproject commit 986f88e2908c6bc555a279b53f11e82d9a8a851c From daea8373b507d192065f6d63673560b70ff2fd60 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Sun, 25 Apr 2021 12:35:24 +0200 Subject: [PATCH 78/79] OBSW VERsion --- common/config/OBSWVersion.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/common/config/OBSWVersion.h b/common/config/OBSWVersion.h index 548363f2..7ac812e6 100644 --- a/common/config/OBSWVersion.h +++ b/common/config/OBSWVersion.h @@ -4,7 +4,7 @@ const char* const SW_NAME = "eive"; #define SW_VERSION 1 -#define SW_SUBVERSION 1 +#define SW_SUBVERSION 2 #define SW_SUBSUBVERSION 0 #endif /* COMMON_CONFIG_OBSWVERSION_H_ */ From c1ae98f1c886f5b31c3b377d99c948ccb0b772a1 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Sun, 25 Apr 2021 12:37:59 +0200 Subject: [PATCH 79/79] obsw version update --- common/config/OBSWVersion.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/common/config/OBSWVersion.h b/common/config/OBSWVersion.h index 7ac812e6..548363f2 100644 --- a/common/config/OBSWVersion.h +++ b/common/config/OBSWVersion.h @@ -4,7 +4,7 @@ const char* const SW_NAME = "eive"; #define SW_VERSION 1 -#define SW_SUBVERSION 2 +#define SW_SUBVERSION 1 #define SW_SUBSUBVERSION 0 #endif /* COMMON_CONFIG_OBSWVERSION_H_ */