solved merge conflicts

This commit is contained in:
Jakob Meier 2021-05-12 17:01:11 +02:00
commit 44bde15a46
14 changed files with 628 additions and 282 deletions

View File

@ -158,10 +158,10 @@ void initmission::initTasks() {
}
#else
FixedTimeslotTaskIF * pollingSequenceTableTE0720 = factory->createFixedTimeslotTask(
"PST_TASK_TE0720", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE * 4, 3.0,
FixedTimeslotTaskIF * pollingSequenceTaskTE0720 = factory->createFixedTimeslotTask(
"PST_TASK_TE0720", 30, PeriodicTaskIF::MINIMUM_STACK_SIZE * 8, 3.0,
missedDeadlineFunc);
result = pst::pollingSequenceTE0720(pollingSequenceTableTE0720);
result = pst::pollingSequenceTE0720(pollingSequenceTaskTE0720);
if (result != HasReturnvaluesIF::RETURN_OK) {
sif::error << "InitMission::initTasks: Creating TE0720 PST failed!" << std::endl;
}
@ -198,7 +198,7 @@ void initmission::initTasks() {
gomSpacePstTask->startTask();
pollingSequenceTableTaskDefault->startTask();
#elif TE0720 == 1 && Q7S_ADD_SPI_TEST == 0
pollingSequenceTableTE0720->startTask();
pollingSequenceTaskTE0720->startTask();
#endif
pusVerification->startTask();

View File

@ -26,12 +26,14 @@
#include <mission/devices/GyroL3GD20Handler.h>
#include <mission/devices/PlocHandler.h>
#include <mission/devices/RadiationSensorHandler.h>
#include <mission/devices/SusHandler.h>
#include <mission/devices/devicedefinitions/GomspaceDefinitions.h>
#include <mission/devices/devicedefinitions/SyrlinksDefinitions.h>
#include <mission/devices/devicedefinitions/PlocDefinitions.h>
#include <mission/devices/devicedefinitions/RadSensorDefinitions.h>
#include <mission/devices/devicedefinitions/Max31865Definitions.h>
#include <mission/devices/devicedefinitions/SusDefinitions.h>
#include <mission/utility/TmFunnel.h>
#include <linux/csp/CspCookie.h>
@ -103,19 +105,17 @@ void ObjectFactory::produce(){
new UartComIF(objects::UART_COM_IF);
#if Q7S_ADD_SPI_TEST == 0
new SpiComIF(objects::SPI_COM_IF, gpioComIF);
#endif
#endif /* Q7S_ADD_SPI_TEST == 0 */
/* Temperature sensors */
Tmp1075Handler* tmp1075Handler_1 = new Tmp1075Handler(
objects::TMP1075_HANDLER_1, objects::I2C_COM_IF,
i2cCookieTmp1075tcs1);
// tmp1075Handler_1->setStartUpImmediately();
(void) tmp1075Handler_1;
Tmp1075Handler* tmp1075Handler_2 = new Tmp1075Handler(
objects::TMP1075_HANDLER_2, objects::I2C_COM_IF,
i2cCookieTmp1075tcs2);
// tmp1075Handler_2->setStartUpImmediately();
GpioCookie* heaterGpiosCookie = new GpioCookie;
(void) tmp1075Handler_2;
#if TE0720 == 0
CspCookie* p60DockCspCookie = new CspCookie(P60Dock::MAX_REPLY_LENGTH,
@ -151,6 +151,150 @@ void ObjectFactory::produce(){
(void) pdu2handler;
(void) acuhandler;
/* Adding gpios for chip select decoding to the gpioComIf */
gpioCallbacks::initSpiCsDecoder(gpioComIF);
GpioCookie* gpioCookieRadSensor = new GpioCookie;
GpiodRegular* chipSelectRadSensor = new GpiodRegular(std::string("gpiochip5"), 19,
std::string("Chip Select Radiation Sensor"), gpio::OUT, 1);
gpioCookieRadSensor->addGpio(gpioIds::CS_RAD_SENSOR, chipSelectRadSensor);
gpioComIF->addGpios(gpioCookieRadSensor);
SpiCookie* spiCookieRadSensor = new SpiCookie(addresses::RAD_SENSOR, gpioIds::CS_RAD_SENSOR,
std::string("/dev/spidev2.0"), RAD_SENSOR::READ_SIZE, spi::DEFAULT_MAX_1227_MODE,
spi::DEFAULT_MAX_1227_SPEED);
RadiationSensorHandler* radSensor = new RadiationSensorHandler(objects::RAD_SENSOR,
objects::SPI_COM_IF, spiCookieRadSensor);
(void) radSensor;
GpioCookie* gpioCookieSus = new GpioCookie();
GpioCallback* susgpio = new GpioCallback(std::string("Chip select SUS 1"), gpio::OUT, 1,
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
gpioCookieSus->addGpio(gpioIds::CS_SUS_1, susgpio);
susgpio = new GpioCallback(std::string("Chip select SUS 2"), gpio::OUT, 1,
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
gpioCookieSus->addGpio(gpioIds::CS_SUS_2, susgpio);
susgpio = new GpioCallback(std::string("Chip select SUS 3"), gpio::OUT, 1,
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
gpioCookieSus->addGpio(gpioIds::CS_SUS_3, susgpio);
susgpio = new GpioCallback(std::string("Chip select SUS 4"), gpio::OUT, 1,
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
gpioCookieSus->addGpio(gpioIds::CS_SUS_4, susgpio);
susgpio = new GpioCallback(std::string("Chip select SUS 5"), gpio::OUT, 1,
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
gpioCookieSus->addGpio(gpioIds::CS_SUS_5, susgpio);
susgpio = new GpioCallback(std::string("Chip select SUS 6"), gpio::OUT, 1,
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
gpioCookieSus->addGpio(gpioIds::CS_SUS_6, susgpio);
susgpio = new GpioCallback(std::string("Chip select SUS 7"), gpio::OUT, 1,
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
gpioCookieSus->addGpio(gpioIds::CS_SUS_7, susgpio);
susgpio = new GpioCallback(std::string("Chip select SUS 8"), gpio::OUT, 1,
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
gpioCookieSus->addGpio(gpioIds::CS_SUS_8, susgpio);
susgpio = new GpioCallback(std::string("Chip select SUS 9"), gpio::OUT, 1,
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
gpioCookieSus->addGpio(gpioIds::CS_SUS_9, susgpio);
susgpio = new GpioCallback(std::string("Chip select SUS 10"), gpio::OUT, 1,
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
gpioCookieSus->addGpio(gpioIds::CS_SUS_10, susgpio);
susgpio = new GpioCallback(std::string("Chip select SUS 11"), gpio::OUT, 1,
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
gpioCookieSus->addGpio(gpioIds::CS_SUS_11, susgpio);
susgpio = new GpioCallback(std::string("Chip select SUS 12"), gpio::OUT, 1,
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
gpioCookieSus->addGpio(gpioIds::CS_SUS_12, susgpio);
susgpio = new GpioCallback(std::string("Chip select SUS 13"), gpio::OUT, 1,
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
gpioCookieSus->addGpio(gpioIds::CS_SUS_13, susgpio);
gpioComIF->addGpios(gpioCookieSus);
SpiCookie* spiCookieSus1 = new SpiCookie(addresses::SUS_1, gpio::NO_GPIO,
std::string("/dev/spidev2.0"), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE,
SUS::MAX1227_SPI_FREQ);
SpiCookie* spiCookieSus2 = new SpiCookie(addresses::SUS_2, gpio::NO_GPIO,
std::string("/dev/spidev2.0"), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE,
SUS::MAX1227_SPI_FREQ);
SpiCookie* spiCookieSus3 = new SpiCookie(addresses::SUS_3, gpio::NO_GPIO,
std::string("/dev/spidev2.0"), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE,
SUS::MAX1227_SPI_FREQ);
SpiCookie* spiCookieSus4 = new SpiCookie(addresses::SUS_4, gpio::NO_GPIO,
std::string("/dev/spidev2.0"), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE,
SUS::MAX1227_SPI_FREQ);
SpiCookie* spiCookieSus5 = new SpiCookie(addresses::SUS_5, gpio::NO_GPIO,
std::string("/dev/spidev2.0"), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE,
SUS::MAX1227_SPI_FREQ);
SpiCookie* spiCookieSus6 = new SpiCookie(addresses::SUS_6, gpio::NO_GPIO,
std::string("/dev/spidev2.0"), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE,
SUS::MAX1227_SPI_FREQ);
SpiCookie* spiCookieSus7 = new SpiCookie(addresses::SUS_7, gpio::NO_GPIO,
std::string("/dev/spidev2.0"), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE,
SUS::MAX1227_SPI_FREQ);
SpiCookie* spiCookieSus8 = new SpiCookie(addresses::SUS_8, gpio::NO_GPIO,
std::string("/dev/spidev2.0"), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE,
SUS::MAX1227_SPI_FREQ);
SpiCookie* spiCookieSus9 = new SpiCookie(addresses::SUS_9, gpio::NO_GPIO,
std::string("/dev/spidev2.0"), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE,
SUS::MAX1227_SPI_FREQ);
SpiCookie* spiCookieSus10 = new SpiCookie(addresses::SUS_10, gpio::NO_GPIO,
std::string("/dev/spidev2.0"), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE,
SUS::MAX1227_SPI_FREQ);
SpiCookie* spiCookieSus11 = new SpiCookie(addresses::SUS_11, gpio::NO_GPIO,
std::string("/dev/spidev2.0"), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE,
SUS::MAX1227_SPI_FREQ);
SpiCookie* spiCookieSus12 = new SpiCookie(addresses::SUS_12, gpio::NO_GPIO,
std::string("/dev/spidev2.0"), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE,
SUS::MAX1227_SPI_FREQ);
SpiCookie* spiCookieSus13 = new SpiCookie(addresses::SUS_13, gpio::NO_GPIO,
std::string("/dev/spidev2.0"), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE,
SUS::MAX1227_SPI_FREQ);
SusHandler* sus1 = new SusHandler(objects::SUS_1, objects::SPI_COM_IF, spiCookieSus1, gpioComIF,
gpioIds::CS_SUS_1);
(void) sus1;
SusHandler* sus2 = new SusHandler(objects::SUS_2, objects::SPI_COM_IF, spiCookieSus2, gpioComIF,
gpioIds::CS_SUS_2);
sus2->setStartUpImmediately();
SusHandler* sus3 = new SusHandler(objects::SUS_3, objects::SPI_COM_IF, spiCookieSus3, gpioComIF,
gpioIds::CS_SUS_3);
(void) sus3;
new SusHandler(objects::SUS_4, objects::SPI_COM_IF, spiCookieSus4, gpioComIF,
gpioIds::CS_SUS_4);
new SusHandler(objects::SUS_5, objects::SPI_COM_IF, spiCookieSus5, gpioComIF,
gpioIds::CS_SUS_5);
new SusHandler(objects::SUS_6, objects::SPI_COM_IF, spiCookieSus6, gpioComIF,
gpioIds::CS_SUS_6);
new SusHandler(objects::SUS_7, objects::SPI_COM_IF, spiCookieSus7, gpioComIF,
gpioIds::CS_SUS_7);
SusHandler* sus8 = new SusHandler(objects::SUS_8, objects::SPI_COM_IF, spiCookieSus8, gpioComIF,
gpioIds::CS_SUS_8);
(void) sus8;
SusHandler* sus9 = new SusHandler(objects::SUS_9, objects::SPI_COM_IF, spiCookieSus9, gpioComIF,
gpioIds::CS_SUS_9);
(void) sus9;
SusHandler* sus10 = new SusHandler(objects::SUS_10, objects::SPI_COM_IF, spiCookieSus10, gpioComIF,
gpioIds::CS_SUS_10);
(void) sus10;
SusHandler* sus11 = new SusHandler(objects::SUS_11, objects::SPI_COM_IF, spiCookieSus11,
gpioComIF, gpioIds::CS_SUS_11);
(void) sus11;
SusHandler* sus12 = new SusHandler(objects::SUS_12, objects::SPI_COM_IF, spiCookieSus12, gpioComIF,
gpioIds::CS_SUS_12);
(void) sus12;
SusHandler* sus13 = new SusHandler(objects::SUS_13, objects::SPI_COM_IF, spiCookieSus13, gpioComIF,
gpioIds::CS_SUS_13);
(void) sus13;
#if OBSW_ADD_ACS_BOARD == 1
GpioCookie* gpioCookieAcsBoard = new GpioCookie();
GpiodRegular* gpio = nullptr;
@ -224,6 +368,8 @@ void ObjectFactory::produce(){
gyroL3gHandler->setStartUpImmediately();
#endif
GpioCookie* heaterGpiosCookie = new GpioCookie;
/* Pin H2-11 on stack connector */
GpiodRegular* gpioConfigHeater0 = new GpiodRegular(std::string("gpiochip7"), 6,
std::string("Heater0"), gpio::OUT, 0);
@ -439,19 +585,6 @@ void ObjectFactory::produce(){
// plocHandler->setStartUpImmediately();
(void) plocHandler;
GpioCookie* gpioCookieRadSensor = new GpioCookie;
GpiodRegular* chipSelectRadSensor = new GpiodRegular(std::string("gpiochip5"), 19,
std::string("Chip Select Radiation Sensor"), gpio::OUT, 1);
gpioCookieRadSensor->addGpio(gpioIds::CS_RAD_SENSOR, chipSelectRadSensor);
gpioComIF->addGpios(gpioCookieRadSensor);
SpiCookie* spiCookieRadSensor = new SpiCookie(addresses::RAD_SENSOR, gpioIds::CS_RAD_SENSOR,
std::string("/dev/spidev2.0"), RAD_SENSOR::READ_SIZE, spi::DEFAULT_MAX_1227_MODE,
spi::DEFAULT_MAX_1227_SPEED);
RadiationSensorHandler* radSensor = new RadiationSensorHandler(objects::RAD_SENSOR,
objects::SPI_COM_IF, spiCookieRadSensor);
radSensor->setStartUpImmediately();
#endif /* TE0720 == 0 */
new UdpTmTcBridge(objects::UDP_BRIDGE, objects::CCSDS_PACKET_DISTRIBUTOR, objects::TM_STORE,
@ -465,8 +598,40 @@ void ObjectFactory::produce(){
GpioCookie* gpioCookie = new GpioCookie;
gpioCookie->addGpio(gpioIds::TEST_ID_0, gpioConfigMio0);
new LibgpiodTest(objects::LIBGPIOD_TEST, objects::GPIO_IF, gpioCookie);
#elif TE0720 == 1
#endif
#if TE0720 == 1 && TEST_SUS_HANDLER == 1
GpioCookie* gpioCookieSus = new GpioCookie;
GpiodRegular* chipSelectSus = new GpiodRegular(std::string("gpiochip1"), 9,
std::string("Chip Select Sus Sensor"), gpio::OUT, 1);
gpioCookieSus->addGpio(gpioIds::CS_SUS_1, chipSelectSus);
gpioComIF->addGpios(gpioCookieSus);
SpiCookie* spiCookieSus = new SpiCookie(addresses::SUS_1, std::string("/dev/spidev1.0"),
SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE, spi::DEFAULT_MAX_1227_SPEED);
SusHandler* sus1 = new SusHandler(objects::SUS_1, objects::SPI_COM_IF, spiCookieSus, gpioComIF,
gpioIds::CS_SUS_1);
sus1->setStartUpImmediately();
#endif
#if TE0720 == 1 && TEST_RADIATION_SENSOR_HANDLER == 1
GpioCookie* gpioCookieRadSensor = new GpioCookie;
GpiodRegular* chipSelectRadSensor = new GpiodRegular(std::string("gpiochip1"), 0,
std::string("Chip select radiation sensor"), gpio::OUT, 1);
gpioCookieRadSensor->addGpio(gpioIds::CS_RAD_SENSOR, chipSelectRadSensor);
gpioComIF->addGpios(gpioCookieRadSensor);
SpiCookie* spiCookieRadSensor = new SpiCookie(addresses::RAD_SENSOR, gpioIds::CS_RAD_SENSOR,
std::string("/dev/spidev1.0"), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE,
spi::DEFAULT_MAX_1227_SPEED);
RadiationSensorHandler* radSensor = new RadiationSensorHandler(objects::RAD_SENSOR,
objects::SPI_COM_IF, spiCookieRadSensor);
radSensor->setStartUpImmediately();
#endif
#if TE0720 == 1 && TEST_PLOC_HANDLER == 1
UartCookie* plocUartCookie = new UartCookie(std::string("/dev/ttyPS1"), 115200,
PLOC::MAX_REPLY_SIZE);
/* Testing PlocHandler on TE0720-03-1CFA */

View File

@ -58,19 +58,18 @@ void spiCsDecoderCallback(gpioId_t gpioId, gpio::GpioOperation gpioOp, int value
void* args) {
if (gpioComInterface == nullptr) {
sif::debug << "tcsBoardDecoderCallback: No gpioComIF specified. Call initTcsBoardDecoder "
sif::debug << "spiCsDecoderCallback: No gpioComIF specified. Call initSpiCsDecoder "
<< "to specify gpioComIF" << std::endl;
return;
}
/* Read is not supported by the callback function */
/* Reading 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);
disableAllDecoder();
}
else if (value == 0) {
switch (gpioId) {
@ -155,70 +154,70 @@ void spiCsDecoderCallback(gpioId_t gpioId, gpio::GpioOperation gpioOp, int value
break;
}
case(gpioIds::CS_SUS_1): {
enableDecoderInterfaceBoardIc21();
enableDecoderInterfaceBoardIc1();
selectY0();
break;
}
case(gpioIds::CS_SUS_2): {
enableDecoderInterfaceBoardIc21();
enableDecoderInterfaceBoardIc1();
selectY1();
break;
}
case(gpioIds::CS_SUS_3): {
enableDecoderInterfaceBoardIc21();
selectY2();
break;
}
case(gpioIds::CS_SUS_4): {
enableDecoderInterfaceBoardIc21();
selectY3();
break;
}
case(gpioIds::CS_SUS_5): {
enableDecoderInterfaceBoardIc21();
selectY4();
break;
}
case(gpioIds::CS_SUS_6): {
enableDecoderInterfaceBoardIc21();
selectY5();
break;
}
case(gpioIds::CS_SUS_7): {
enableDecoderInterfaceBoardIc21();
selectY6();
break;
}
case(gpioIds::CS_SUS_8): {
enableDecoderInterfaceBoardIc22();
enableDecoderInterfaceBoardIc2();
selectY0();
break;
}
case(gpioIds::CS_SUS_9): {
enableDecoderInterfaceBoardIc22();
case(gpioIds::CS_SUS_4): {
enableDecoderInterfaceBoardIc2();
selectY1();
break;
}
case(gpioIds::CS_SUS_10): {
enableDecoderInterfaceBoardIc22();
case(gpioIds::CS_SUS_5): {
enableDecoderInterfaceBoardIc2();
selectY2();
break;
}
case(gpioIds::CS_SUS_11): {
enableDecoderInterfaceBoardIc22();
case(gpioIds::CS_SUS_6): {
enableDecoderInterfaceBoardIc1();
selectY2();
break;
}
case(gpioIds::CS_SUS_7): {
enableDecoderInterfaceBoardIc1();
selectY3();
break;
}
case(gpioIds::CS_SUS_12): {
enableDecoderInterfaceBoardIc22();
case(gpioIds::CS_SUS_8): {
enableDecoderInterfaceBoardIc2();
selectY3();
break;
}
case(gpioIds::CS_SUS_9): {
enableDecoderInterfaceBoardIc1();
selectY4();
break;
}
case(gpioIds::CS_SUS_13): {
enableDecoderInterfaceBoardIc22();
case(gpioIds::CS_SUS_10): {
enableDecoderInterfaceBoardIc1();
selectY5();
break;
}
case(gpioIds::CS_SUS_11): {
enableDecoderInterfaceBoardIc2();
selectY4();
break;
}
case(gpioIds::CS_SUS_12): {
enableDecoderInterfaceBoardIc2();
selectY5();
break;
}
case(gpioIds::CS_SUS_13): {
enableDecoderInterfaceBoardIc1();
selectY6();
break;
}
default:
sif::debug << "spiCsDecoderCallback: Invalid gpio id " << gpioId << std::endl;
}
@ -240,13 +239,13 @@ void enableDecoderTcsIc2() {
gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_3);
}
void enableDecoderInterfaceBoardIc21() {
void enableDecoderInterfaceBoardIc1() {
gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_1);
gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_2);
gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_3);
}
void enableDecoderInterfaceBoardIc22() {
void enableDecoderInterfaceBoardIc2() {
gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_1);
gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_2);
gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_3);
@ -300,4 +299,10 @@ void selectY7() {
gpioComInterface->pullHigh(gpioIds::SPI_MUX_BIT_6);
}
void disableAllDecoder() {
gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_1);
gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_2);
gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_3);
}
}

View File

@ -35,13 +35,18 @@ namespace gpioCallbacks {
* @brief This function sets mux bits 1-3 to a state which will only enable the decoder
* on the inteface board board which is named to IC21 in the schematic.
*/
void enableDecoderInterfaceBoardIc21();
void enableDecoderInterfaceBoardIc1();
/**
* @brief This function sets mux bits 1-3 to a state which will only enable the decoder
* on the inteface board board which is named to IC22 in the schematic.
*/
void enableDecoderInterfaceBoardIc22();
void enableDecoderInterfaceBoardIc2();
/**
* @brief This function disables all decoder.
*/
void disableAllDecoder();
/** The following functions enable the appropriate channel of the currently enabled decoder */
void selectY0();

View File

@ -1,6 +1,7 @@
#include "InitMission.h"
#include <OBSWVersion.h>
#include <fsfw/tasks/TaskFactory.h>
#include "OBSWConfig.h"
#include <iostream>
@ -13,7 +14,11 @@
int main(void)
{
std::cout << "-- EIVE OBSW --" << std::endl;
#if TE0720 == 0
std::cout << "-- Compiled for Linux (Xiphos Q7S) --" << std::endl;
#else
std::cout << "-- Compiled for Linux (TE0720) --" << std::endl;
#endif
std::cout << "-- Software version " << SW_NAME << " v" << SW_VERSION << "."
<< SW_SUBVERSION << "." << SW_SUBSUBVERSION << " -- " << std::endl;
std::cout << "-- " << __DATE__ << " " << __TIME__ << " --" << std::endl;

@ -1 +1 @@
Subproject commit a85c01465bc8687773676f05c5e7eb8af54b25ff
Subproject commit 425cfd2ababe3639355c6681ce3f9b606b893430

View File

@ -16,12 +16,15 @@
/* These defines should be disabled for mission code but are useful for
debugging. */
#define OBSW_VERBOSE_LEVEL 1
#define OBSW_PRINT_MISSED_DEADLINES 1
#define OBSW_ADD_TEST_CODE 1
#define TEST_LIBGPIOD 0
#define OBSW_VERBOSE_LEVEL 1
#define OBSW_PRINT_MISSED_DEADLINES 1
#define OBSW_ADD_TEST_CODE 1
#define TEST_LIBGPIOD 0
#define TEST_RADIATION_SENSOR_HANDLER 1
#define TEST_SUS_HANDLER 1
#define TEST_PLOC_HANDLER 0
#define TE0720 0
#define TE0720 1
#define TE0720_HEATER_TEST 0
#define P60DOCK_DEBUG 0

View File

@ -54,6 +54,21 @@ namespace objects {
IMTQ_HANDLER = 0x44000014,
PLOC_HANDLER = 0x44000015,
SUS_1 = 0x44000016,
SUS_2 = 0x44000017,
SUS_3 = 0x44000018,
SUS_4 = 0x44000019,
SUS_5 = 0x4400001A,
SUS_6 = 0x4400001B,
SUS_7 = 0x4400001C,
SUS_8 = 0x4400001D,
SUS_9 = 0x4400001E,
SUS_10 = 0x4400001F,
SUS_11 = 0x44000021,
SUS_12 = 0x44000022,
SUS_13 = 0x44000023,
/* Custom device handler */
PCDU_HANDLER = 0x44001000,
SOLAR_ARRAY_DEPL_HANDLER = 0x44001001,
@ -84,20 +99,6 @@ namespace objects {
RAD_SENSOR = 0x54000050,
SUS_1 = 0x54000051,
SUS_2 = 0x54000052,
SUS_3 = 0x54000053,
SUS_4 = 0x54000054,
SUS_5 = 0x54000055,
SUS_6 = 0x54000056,
SUS_7 = 0x54000057,
SUS_8 = 0x54000058,
SUS_9 = 0x54000059,
SUS_10 = 0x5400005A,
SUS_11 = 0x5400005B,
SUS_12 = 0x5400005C,
SUS_13 = 0x5400005D,
/* 0x54 ('T') for test handlers */
TEST_TASK = 0x54694269,
LIBGPIOD_TEST = 0x54123456,

View File

@ -6,6 +6,7 @@
#include <fsfw/tasks/FixedTimeslotTaskIF.h>
#include <fsfwconfig/objects/systemObjectList.h>
#include <fsfwconfig/OBSWConfig.h>
#include <mission/devices/SusHandler.h>
ReturnValue_t pst::pollingSequenceInitDefault(FixedTimeslotTaskIF *thisSequence)
@ -150,12 +151,60 @@ ReturnValue_t pst::pollingSequenceInitDefault(FixedTimeslotTaskIF *thisSequence)
thisSequence->addSlot(objects::RAD_SENSOR, length * 0.6, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::RAD_SENSOR, length * 0.8, DeviceHandlerIF::GET_READ);
/* Sun sensor 1 */
thisSequence->addSlot(objects::SUS_1, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_1, length * 0.2, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_1, length * 0.4, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_1, length * 0.6, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_1, length * 0.8, DeviceHandlerIF::GET_READ);
if (length != 3000) {
sif::warning << "pollingSequenceInitDefault: Frequency changed. Make sure timing critical "
<< "SUS sensors still produce correct values" << std::endl;
}
/**
* The sun sensor will be shutdown as soon as the chip select is pulled high. Thus all
* requests to a sun sensor must be performed consecutively. Another reason for calling multiple
* device handler cycles is that the ADC conversions take some time. Thus first the ADC
* conversions are initiated and in a next step the results can be read from the internal FIFO.
* One sun sensor communication sequence also blocks the SPI bus. So other devices can not be
* inserted between the device handler cycles of one SUS.
*/
/* Write setup */
thisSequence->addSlot(objects::SUS_8, length * 0.901, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_8, length * 0.902, SusHandler::FIRST_WRITE);
thisSequence->addSlot(objects::SUS_8, length * 0.903, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_8, length * 0.904, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_8, length * 0.905, DeviceHandlerIF::GET_READ);
/* Start ADC conversions */
thisSequence->addSlot(objects::SUS_8, length * 0.906, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_8, length * 0.907, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_8, length * 0.908, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_8, length * 0.909, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_8, length * 0.91, DeviceHandlerIF::GET_READ);
/* Read ADC conversions from inernal FIFO */
thisSequence->addSlot(objects::SUS_8, length * 0.911, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_8, length * 0.912, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_8, length * 0.913, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_8, length * 0.914, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_8, length * 0.915, DeviceHandlerIF::GET_READ);
/* Write setup */
thisSequence->addSlot(objects::SUS_12, length * 0.916, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_12, length * 0.917, SusHandler::FIRST_WRITE);
thisSequence->addSlot(objects::SUS_12, length * 0.918, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_12, length * 0.919, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_12, length * 0.920, DeviceHandlerIF::GET_READ);
/* Start ADC conversions */
thisSequence->addSlot(objects::SUS_12, length * 0.921, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_12, length * 0.922, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_12, length * 0.923, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_12, length * 0.924, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_12, length * 0.925, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::SUS_12, length * 0.926, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_12, length * 0.927, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_12, length * 0.928, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_12, length * 0.929, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_12, length * 0.93, DeviceHandlerIF::GET_READ);
if (thisSequence->checkSequence() == HasReturnvaluesIF::RETURN_OK) {
return HasReturnvaluesIF::RETURN_OK;
@ -217,62 +266,62 @@ 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_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_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);
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_2_L3G_HANDLER, length * 0,
// DeviceHandlerIF::PERFORM_OPERATION);
// thisSequence->addSlot(objects::GYRO_2_L3G_HANDLER, length * 0.2,
// DeviceHandlerIF::SEND_WRITE);
// thisSequence->addSlot(objects::GYRO_2_L3G_HANDLER, length * 0.4,
// DeviceHandlerIF::GET_WRITE);
// thisSequence->addSlot(objects::GYRO_2_L3G_HANDLER, length * 0.6,
// DeviceHandlerIF::SEND_READ);
// thisSequence->addSlot(objects::GYRO_2_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);
thisSequence->addSlot(objects::GYRO_2_L3G_HANDLER, length * 0,
DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::GYRO_2_L3G_HANDLER, length * 0.2,
DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::GYRO_2_L3G_HANDLER, length * 0.4,
DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::GYRO_2_L3G_HANDLER, length * 0.6,
DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::GYRO_2_L3G_HANDLER, length * 0.8,
DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::MGM_3_RM3100_HANDLER, length * 0,
@ -340,16 +389,44 @@ ReturnValue_t pst::pollingSequenceAcsTest(FixedTimeslotTaskIF *thisSequence) {
ReturnValue_t pst::pollingSequenceTE0720(FixedTimeslotTaskIF *thisSequence) {
uint32_t length = thisSequence->getPeriodMs();
thisSequence->addSlot(objects::PLOC_HANDLER, length * 0,
DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::PLOC_HANDLER, length * 0.2,
DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::PLOC_HANDLER, length * 0.4,
DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::PLOC_HANDLER, length * 0.6,
DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::PLOC_HANDLER, length * 0.8,
DeviceHandlerIF::GET_READ);
#if TEST_PLOC_HANDLER == 1
thisSequence->addSlot(objects::PLOC_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::PLOC_HANDLER, length * 0.2, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::PLOC_HANDLER, length * 0.4, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::PLOC_HANDLER, length * 0.6, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::PLOC_HANDLER, length * 0.8, DeviceHandlerIF::GET_READ);
#endif
#if TEST_RADIATION_SENSOR_HANDLER == 1
thisSequence->addSlot(objects::RAD_SENSOR, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::RAD_SENSOR, length * 0.2, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::RAD_SENSOR, length * 0.4, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::RAD_SENSOR, length * 0.6, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::RAD_SENSOR, length * 0.8, DeviceHandlerIF::GET_READ);
#endif
#if TEST_SUS_HANDLER == 1
/* Write setup */
thisSequence->addSlot(objects::SUS_1, length * 0.901, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_1, length * 0.902, SusHandler::FIRST_WRITE);
thisSequence->addSlot(objects::SUS_1, length * 0.903, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_1, length * 0.904, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_1, length * 0.905, DeviceHandlerIF::GET_READ);
/* Start conversion*/
thisSequence->addSlot(objects::SUS_1, length * 0.906, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_1, length * 0.907, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_1, length * 0.908, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_1, length * 0.909, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_1, length * 0.91, DeviceHandlerIF::GET_READ);
/* Read conversions */
thisSequence->addSlot(objects::SUS_1, length * 0.911, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_1, length * 0.912, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_1, length * 0.913, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_1, length * 0.914, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_1, length * 0.915, DeviceHandlerIF::GET_READ);
#endif
if (thisSequence->checkSequence() != HasReturnvaluesIF::RETURN_OK) {
sif::error << "Initialization of TE0720 PST failed" << std::endl;

View File

@ -20,7 +20,8 @@ enum {
SA_DEPL_HANDLER,
SYRLINKS_HANDLER,
IMTQ_HANDLER,
PLOC_HANDLER
PLOC_HANDLER,
SUS_HANDLER
};
}

View File

@ -1,28 +1,70 @@
#include <fsfw/datapool/PoolReadGuard.h>
#include <mission/devices/SusHandler.h>
#include <OBSWConfig.h>
#include <fsfw_hal/linux/spi/SpiComIF.h>
SusHandler::SusHandler(object_id_t objectId, object_id_t comIF,
CookieIF * comCookie) :
DeviceHandlerBase(objectId, comIF, comCookie), dataset(
this) {
if (comCookie == NULL) {
sif::error << "SusHandler: Invalid com cookie" << std::endl;
}
SusHandler::SusHandler(object_id_t objectId, object_id_t comIF, CookieIF * comCookie,
LinuxLibgpioIF* gpioComIF, gpioId_t chipSelectId) :
DeviceHandlerBase(objectId, comIF, comCookie), gpioComIF(gpioComIF), chipSelectId(
chipSelectId), dataset(this) {
if (comCookie == NULL) {
sif::error << "SusHandler: Invalid com cookie" << std::endl;
}
if (gpioComIF == NULL) {
sif::error << "SusHandler: Invalid GpioComIF" << std::endl;
}
}
SusHandler::~SusHandler() {
}
ReturnValue_t SusHandler::performOperation(uint8_t counter) {
if (counter != FIRST_WRITE) {
DeviceHandlerBase::performOperation(counter);
return RETURN_OK;
}
if (mode != MODE_NORMAL) {
DeviceHandlerBase::performOperation(DeviceHandlerIF::SEND_WRITE);
return RETURN_OK;
}
/* If device is in normale mode the communication sequence is initiated here */
if (communicationStep == CommunicationStep::IDLE) {
communicationStep = CommunicationStep::WRITE_SETUP;
}
DeviceHandlerBase::performOperation(DeviceHandlerIF::SEND_WRITE);
return RETURN_OK;
}
ReturnValue_t SusHandler::initialize() {
ReturnValue_t result = RETURN_OK;
result = DeviceHandlerBase::initialize();
if (result != RETURN_OK) {
return result;
}
auto spiComIF = dynamic_cast<SpiComIF*>(communicationInterface);
if (spiComIF == nullptr) {
sif::debug << "SusHandler::initialize: Invalid communication interface" << std::endl;
return ObjectManagerIF::CHILD_INIT_FAILED;
}
spiMutex = spiComIF->getMutex();
if (spiMutex == nullptr) {
sif::debug << "SusHandler::initialize: Failed to get spi mutex" << std::endl;
return ObjectManagerIF::CHILD_INIT_FAILED;
}
return RETURN_OK;
}
void SusHandler::doStartUp(){
if (internalState == InternalState::CONFIGURED) {
#if OBSW_SWITCH_TO_NORMAL_MODE_AFTER_STARTUP == 1
setMode(MODE_NORMAL);
setMode(MODE_NORMAL);
#else
setMode(_MODE_TO_ON);
setMode(_MODE_TO_ON);
#endif
}
}
void SusHandler::doShutDown(){
@ -32,36 +74,28 @@ void SusHandler::doShutDown(){
ReturnValue_t SusHandler::buildNormalDeviceCommand(
DeviceCommandId_t * id) {
switch (communicationStep) {
case CommunicationStep::START_CONVERSION: {
*id = SUS::START_CONVERSION;
communicationStep = CommunicationStep::READ_CONVERSIONS;
break;
if (communicationStep == CommunicationStep::IDLE) {
return NOTHING_TO_SEND;
}
case CommunicationStep::READ_CONVERSIONS: {
if (communicationStep == CommunicationStep::WRITE_SETUP) {
*id = SUS::WRITE_SETUP;
communicationStep = CommunicationStep::START_CONVERSIONS;
}
else if (communicationStep == CommunicationStep::START_CONVERSIONS) {
*id = SUS::START_CONVERSIONS;
communicationStep = CommunicationStep::READ_CONVERSIONS;
}
else if (communicationStep == CommunicationStep::READ_CONVERSIONS) {
*id = SUS::READ_CONVERSIONS;
// communicationStep = CommunicationStep::START_CONVERSION;
communicationStep = CommunicationStep::READ_CONVERSIONS;
break;
communicationStep = CommunicationStep::IDLE;
}
default: {
sif::debug << "SusHandler::buildNormalDeviceCommand: Unknwon communication "
<< "step" << std::endl;
return HasReturnvaluesIF::RETURN_OK;
}
}
return buildCommandFromCommand(*id, nullptr, 0);
return buildCommandFromCommand(*id, nullptr, 0);
}
ReturnValue_t SusHandler::buildTransitionDeviceCommand(
DeviceCommandId_t * id){
if (internalState == InternalState::SETUP) {
*id = SUS::WRITE_SETUP;
}
else {
return HasReturnvaluesIF::RETURN_OK;
}
return buildCommandFromCommand(*id, nullptr, 0);
return HasReturnvaluesIF::RETURN_OK;
}
ReturnValue_t SusHandler::buildCommandFromCommand(
@ -69,33 +103,42 @@ ReturnValue_t SusHandler::buildCommandFromCommand(
size_t commandDataLen) {
switch(deviceCommand) {
case(SUS::WRITE_SETUP): {
cmdBuffer[0] = SUS::SETUP_DEFINITION;
cmdBuffer[1] = SUS::UNIPOLAR_CONFIG;
/**
* The sun sensor ADC is shutdown when CS is pulled high, so each time requesting a
* measurement the setup has to be rewritten. There must also be a little delay between
* the transmission of the setup byte and the first conversion. Thus the conversion
* will be performed in an extra step.
* Because the chip select is driven manually by the SusHandler the SPI bus must be
* protected with a mutex here.
*/
ReturnValue_t result = spiMutex->lockMutex(timeoutType, timeoutMs);
if(result == MutexIF::MUTEX_TIMEOUT) {
sif::error << "SusHandler::buildCommandFromCommand: Mutex timeout" << std::endl;
return ERROR_LOCK_MUTEX;
}
else if(result != HasReturnvaluesIF::RETURN_OK) {
sif::error << "SusHandler::buildCommandFromCommand: Failed to lock spi mutex"
<< std::endl;
return ERROR_LOCK_MUTEX;
}
gpioComIF->pullLow(chipSelectId);
cmdBuffer[0] = SUS::SETUP;
rawPacket = cmdBuffer;
rawPacketLen = 2;
internalState = InternalState::CONFIGURED;
rawPacketLen = 1;
return RETURN_OK;
}
case(SUS::START_CONVERSION): {
/* First the fifo will be reset before a new conversion is initiated */
cmdBuffer[0] = SUS::RESET_DEFINITION;
cmdBuffer[1] = SUS::CONVERSION_DEFINITION;
case(SUS::START_CONVERSIONS): {
std::memset(cmdBuffer, 0, sizeof(cmdBuffer));
cmdBuffer[0] = SUS::CONVERSION;
rawPacket = cmdBuffer;
rawPacketLen = 2;
return RETURN_OK;
}
case(SUS::READ_CONVERSIONS): {
cmdBuffer[0] = SUS::DUMMY_BYTE;
cmdBuffer[1] = SUS::DUMMY_BYTE;
cmdBuffer[2] = SUS::DUMMY_BYTE;
cmdBuffer[3] = SUS::DUMMY_BYTE;
cmdBuffer[4] = SUS::DUMMY_BYTE;
cmdBuffer[5] = SUS::DUMMY_BYTE;
cmdBuffer[6] = SUS::DUMMY_BYTE;
cmdBuffer[7] = SUS::DUMMY_BYTE;
cmdBuffer[8] = SUS::DUMMY_BYTE;
rawPacket = cmdBuffer;
rawPacketLen = SUS::READ_SIZE;
std::memset(cmdBuffer, 0, sizeof(cmdBuffer));
rawPacket = cmdBuffer;
rawPacketLen = SUS::SIZE_READ_CONVERSIONS;
return RETURN_OK;
}
default:
@ -106,9 +149,8 @@ ReturnValue_t SusHandler::buildCommandFromCommand(
void SusHandler::fillCommandAndReplyMap() {
this->insertInCommandMap(SUS::WRITE_SETUP);
this->insertInCommandMap(SUS::START_CONVERSION);
this->insertInCommandAndReplyMap(SUS::READ_CONVERSIONS, 1, &dataset,
SUS::READ_SIZE);
this->insertInCommandMap(SUS::START_CONVERSIONS);
this->insertInCommandAndReplyMap(SUS::READ_CONVERSIONS, 1, &dataset, SUS::SIZE_READ_CONVERSIONS);
}
ReturnValue_t SusHandler::scanForReply(const uint8_t *start,
@ -123,20 +165,37 @@ ReturnValue_t SusHandler::interpretDeviceReply(DeviceCommandId_t id,
switch (id) {
case SUS::READ_CONVERSIONS: {
PoolReadGuard readSet(&dataset);
dataset.temperatureCelcius = (*(packet) << 8 | *(packet + 1)) * 0.125;
dataset.diffScanChannel0_1 = (*(packet + 2) << 8 | *(packet + 3));
dataset.diffScanChannel2_3 = (*(packet + 2) << 8 | *(packet + 3));
dataset.diffScanChannel4_5 = (*(packet + 2) << 8 | *(packet + 3));
dataset.temperatureCelcius = (*(packet) << 8 | *(packet + 1)) * 0.125;
dataset.ain0 = (*(packet + 2) << 8 | *(packet + 3));
dataset.ain1 = (*(packet + 4) << 8 | *(packet + 5));
dataset.ain2 = (*(packet + 6) << 8 | *(packet + 7));
dataset.ain3 = (*(packet + 8) << 8 | *(packet + 9));
dataset.ain4 = (*(packet + 10) << 8 | *(packet + 11));
dataset.ain5 = (*(packet + 12) << 8 | *(packet + 13));
#if OBSW_VERBOSE_LEVEL >= 1 && DEBUG_SUS
sif::info << "SUS with object id " << std::hex << this->getObjectId() << ", temperature: "
sif::info << "SUS object id 0x" << std::hex << this->getObjectId() << ", Temperature: "
<< dataset.temperatureCelcius << " °C" << std::endl;
sif::info << "SUS with object id " << std::hex << this->getObjectId() << ", channel 0/1: "
<< dataset.diffScanChannel0_1 << std::endl;
sif::info << "SUS with object id " << std::hex << this->getObjectId() << ", channel 2/3: "
<< dataset.diffScanChannel2_3 << std::endl;
sif::info << "SUS with object id " << std::hex << this->getObjectId() << ", channel 4/5: "
<< dataset.diffScanChannel4_5 << std::endl;
sif::info << "SUS object id 0x" << std::hex << this->getObjectId() << ", AIN0: "
<< std::dec << dataset.ain0 << std::endl;
sif::info << "SUS object id 0x" << std::hex << this->getObjectId() << ", AIN1: "
<< std::dec << dataset.ain1 << std::endl;
sif::info << "SUS object id 0x" << std::hex << this->getObjectId() << ", AIN2: "
<< std::dec << dataset.ain2 << std::endl;
sif::info << "SUS object id 0x" << std::hex << this->getObjectId() << ", AIN3: "
<< std::dec << dataset.ain3 << std::endl;
sif::info << "SUS object id 0x" << std::hex << this->getObjectId() << ", AIN4: "
<< std::dec << dataset.ain4 << std::endl;
sif::info << "SUS object id 0x" << std::hex << this->getObjectId() << ", AIN5: "
<< std::dec << dataset.ain5 << std::endl;
#endif
/** SUS can now be shutdown and thus the SPI bus released again */
gpioComIF->pullHigh(chipSelectId);
ReturnValue_t result = spiMutex->unlockMutex();
if (result != RETURN_OK) {
sif::error << "SusHandler::interpretDeviceReply: Failed to unlock spi mutex"
<< std::endl;
return ERROR_UNLOCK_MUTEX;
}
break;
}
default: {
@ -153,15 +212,18 @@ void SusHandler::setNormalDatapoolEntriesInvalid(){
}
uint32_t SusHandler::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo){
return 5000;
return 1000;
}
ReturnValue_t SusHandler::initializeLocalDataPool(localpool::DataPool& localDataPoolMap,
LocalDataPoolManager& poolManager) {
localDataPoolMap.emplace(SUS::TEMPERATURE_C, new PoolEntry<float>( { 0.0 }));
localDataPoolMap.emplace(SUS::DIFF_SCAN_CHANNEL_0_1, new PoolEntry<uint16_t>( { 0 }));
localDataPoolMap.emplace(SUS::DIFF_SCAN_CHANNEL_2_3, new PoolEntry<uint16_t>( { 0 }));
localDataPoolMap.emplace(SUS::DIFF_SCAN_CHANNEL_4_5, new PoolEntry<uint16_t>( { 0 }));
localDataPoolMap.emplace(SUS::AIN0, new PoolEntry<uint16_t>( { 0 }));
localDataPoolMap.emplace(SUS::AIN1, new PoolEntry<uint16_t>( { 0 }));
localDataPoolMap.emplace(SUS::AIN2, new PoolEntry<uint16_t>( { 0 }));
localDataPoolMap.emplace(SUS::AIN3, new PoolEntry<uint16_t>( { 0 }));
localDataPoolMap.emplace(SUS::AIN4, new PoolEntry<uint16_t>( { 0 }));
localDataPoolMap.emplace(SUS::AIN5, new PoolEntry<uint16_t>( { 0 }));
return HasReturnvaluesIF::RETURN_OK;
}

View File

@ -3,6 +3,8 @@
#include <fsfw/devicehandlers/DeviceHandlerBase.h>
#include <mission/devices/devicedefinitions/SusDefinitions.h>
#include <fsfw_hal/linux/gpio/LinuxLibgpioIF.h>
#include <fsfw/ipc/MutexGuard.h>
/**
* @brief This is the device handler class for the SUS sensor. The sensor is
@ -11,15 +13,25 @@
*
* @details Datasheet of MAX1227: https://datasheets.maximintegrated.com/en/ds/MAX1227-MAX1231.pdf
*
* @note When adding a SusHandler to the polling sequence table make sure to add a slot with
* the executionStep FIRST_WRITE. Otherwise the communication sequence will never be
* started.
*
* @author J. Meier
*/
class SusHandler: public DeviceHandlerBase {
public:
static const uint8_t FIRST_WRITE = 7;
SusHandler(object_id_t objectId, object_id_t comIF,
CookieIF * comCookie);
CookieIF * comCookie, LinuxLibgpioIF* gpioComIF, gpioId_t chipSelectId);
virtual ~SusHandler();
virtual ReturnValue_t performOperation(uint8_t counter) override;
virtual ReturnValue_t initialize() override;
protected:
void doStartUp() override;
void doShutDown() override;
@ -39,23 +51,31 @@ protected:
private:
static const uint8_t INTERFACE_ID = CLASS_ID::SUS_HANDLER;
static const ReturnValue_t ERROR_UNLOCK_MUTEX = MAKE_RETURN_CODE(0xA0);
static const ReturnValue_t ERROR_LOCK_MUTEX = MAKE_RETURN_CODE(0xA1);
enum class CommunicationStep {
START_CONVERSION,
IDLE,
WRITE_SETUP,
START_CONVERSIONS,
READ_CONVERSIONS
};
enum class InternalState {
SETUP,
CONFIGURED
};
LinuxLibgpioIF* gpioComIF = nullptr;
gpioId_t chipSelectId = gpio::NO_GPIO;
SUS::SusDataset dataset;
static const uint8_t MAX_CMD_LEN = SUS::READ_SIZE;
uint8_t cmdBuffer[SUS::MAX_CMD_SIZE];
CommunicationStep communicationStep = CommunicationStep::IDLE;
uint8_t cmdBuffer[MAX_CMD_LEN];
InternalState internalState = InternalState::SETUP;
CommunicationStep communicationStep = CommunicationStep::START_CONVERSION;
MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING;
uint32_t timeoutMs = 20;
MutexIF* spiMutex = nullptr;
};
#endif /* MISSION_DEVICES_SUSHANDLER_H_ */

View File

@ -18,7 +18,7 @@ namespace RAD_SENSOR {
* power on.
*
* @note Bit1 (DIFFSEL1) - Bit0 (DIFFSEL0): 0b00, no data follows the setup byte
* Bit3 (REFSEL1) - Bit2 (REFSEL0): 0b01, external reference single ended
* Bit3 (REFSEL1) - Bit2 (REFSEL0): 0b10, internal reference, no wake-up delay
* Bit5 (CLKSEL1) - Bit4 (CLKSEL0): 0b10, MAX1227 uses internal oscillator for timing
* Bit7 - Bit6: 0b01, tells MAX1227 that this is the setup register
*

View File

@ -3,70 +3,69 @@
namespace SUS {
/**
* Some MAX1227 could not be reached with frequencies around 4 MHz. Maybe this is caused by
* the decoder and buffer circuits. Thus frequency is here defined to 1 MHz.
*/
static const uint32_t MAX1227_SPI_FREQ = 1000000;
static const DeviceCommandId_t NONE = 0x0; // Set when no command is pending
/**
* This command initiates the ADC conversion for all channels including the internal
* temperature sensor.
*/
static const DeviceCommandId_t WRITE_SETUP = 0x1;
static const DeviceCommandId_t START_CONVERSION = 0x2;
/**
* This command initiates the ADC conversion for all channels including the internal
* temperature sensor.
*/
static const DeviceCommandId_t START_CONVERSIONS = 0x2;
/**
* This command reads the internal fifo which holds the temperature and the channel
* conversions.
*/
static const DeviceCommandId_t READ_CONVERSIONS = 0x3;
/**
* @brief This is the configuration byte which will be written to the setup register after
* power on.
*
* @note Bit1 (DIFFSEL1) - Bit0 (DIFFSEL0): 0b10, following byte will be written to the
* unipolar register to perform differential conversion
* Bit3 (REFSEL1) - Bit2 (REFSEL0): 0b11, external reference differential (AIN6 is REF-)
* Bit5 (CLKSEL1) - Bit4 (CLKSEL0): 0b10, MAX1227 uses internal oscillator for timing
* Bit7 - Bit6: 0b01, tells MAX1227 that this is the setup register
* @note Bit1 (DIFFSEL1) - Bit0 (DIFFSEL0): 0b00, No byte is following the setup byte
* Bit3 (REFSEL1) - Bit2 (REFSEL0): 0b10, Internal reference, no wake-up delay
* Bit5 (CLKSEL1) - Bit4 (CLKSEL0): 0b10, Internally clocked
* Bit7 - Bit6: 0b01, Tells MAX1227 that this byte should be
* written to the setup register
*
*/
static const uint8_t SETUP_DEFINITION = 0b01101110;
static const uint8_t SETUP = 0b01101000;
/**
* @brief This byte will be written to the unipolar register
*
* @details Setting bits 7 - 5 to will configure channels 0/1, 2/3 and 4/5 as differential
* pairs.
*/
static const uint8_t UNIPOLAR_CONFIG = 0b11100000;
/**
* @brief Writing this value resets the fifo of the MAX1227.
*/
static const uint8_t RESET_DEFINITION = 0b00011000;
/**
* @brief This value will always be written to the ADC conversion register to specify the
* @brief This values will always be written to the ADC conversion register to specify the
* conversions to perform.
* @details Bit0: 1 - Enables temperature conversion
* Bit2 (SCAN1) and Bit1 (SCAN0): 0b00 (channel conversion from 0 to N)
* Bit6 - Bit3 defines N: 0b0001 (N = 4)
* Bit2 (SCAN1) and Bit1 (SCAN0): 0b00, Scans channels 0 through N
* Bit6 - Bit3 defines N: 0b0101 (N = 5)
* Bit7: Always 1. Tells the ADC that this is the conversion register.
*/
static const uint8_t CONVERSION_DEFINITION = 0b10100001;
static const uint8_t DUMMY_BYTE = 0xFF;
static const uint8_t CONVERSION = 0b10101001;
static const uint8_t SUS_DATA_SET_ID = READ_CONVERSIONS;
/**
* One temperature value, one differential conversion for channels 0/1, one for channels 2/3 and
* one for channels 3/4
*/
static const uint8_t READ_SIZE = 8;
/** Size of data replies. Temperature and 6 channel convesions (AIN0 - AIN5) */
static const uint8_t SIZE_READ_CONVERSIONS = 14;
static const uint8_t MAX_CMD_SIZE = SIZE_READ_CONVERSIONS;
static const uint8_t POOL_ENTRIES = 7;
enum Max1227PoolIds: lp_id_t {
TEMPERATURE_C,
DIFF_SCAN_CHANNEL_0_1,
DIFF_SCAN_CHANNEL_2_3,
DIFF_SCAN_CHANNEL_4_5,
AIN0,
AIN1,
AIN2,
AIN3,
AIN4,
AIN5,
};
class SusDataset: public StaticLocalDataSet<sizeof(float)> {
class SusDataset: public StaticLocalDataSet<POOL_ENTRIES> {
public:
SusDataset(HasLocalDataPoolIF* owner) :
@ -78,9 +77,12 @@ public:
}
lp_var_t<float> temperatureCelcius = lp_var_t<float>(sid.objectId, TEMPERATURE_C, this);
lp_var_t<uint16_t> diffScanChannel0_1 = lp_var_t<uint16_t>(sid.objectId, DIFF_SCAN_CHANNEL_0_1, this);
lp_var_t<uint16_t> diffScanChannel2_3 = lp_var_t<uint16_t>(sid.objectId, DIFF_SCAN_CHANNEL_2_3, this);
lp_var_t<uint16_t> diffScanChannel4_5 = lp_var_t<uint16_t>(sid.objectId, DIFF_SCAN_CHANNEL_4_5, this);
lp_var_t<uint16_t> ain0 = lp_var_t<uint16_t>(sid.objectId, AIN0, this);
lp_var_t<uint16_t> ain1 = lp_var_t<uint16_t>(sid.objectId, AIN1, this);
lp_var_t<uint16_t> ain2 = lp_var_t<uint16_t>(sid.objectId, AIN2, this);
lp_var_t<uint16_t> ain3 = lp_var_t<uint16_t>(sid.objectId, AIN3, this);
lp_var_t<uint16_t> ain4 = lp_var_t<uint16_t>(sid.objectId, AIN4, this);
lp_var_t<uint16_t> ain5 = lp_var_t<uint16_t>(sid.objectId, AIN5, this);
};
}