Merge branch 'develop' into mohr/catch2
Some checks failed
EIVE/eive-obsw/pipeline/head There was a failure building this commit

This commit is contained in:
2022-03-02 16:19:10 +01:00
committed by Uli
146 changed files with 9279 additions and 5091 deletions

View File

@ -15,16 +15,20 @@
#include <bitset>
#if defined(XIPHOS_Q7S)
#include "busConf.h"
#endif
#include "devices/gpioIds.h"
#include "mission/devices/max1227.h"
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());
testMode = TestModes::MAX1227;
spiTransferStruct[0].rx_buf = reinterpret_cast<__u64>(recvBuffer.data());
setSendBuffer();
}
ReturnValue_t SpiTestClass::performOneShotAction() {
@ -44,11 +48,25 @@ ReturnValue_t SpiTestClass::performOneShotAction() {
performL3gTest(gyro1L3gd20ChipSelect);
break;
}
case (TestModes::MAX1227): {
performOneShotMax1227Test();
break;
}
}
return HasReturnvaluesIF::RETURN_OK;
}
ReturnValue_t SpiTestClass::performPeriodicAction() { return HasReturnvaluesIF::RETURN_OK; }
ReturnValue_t SpiTestClass::performPeriodicAction() {
switch (testMode) {
case (TestModes::MAX1227): {
performPeriodicMax1227Test();
break;
}
default:
break;
}
return HasReturnvaluesIF::RETURN_OK;
}
void SpiTestClass::performRm3100Test(uint8_t mgmId) {
/* Configure all SPI chip selects and pull them high */
@ -180,7 +198,7 @@ void SpiTestClass::performLis3MdlTest(uint8_t lis3Id) {
return;
}
setSpiSpeedAndMode(fileDescriptor, spiMode, spiSpeed);
spiTransferStruct.delay_usecs = 0;
spiTransferStruct[0].delay_usecs = 0;
uint8_t whoAmIRegVal = readStmRegister(fileDescriptor, currentGpioId, whoAmIReg, false);
sif::info << "SpiTestClass::performLis3MdlTest: WHO AM I register 0b"
@ -273,73 +291,422 @@ void SpiTestClass::performL3gTest(uint8_t l3gId) {
sif::info << "Z: " << angVelocZ << std::endl;
}
void SpiTestClass::performOneShotMax1227Test() {
using namespace max1227;
adcCfg.testRadSensorExtConvWithDelay = false;
adcCfg.testRadSensorIntConv = false;
bool setAllSusOn = false;
bool susIntConv = false;
bool susExtConv = false;
if (setAllSusOn) {
for (uint8_t idx = 0; idx < 12; idx++) {
adcCfg.testSus[idx].doTest = true;
}
} else {
for (uint8_t idx = 0; idx < 12; idx++) {
adcCfg.testSus[idx].doTest = false;
}
}
if (susIntConv) {
for (uint8_t idx = 0; idx < 12; idx++) {
adcCfg.testSus[idx].intConv = true;
}
}
if (susExtConv) {
for (uint8_t idx = 0; idx < 12; idx++) {
adcCfg.testSus[idx].extConv = true;
}
}
adcCfg.plPcduAdcExtConv = true;
adcCfg.plPcduAdcIntConv = false;
// Is problematic, don't know why
adcCfg.plPcduAdcExtConvAsOne = false;
performMax1227Test();
}
void SpiTestClass::performPeriodicMax1227Test() {
using namespace max1227;
performMax1227Test();
}
void SpiTestClass::performMax1227Test() {
#ifdef XIPHOS_Q7S
std::string deviceName = q7s::SPI_DEFAULT_DEV;
#elif defined(RASPBERRY_PI)
std::string deviceName = "";
#elif defined(EGSE)
std::string deviceName = "";
#endif
int fd = 0;
UnixFileGuard fileHelper(deviceName, &fd, O_RDWR, "SpiComIF::initializeInterface");
if (fileHelper.getOpenResult()) {
sif::error << "SpiTestClass::performLis3Mdl3100Test: File descriptor could not be opened!"
<< std::endl;
return;
}
uint32_t spiSpeed = 976'000;
spi::SpiModes spiMode = spi::SpiModes::MODE_3;
setSpiSpeedAndMode(fd, spiMode, spiSpeed);
max1227RadSensorTest(fd);
int idx = 0;
bool firstTest = true;
for (auto &susCfg : adcCfg.testSus) {
if (susCfg.doTest) {
if (firstTest) {
firstTest = false;
sif::info << "---------- SUS ADC Values -----------" << std::endl;
}
sif::info << "SUS " << std::setw(2) << idx << ": ";
max1227SusTest(fd, susCfg);
}
idx++;
}
max1227PlPcduTest(fd);
}
void SpiTestClass::max1227RadSensorTest(int fd) {
using namespace max1227;
if (adcCfg.testRadSensorExtConvWithDelay) {
sendBuffer[0] = max1227::buildResetByte(true);
spiTransferStruct[0].len = 1;
transfer(fd, gpioIds::CS_RAD_SENSOR);
usleep(200);
sendBuffer[0] = max1227::buildSetupByte(ClkSel::EXT_CONV_EXT_TIMED, RefSel::INT_REF_WITH_WAKEUP,
DiffSel::NONE_0);
spiTransferStruct[0].len = 1;
transfer(fd, gpioIds::CS_RAD_SENSOR);
max1227::prepareExternallyClockedRead0ToN(sendBuffer.data(), 7, spiTransferStruct[0].len);
size_t tmpLen = spiTransferStruct[0].len;
spiTransferStruct[0].len = 1;
transfer(fd, gpioIds::CS_RAD_SENSOR);
std::memcpy(sendBuffer.data(), sendBuffer.data() + 1, tmpLen - 1);
spiTransferStruct[0].len = tmpLen - 1;
usleep(65);
transfer(fd, gpioIds::CS_RAD_SENSOR);
arrayprinter::print(recvBuffer.data(), 13, OutputType::HEX);
uint16_t adcRaw[8] = {};
adcRaw[0] = (recvBuffer[0] << 8) | recvBuffer[1];
adcRaw[1] = (recvBuffer[2] << 8) | recvBuffer[3];
adcRaw[2] = (recvBuffer[4] << 8) | recvBuffer[5];
adcRaw[3] = (recvBuffer[6] << 8) | recvBuffer[7];
adcRaw[4] = (recvBuffer[8] << 8) | recvBuffer[9];
adcRaw[5] = (recvBuffer[10] << 8) | recvBuffer[11];
adcRaw[6] = (recvBuffer[12] << 8) | recvBuffer[13];
adcRaw[7] = (recvBuffer[14] << 8) | recvBuffer[15];
arrayprinter::print(recvBuffer.data(), 17, OutputType::HEX);
for (int idx = 0; idx < 8; idx++) {
sif::info << "ADC raw " << idx << ": " << adcRaw[idx] << std::endl;
}
max1227::prepareExternallyClockedTemperatureRead(sendBuffer.data(), spiTransferStruct[0].len);
spiTransferStruct[0].len = 1;
transfer(fd, gpioIds::CS_RAD_SENSOR);
usleep(65);
spiTransferStruct[0].len = 24;
std::memcpy(sendBuffer.data(), sendBuffer.data() + 1, 24);
transfer(fd, gpioIds::CS_RAD_SENSOR);
int16_t tempRaw = ((recvBuffer[22] & 0x0f) << 8) | recvBuffer[23];
float temp = max1227::getTemperature(tempRaw);
sif::info << "Temperature: " << temp << std::endl;
}
if (adcCfg.testRadSensorIntConv) {
sendBuffer[0] = max1227::buildResetByte(false);
spiTransferStruct[0].len = 1;
transfer(fd, gpioIds::CS_RAD_SENSOR);
usleep(5);
// Now use internal conversion
sendBuffer[0] = max1227::buildSetupByte(ClkSel::INT_CONV_INT_TIMED_CNVST_AS_AIN,
RefSel::INT_REF_NO_WAKEUP, DiffSel::NONE_0);
spiTransferStruct[0].len = 1;
transfer(fd, gpioIds::CS_RAD_SENSOR);
usleep(10);
sendBuffer[0] = buildConvByte(ScanModes::CHANNELS_0_TO_N, 7, true);
spiTransferStruct[0].len = 1;
transfer(fd, gpioIds::CS_RAD_SENSOR);
usleep(65);
spiTransferStruct[0].len = 18;
// Shift out zeros
shiftOutZeros();
transfer(fd, gpioIds::CS_RAD_SENSOR);
setSendBuffer();
arrayprinter::print(recvBuffer.data(), 14);
uint16_t adcRaw[8] = {};
int16_t tempRaw = ((recvBuffer[0] & 0x0f) << 8) | recvBuffer[1];
sif::info << "Temperature: " << tempRaw * 0.125 << " C" << std::endl;
adcRaw[0] = (recvBuffer[2] << 8) | recvBuffer[3];
adcRaw[1] = (recvBuffer[4] << 8) | recvBuffer[5];
adcRaw[2] = (recvBuffer[6] << 8) | recvBuffer[7];
adcRaw[3] = (recvBuffer[8] << 8) | recvBuffer[9];
adcRaw[4] = (recvBuffer[10] << 8) | recvBuffer[11];
adcRaw[5] = (recvBuffer[12] << 8) | recvBuffer[13];
adcRaw[6] = (recvBuffer[14] << 8) | recvBuffer[15];
adcRaw[7] = (recvBuffer[16] << 8) | recvBuffer[17];
for (int idx = 0; idx < 8; idx++) {
sif::info << "ADC raw " << idx << ": " << adcRaw[idx] << std::endl;
}
}
}
void SpiTestClass::max1227SusTest(int fd, SusTestCfg &cfg) {
using namespace max1227;
if (cfg.extConv) {
sendBuffer[0] = max1227::buildResetByte(false);
spiTransferStruct[0].len = 1;
transfer(fd, cfg.gpioId);
usleep(65);
sendBuffer[0] = max1227::buildSetupByte(ClkSel::EXT_CONV_EXT_TIMED, RefSel::INT_REF_NO_WAKEUP,
DiffSel::NONE_0);
spiTransferStruct[0].len = 1;
transfer(fd, cfg.gpioId);
max1227::prepareExternallyClockedRead0ToN(sendBuffer.data(), 5, spiTransferStruct[0].len);
transfer(fd, cfg.gpioId);
uint16_t adcRaw[6] = {};
adcRaw[0] = (recvBuffer[1] << 8) | recvBuffer[2];
adcRaw[1] = (recvBuffer[3] << 8) | recvBuffer[4];
adcRaw[2] = (recvBuffer[5] << 8) | recvBuffer[6];
adcRaw[3] = (recvBuffer[7] << 8) | recvBuffer[8];
adcRaw[4] = (recvBuffer[9] << 8) | recvBuffer[10];
adcRaw[5] = (recvBuffer[11] << 8) | recvBuffer[12];
sif::info << "Ext Conv [" << std::hex << std::setw(3);
for (int idx = 0; idx < 5; idx++) {
sif::info << adcRaw[idx];
if (idx < 6) {
sif::info << ",";
}
}
sif::info << std::dec << "]" << std::endl; // | Temperature: " << temp << " C" << std::endl;
}
if (cfg.intConv) {
sendBuffer[0] = max1227::buildResetByte(false);
spiTransferStruct[0].len = 1;
transfer(fd, cfg.gpioId);
usleep(65);
// Now use internal conversion
sendBuffer[0] = max1227::buildSetupByte(ClkSel::INT_CONV_INT_TIMED_CNVST_AS_AIN,
RefSel::INT_REF_NO_WAKEUP, DiffSel::NONE_0);
spiTransferStruct[0].len = 1;
transfer(fd, cfg.gpioId);
usleep(10);
sendBuffer[0] = buildConvByte(ScanModes::CHANNELS_0_TO_N, 5, true);
spiTransferStruct[0].len = 1;
transfer(fd, cfg.gpioId);
usleep(65);
spiTransferStruct[0].len = 14;
// Shift out zeros
shiftOutZeros();
transfer(fd, cfg.gpioId);
setSendBuffer();
// arrayprinter::print(recvBuffer.data(), 14);
float temp = static_cast<int16_t>(((recvBuffer[0] & 0x0f) << 8) | recvBuffer[1]) * 0.125;
uint16_t adcRaw[6] = {};
adcRaw[0] = (recvBuffer[2] << 8) | recvBuffer[3];
adcRaw[1] = (recvBuffer[4] << 8) | recvBuffer[5];
adcRaw[2] = (recvBuffer[6] << 8) | recvBuffer[7];
adcRaw[3] = (recvBuffer[8] << 8) | recvBuffer[9];
adcRaw[4] = (recvBuffer[10] << 8) | recvBuffer[11];
adcRaw[5] = (recvBuffer[12] << 8) | recvBuffer[13];
sif::info << "Int Conv [" << std::hex << std::setw(3);
for (int idx = 0; idx < 6; idx++) {
sif::info << adcRaw[idx];
if (idx < 5) {
sif::info << ",";
}
}
sif::info << std::dec << "] | T[C] " << temp << std::endl;
}
}
void SpiTestClass::max1227PlPcduTest(int fd) {
using namespace max1227;
if ((adcCfg.plPcduAdcExtConv or adcCfg.plPcduAdcIntConv or adcCfg.plPcduAdcExtConvAsOne) and
adcCfg.vbatSwitch) {
// This enables the ADC
ReturnValue_t result = gpioIF->pullHigh(gpioIds::PLPCDU_ENB_VBAT0);
if (result != HasReturnvaluesIF::RETURN_OK) {
return;
}
result = gpioIF->pullHigh(gpioIds::PLPCDU_ENB_VBAT1);
if (result != HasReturnvaluesIF::RETURN_OK) {
return;
}
adcCfg.vbatSwitch = false;
// Takes a bit of time until the ADC is usable
TaskFactory::delayTask(50);
sendBuffer[0] = max1227::buildResetByte(false);
spiTransferStruct[0].len = 1;
transfer(fd, gpioIds::PLPCDU_ADC_CS);
}
if (adcCfg.plPcduAdcExtConv) {
sendBuffer[0] = max1227::buildSetupByte(ClkSel::EXT_CONV_EXT_TIMED, RefSel::INT_REF_NO_WAKEUP,
DiffSel::NONE_0);
spiTransferStruct[0].len = 1;
transfer(fd, gpioIds::PLPCDU_ADC_CS);
uint8_t n = 11;
max1227::prepareExternallyClockedRead0ToN(sendBuffer.data(), n, spiTransferStruct[0].len);
size_t dummy = 0;
max1227::prepareExternallyClockedTemperatureRead(sendBuffer.data() + spiTransferStruct[0].len,
dummy);
// + 1 to account for temp conversion byte
spiTransferStruct[0].len += 1;
transfer(fd, gpioIds::PLPCDU_ADC_CS);
uint16_t adcRaw[n + 1] = {};
for (uint8_t idx = 0; idx < n + 1; idx++) {
adcRaw[idx] = (recvBuffer[idx * 2 + 1] << 8) | recvBuffer[idx * 2 + 2];
}
spiTransferStruct[0].len = 24;
// Shift out zeros
shiftOutZeros();
transfer(fd, gpioIds::PLPCDU_ADC_CS);
setSendBuffer();
int16_t tempRaw = ((recvBuffer[22] & 0x0f) << 8) | recvBuffer[23];
sif::info << "PL PCDU ADC ext conv [" << std::hex << std::setfill('0');
for (int idx = 0; idx < n + 1; idx++) {
sif::info << std::setw(3) << adcRaw[idx];
if (idx < n) {
sif::info << ",";
}
}
sif::info << "]" << std::endl;
sif::info << "Temperature: " << max1227::getTemperature(tempRaw) << " C" << std::endl;
}
if (adcCfg.plPcduAdcExtConvAsOne) {
sendBuffer[0] = max1227::buildSetupByte(ClkSel::EXT_CONV_EXT_TIMED, RefSel::INT_REF_NO_WAKEUP,
DiffSel::NONE_0);
spiTransferStruct[0].len = 1;
transfer(fd, gpioIds::PLPCDU_ADC_CS);
uint8_t n = 11;
max1227::prepareExternallyClockedRead0ToN(sendBuffer.data(), n, spiTransferStruct[0].len);
max1227::prepareExternallyClockedTemperatureRead(sendBuffer.data() + spiTransferStruct[0].len,
spiTransferStruct[0].len);
transfer(fd, gpioIds::PLPCDU_ADC_CS);
uint16_t adcRaw[n + 1] = {};
for (uint8_t idx = 0; idx < n + 1; idx++) {
adcRaw[idx] = (recvBuffer[idx * 2 + 1] << 8) | recvBuffer[idx * 2 + 2];
}
int16_t tempRaw = ((recvBuffer[spiTransferStruct[0].len - 2] & 0x0f) << 8) |
recvBuffer[spiTransferStruct[0].len - 1];
sif::info << "PL PCDU ADC ext conv [" << std::hex << std::setfill('0');
for (int idx = 0; idx < n + 1; idx++) {
sif::info << std::setw(3) << adcRaw[idx];
if (idx < n) {
sif::info << ",";
}
}
sif::info << "]" << std::endl;
sif::info << "Temperature: " << max1227::getTemperature(tempRaw) << " C" << std::endl;
}
if (adcCfg.plPcduAdcIntConv) {
sendBuffer[0] = max1227::buildResetByte(true);
spiTransferStruct[0].len = 1;
transfer(fd, gpioIds::PLPCDU_ADC_CS);
// Now use internal conversion
sendBuffer[0] = max1227::buildSetupByte(ClkSel::INT_CONV_INT_TIMED_CNVST_AS_AIN,
RefSel::INT_REF_NO_WAKEUP, DiffSel::NONE_0);
spiTransferStruct[0].len = 1;
transfer(fd, gpioIds::PLPCDU_ADC_CS);
usleep(10);
uint8_t n = 11;
sendBuffer[0] = buildConvByte(ScanModes::CHANNELS_0_TO_N, n, true);
spiTransferStruct[0].len = 1;
transfer(fd, gpioIds::PLPCDU_ADC_CS);
usleep(65);
spiTransferStruct[0].len = 26;
// Shift out zeros
shiftOutZeros();
transfer(fd, gpioIds::PLPCDU_ADC_CS);
setSendBuffer();
uint16_t adcRaw[n + 1] = {};
int16_t tempRaw = ((recvBuffer[0] & 0x0f) << 8) | recvBuffer[1];
sif::info << "PL PCDU ADC int conv [" << std::hex << std::setfill('0');
for (int idx = 0; idx < n + 1; idx++) {
adcRaw[idx] = (recvBuffer[idx * 2 + 2] << 8) | recvBuffer[idx * 2 + 3];
sif::info << std::setw(3) << adcRaw[idx];
if (idx < n) {
sif::info << ",";
}
}
sif::info << "]" << std::endl;
sif::info << "Temperature: " << max1227::getTemperature(tempRaw) << " C" << std::endl;
}
}
void SpiTestClass::acsInit() {
using namespace gpio;
GpioCookie *gpioCookie = new GpioCookie();
#ifdef RASPBERRY_PI
GpiodRegularByChip *gpio = nullptr;
std::string rpiGpioName = "gpiochip0";
gpio = new GpiodRegularByChip(rpiGpioName, mgm0Lis3mdlChipSelect, "MGM_0_LIS3", gpio::DIR_OUT,
gpio::HIGH);
gpio = new GpiodRegularByChip(rpiGpioName, mgm0Lis3mdlChipSelect, "MGM_0_LIS3", Direction::OUT,
Levels::HIGH);
gpioCookie->addGpio(gpioIds::MGM_0_LIS3_CS, gpio);
gpio = new GpiodRegularByChip(rpiGpioName, mgm1Rm3100ChipSelect, "MGM_1_RM3100", gpio::DIR_OUT,
gpio::HIGH);
gpio = new GpiodRegularByChip(rpiGpioName, mgm1Rm3100ChipSelect, "MGM_1_RM3100", Direction::OUT,
Levels::HIGH);
gpioCookie->addGpio(gpioIds::MGM_1_RM3100_CS, gpio);
gpio = new GpiodRegularByChip(rpiGpioName, gyro0AdisChipSelect, "GYRO_0_ADIS", gpio::DIR_OUT,
gpio::HIGH);
gpio = new GpiodRegularByChip(rpiGpioName, gyro0AdisChipSelect, "GYRO_0_ADIS", Direction::OUT,
Levels::HIGH);
gpioCookie->addGpio(gpioIds::GYRO_0_ADIS_CS, gpio);
gpio = new GpiodRegularByChip(rpiGpioName, gyro1L3gd20ChipSelect, "GYRO_1_L3G", gpio::DIR_OUT,
gpio::HIGH);
gpio = new GpiodRegularByChip(rpiGpioName, gyro1L3gd20ChipSelect, "GYRO_1_L3G", Direction::OUT,
Levels::HIGH);
gpioCookie->addGpio(gpioIds::GYRO_1_L3G_CS, gpio);
gpio = new GpiodRegularByChip(rpiGpioName, gyro3L3gd20ChipSelect, "GYRO_2_L3G", gpio::DIR_OUT,
gpio::HIGH);
gpio = new GpiodRegularByChip(rpiGpioName, gyro3L3gd20ChipSelect, "GYRO_2_L3G", Direction::OUT,
Levels::HIGH);
gpioCookie->addGpio(gpioIds::GYRO_3_L3G_CS, gpio);
gpio = new GpiodRegularByChip(rpiGpioName, mgm2Lis3mdlChipSelect, "MGM_2_LIS3", gpio::DIR_OUT,
gpio::HIGH);
gpio = new GpiodRegularByChip(rpiGpioName, mgm2Lis3mdlChipSelect, "MGM_2_LIS3", Direction::OUT,
Levels::HIGH);
gpioCookie->addGpio(gpioIds::MGM_2_LIS3_CS, gpio);
gpio = new GpiodRegularByChip(rpiGpioName, mgm3Rm3100ChipSelect, "MGM_3_RM3100", gpio::DIR_OUT,
gpio::HIGH);
gpio = new GpiodRegularByChip(rpiGpioName, mgm3Rm3100ChipSelect, "MGM_3_RM3100", Direction::OUT,
Levels::HIGH);
gpioCookie->addGpio(gpioIds::MGM_3_RM3100_CS, gpio);
#elif defined(XIPHOS_Q7S)
GpiodRegularByLineName *gpio = nullptr;
gpio =
new GpiodRegularByLineName(q7s::gpioNames::MGM_0_CS, "MGM_0_LIS3", gpio::DIR_OUT, gpio::HIGH);
gpio = new GpiodRegularByLineName(q7s::gpioNames::MGM_0_CS, "MGM_0_LIS3", Direction::OUT,
Levels::HIGH);
gpioCookie->addGpio(gpioIds::MGM_0_LIS3_CS, gpio);
gpio = new GpiodRegularByLineName(q7s::gpioNames::MGM_1_CS, "MGM_1_RM3100", gpio::DIR_OUT,
gpio::HIGH);
gpio = new GpiodRegularByLineName(q7s::gpioNames::MGM_1_CS, "MGM_1_RM3100", Direction::OUT,
Levels::HIGH);
gpioCookie->addGpio(gpioIds::MGM_1_RM3100_CS, gpio);
gpio =
new GpiodRegularByLineName(q7s::gpioNames::MGM_2_CS, "MGM_2_LIS3", gpio::DIR_OUT, gpio::HIGH);
gpio = new GpiodRegularByLineName(q7s::gpioNames::MGM_2_CS, "MGM_2_LIS3", Direction::OUT,
Levels::HIGH);
gpioCookie->addGpio(gpioIds::MGM_2_LIS3_CS, gpio);
gpio = new GpiodRegularByLineName(q7s::gpioNames::MGM_1_CS, "MGM_3_RM3100", gpio::DIR_OUT,
gpio::HIGH);
gpio = new GpiodRegularByLineName(q7s::gpioNames::MGM_1_CS, "MGM_3_RM3100", Direction::OUT,
Levels::HIGH);
gpioCookie->addGpio(gpioIds::MGM_3_RM3100_CS, gpio);
gpio = new GpiodRegularByLineName(q7s::gpioNames::GYRO_0_ADIS_CS, "GYRO_0_ADIS", gpio::DIR_OUT,
gpio::HIGH);
gpio = new GpiodRegularByLineName(q7s::gpioNames::GYRO_0_ADIS_CS, "GYRO_0_ADIS", Direction::OUT,
Levels::HIGH);
gpioCookie->addGpio(gpioIds::GYRO_0_ADIS_CS, gpio);
gpio = new GpiodRegularByLineName(q7s::gpioNames::GYRO_1_L3G_CS, "GYRO_1_L3G", gpio::DIR_OUT,
gpio::HIGH);
gpio = new GpiodRegularByLineName(q7s::gpioNames::GYRO_1_L3G_CS, "GYRO_1_L3G", Direction::OUT,
Levels::HIGH);
gpioCookie->addGpio(gpioIds::GYRO_1_L3G_CS, gpio);
gpio = new GpiodRegularByLineName(q7s::gpioNames::GYRO_2_ADIS_CS, "GYRO_2_ADIS", gpio::DIR_OUT,
gpio::HIGH);
gpio = new GpiodRegularByLineName(q7s::gpioNames::GYRO_2_ADIS_CS, "GYRO_2_ADIS", Direction::OUT,
Levels::HIGH);
gpioCookie->addGpio(gpioIds::GYRO_2_ADIS_CS, gpio);
gpio = new GpiodRegularByLineName(q7s::gpioNames::GYRO_3_L3G_CS, "GYRO_3_L3G", gpio::DIR_OUT,
gpio::HIGH);
gpio = new GpiodRegularByLineName(q7s::gpioNames::GYRO_3_L3G_CS, "GYRO_3_L3G", Direction::OUT,
Levels::HIGH);
gpioCookie->addGpio(gpioIds::GYRO_3_L3G_CS, gpio);
// Enable pins must be pulled low for regular operations
gpio = new GpiodRegularByLineName(q7s::gpioNames::GYRO_0_ENABLE, "GYRO_0_ENABLE", gpio::DIR_OUT,
gpio::LOW);
gpio = new GpiodRegularByLineName(q7s::gpioNames::GYRO_0_ENABLE, "GYRO_0_ENABLE", Direction::OUT,
Levels::LOW);
gpioCookie->addGpio(gpioIds::GYRO_0_ENABLE, gpio);
gpio = new GpiodRegularByLineName(q7s::gpioNames::GYRO_0_ENABLE, "GYRO_2_ENABLE", gpio::DIR_OUT,
gpio::LOW);
gpio = new GpiodRegularByLineName(q7s::gpioNames::GYRO_0_ENABLE, "GYRO_2_ENABLE", Direction::OUT,
Levels::LOW);
gpioCookie->addGpio(gpioIds::GYRO_2_ENABLE, gpio);
#endif
if (gpioIF != nullptr) {
@ -348,8 +715,27 @@ void SpiTestClass::acsInit() {
}
void SpiTestClass::setSpiSpeedAndMode(int spiFd, spi::SpiModes mode, uint32_t speed) {
int mode_test = SPI_MODE_3;
int retval = ioctl(spiFd, SPI_IOC_WR_MODE, &mode_test); // reinterpret_cast<uint8_t*>(&mode));
int modeUnix = 0;
switch (mode) {
case (spi::SpiModes::MODE_0): {
modeUnix = SPI_MODE_0;
break;
}
case (spi::SpiModes::MODE_1): {
modeUnix = SPI_MODE_1;
break;
}
case (spi::SpiModes::MODE_2): {
modeUnix = SPI_MODE_2;
break;
}
case (spi::SpiModes::MODE_3): {
modeUnix = SPI_MODE_3;
break;
}
}
int retval = ioctl(spiFd, SPI_IOC_WR_MODE, &modeUnix); // reinterpret_cast<uint8_t*>(&mode));
if (retval != 0) {
utility::handleIoctlError("SpiTestClass::performRm3100Test: Setting SPI mode failed!");
}
@ -361,7 +747,7 @@ void SpiTestClass::setSpiSpeedAndMode(int spiFd, spi::SpiModes mode, uint32_t sp
}
void SpiTestClass::writeRegister(int fd, gpioId_t chipSelect, uint8_t reg, uint8_t value) {
spiTransferStruct.len = 2;
spiTransferStruct[0].len = 2;
sendBuffer[0] = reg;
sendBuffer[1] = value;
@ -405,7 +791,7 @@ void SpiTestClass::writeMultipleRegisters(int fd, gpioId_t chipSelect, uint8_t r
sendBuffer[0] = reg;
std::memcpy(sendBuffer.data() + 1, values, len);
spiTransferStruct.len = len + 1;
spiTransferStruct[0].len = len + 1;
if (gpioIF != nullptr and chipSelect != gpio::NO_GPIO) {
gpioIF->pullLow(chipSelect);
@ -429,13 +815,19 @@ void SpiTestClass::readMultipleStmRegisters(int fd, gpioId_t chipSelect, uint8_t
readMultipleRegisters(fd, chipSelect, reg, reply, len);
}
void SpiTestClass::shiftOutZeros() { spiTransferStruct[0].tx_buf = 0; }
void SpiTestClass::setSendBuffer() {
spiTransferStruct[0].tx_buf = reinterpret_cast<__u64>(sendBuffer.data());
}
void SpiTestClass::readMultipleRegisters(int fd, gpioId_t chipSelect, uint8_t reg, uint8_t *reply,
size_t len) {
if (reply == nullptr) {
return;
}
spiTransferStruct.len = len + 1;
spiTransferStruct[0].len = len + 1;
sendBuffer[0] = reg | STM_READ_MASK;
for (uint8_t idx = 0; idx < len; idx++) {
@ -465,7 +857,7 @@ uint8_t SpiTestClass::readStmRegister(int fd, gpioId_t chipSelect, uint8_t reg,
}
uint8_t SpiTestClass::readRegister(int fd, gpioId_t chipSelect, uint8_t reg) {
spiTransferStruct.len = 2;
spiTransferStruct[0].len = 2;
sendBuffer[0] = reg;
sendBuffer[1] = 0;
@ -481,3 +873,28 @@ uint8_t SpiTestClass::readRegister(int fd, gpioId_t chipSelect, uint8_t reg) {
}
return recvBuffer[1];
}
ReturnValue_t SpiTestClass::transfer(int fd, gpioId_t chipSelect = gpio::NO_GPIO) {
int retval = 0;
ReturnValue_t result = HasReturnvaluesIF::RETURN_OK;
if (chipSelect != gpio::NO_GPIO) {
result = gpioIF->pullLow(chipSelect);
if (result != HasReturnvaluesIF::RETURN_OK) {
return result;
}
}
retval = ioctl(fd, SPI_IOC_MESSAGE(1), &spiTransferStruct);
if (retval < 0) {
utility::handleIoctlError("SpiTestClass::transfer: ioctl failed");
return HasReturnvaluesIF::RETURN_FAILED;
}
if (chipSelect != gpio::NO_GPIO) {
result = gpioIF->pullHigh(chipSelect);
if (result != HasReturnvaluesIF::RETURN_OK) {
return result;
}
}
return HasReturnvaluesIF::RETURN_OK;
}

View File

@ -6,21 +6,40 @@
#if defined(XIPHOS_Q7S)
#include "busConf.h"
#endif
#include <fsfw_hal/common/gpio/GpioIF.h>
#include <fsfw_hal/linux/spi/SpiCookie.h>
#include <test/testtasks/TestTask.h>
#include <vector>
#include "devices/gpioIds.h"
struct SusTestCfg {
SusTestCfg(bool doTest, gpioId_t gpioId) : gpioId(gpioId) {}
bool doTest = false;
const gpioId_t gpioId;
bool intConv = true;
bool extConv = false;
};
struct Max1227TestCfg {
bool testRadSensorExtConvWithDelay = false;
bool testRadSensorIntConv = false;
bool plPcduAdcExtConv = false;
bool plPcduAdcExtConvAsOne = false;
bool plPcduAdcIntConv = false;
bool vbatSwitch = true;
SusTestCfg testSus[12] = {
{false, gpioIds::CS_SUS_0}, {false, gpioIds::CS_SUS_1}, {false, gpioIds::CS_SUS_2},
{false, gpioIds::CS_SUS_3}, {false, gpioIds::CS_SUS_4}, {false, gpioIds::CS_SUS_5},
{false, gpioIds::CS_SUS_6}, {false, gpioIds::CS_SUS_7}, {false, gpioIds::CS_SUS_8},
{false, gpioIds::CS_SUS_9}, {false, gpioIds::CS_SUS_10}, {false, gpioIds::CS_SUS_11},
};
};
class SpiTestClass : public TestTask {
public:
enum TestModes {
NONE,
MGM_LIS3MDL,
MGM_RM3100,
GYRO_L3GD20H,
};
enum TestModes { NONE, MGM_LIS3MDL, MGM_RM3100, GYRO_L3GD20H, MAX1227 };
TestModes testMode;
@ -31,14 +50,18 @@ class SpiTestClass : public TestTask {
private:
GpioIF* gpioIF;
Max1227TestCfg adcCfg = {};
std::array<uint8_t, 128> recvBuffer;
std::array<uint8_t, 128> sendBuffer;
struct spi_ioc_transfer spiTransferStruct = {};
struct spi_ioc_transfer spiTransferStruct[6] = {};
void performRm3100Test(uint8_t mgmId);
void performLis3MdlTest(uint8_t lis3Id);
void performL3gTest(uint8_t l3gId);
void performOneShotMax1227Test();
void performPeriodicMax1227Test();
void performMax1227Test();
/* ACS board specific code which pulls all GPIOs high */
void acsInit();
@ -55,6 +78,7 @@ class SpiTestClass : public TestTask {
uint8_t gyro2AdisChipSelect = gpio::GYRO_2_BCM_PIN;
uint8_t gyro3L3gd20ChipSelect = gpio::GYRO_3_BCM_PIN;
#else
uint8_t mgm0Lis3mdlChipSelect = 0;
uint8_t mgm1Rm3100ChipSelect = 0;
uint8_t gyro0AdisResetLine = 0;
@ -69,6 +93,13 @@ class SpiTestClass : public TestTask {
static constexpr uint8_t RM3100_READ_MASK = STM_READ_MASK;
static constexpr uint8_t STM_AUTO_INCR_MASK = 0b0100'0000;
void shiftOutZeros();
void setSendBuffer();
void max1227RadSensorTest(int fd);
void max1227SusTest(int fd, SusTestCfg& cfg);
void max1227PlPcduTest(int fd);
void setSpiSpeedAndMode(int spiFd, spi::SpiModes mode, uint32_t speed);
void writeStmRegister(int fd, gpioId_t chipSelect, uint8_t reg, uint8_t value,
@ -78,6 +109,7 @@ class SpiTestClass : public TestTask {
void writeMultipleRegisters(int fd, gpioId_t chipSelect, uint8_t reg, uint8_t* values,
size_t len);
void writeRegister(int fd, gpioId_t chipSelect, uint8_t reg, uint8_t value);
ReturnValue_t transfer(int fd, gpioId_t chipSelect);
uint8_t readRm3100Register(int fd, gpioId_t chipSelect, uint8_t reg);
uint8_t readStmRegister(int fd, gpioId_t chipSelect, uint8_t reg, bool autoIncrement);

View File

@ -1,16 +1,11 @@
#include "UartTestClass.h"
#include <errno.h> // Error integer and strerror() function
#include <fcntl.h> // Contains file controls like O_RDWR
#include <fsfw/tasks/TaskFactory.h>
#if defined(RASPBERRY_PI)
#include "rpiConfig.h"
#elif defined(XIPHOS_Q7S)
#include "q7sConfig.h"
#endif
#include <errno.h> // Error integer and strerror() function
#include <fcntl.h> // Contains file controls like O_RDWR
#include <unistd.h> // write(), read(), close()
#include "OBSWConfig.h"
#include "fsfw/globalfunctions/CRC.h"
#include "fsfw/globalfunctions/DleEncoder.h"
#include "fsfw/globalfunctions/arrayprinter.h"
@ -42,7 +37,7 @@ ReturnValue_t UartTestClass::performPeriodicAction() {
}
void UartTestClass::gpsInit() {
#if RPI_TEST_GPS_DEVICE == 1
#if RPI_TEST_GPS_HANDLER == 1
int result = lwgps_init(&gpsData);
if (result == 0) {
sif::warning << "lwgps_init error: " << result << std::endl;
@ -90,7 +85,7 @@ void UartTestClass::gpsInit() {
}
void UartTestClass::gpsPeriodic() {
#if RPI_TEST_GPS_DEVICE == 1
#if RPI_TEST_GPS_HANDLER == 1
int bytesRead = 0;
do {
bytesRead = read(serialPort, reinterpret_cast<void*>(recBuf.data()),
@ -129,7 +124,7 @@ void UartTestClass::gpsPeriodic() {
void UartTestClass::scexInit() {
#if defined(RASPBERRY_PI)
std::string devname = "/dev/ttyUSB1";
std::string devname = "/dev/serial0";
#else
std::string devname = "/dev/ul-scex";
#endif
@ -156,6 +151,13 @@ void UartTestClass::scexInit() {
tty.c_cc[VTIME] = 1; // In units of 0.1 seconds
tty.c_cc[VMIN] = 255; // Read up to 255 bytes
// Q7S UART Lite has fixed baud rate. For other linux systems, set baud rate here.
#if !defined(XIPHOS_Q7S)
if (cfsetispeed(&tty, B57600) != 0) {
sif::warning << "UartTestClass::scexInit: Setting baud rate failed" << std::endl;
}
#endif
if (tcsetattr(serialPort, TCSANOW, &tty) != 0) {
sif::warning << "tcsetattr call failed with error [" << errno << ", " << strerror(errno)
<< std::endl;
@ -165,37 +167,12 @@ void UartTestClass::scexInit() {
}
void UartTestClass::scexPeriodic() {
auto dleEncoder = DleEncoder();
std::array<uint8_t, 128> tmpCmdBuf = {};
// Send ping command
tmpCmdBuf[0] = scex::CMD_PING;
// These two fields are the packet counter and the total packet count. Those are 1 and 1 for each
// telecommand so far
tmpCmdBuf[1] = 1;
tmpCmdBuf[2] = 1;
uint16_t userDataLen = 0;
tmpCmdBuf[3] = (userDataLen >> 8) & 0xff;
tmpCmdBuf[4] = userDataLen & 0xff;
uint16_t crc = CRC::crc16ccitt(tmpCmdBuf.data(), 5);
tmpCmdBuf[5] = (crc >> 8) & 0xff;
tmpCmdBuf[6] = crc & 0xff;
size_t encodedLen = 0;
ReturnValue_t result =
dleEncoder.encode(tmpCmdBuf.data(), 7, cmdBuf.data(), cmdBuf.size(), &encodedLen, true);
if (result != HasReturnvaluesIF::RETURN_OK) {
sif::warning << "UartTestClass::scexInit: Encoding failed" << std::endl;
sif::info << "UartTestClass::scexInit: Sending ping command to SCEX" << std::endl;
int result = prepareScexPing();
if (result != 0) {
return;
}
arrayprinter::print(cmdBuf.data(), 9);
};
size_t bytesWritten = write(serialPort, cmdBuf.data(), encodedLen);
if (bytesWritten != encodedLen) {
sif::warning << "Sending ping command to solar experiment failed" << std::endl;
}
TaskFactory::delayTask(20);
bytesWritten = write(serialPort, cmdBuf.data(), encodedLen);
if (bytesWritten != encodedLen) {
sif::warning << "Sending ping command to solar experiment failed" << std::endl;
}
@ -210,12 +187,35 @@ void UartTestClass::scexPeriodic() {
<< ", " << strerror(errno) << "]" << std::endl;
break;
} else if (bytesRead >= static_cast<int>(recBuf.size())) {
sif::debug << "UartTestClass::performPeriodicAction: "
"recv buffer might not be large enough"
sif::debug << "UartTestClass::performPeriodicAction: recv buffer might not be large enough"
<< std::endl;
} else if (bytesRead > 0) {
sif::info << "Received " << bytesRead << " from the Solar Cell Experiment:" << std::endl;
arrayprinter::print(recBuf.data(), bytesRead);
sif::info << "Received " << bytesRead
<< " bytes from the Solar Cell Experiment:" << std::endl;
arrayprinter::print(recBuf.data(), bytesRead, OutputType::HEX, false);
}
} while (bytesRead > 0);
}
int UartTestClass::prepareScexPing() {
std::array<uint8_t, 128> tmpCmdBuf = {};
// Send ping command
tmpCmdBuf[0] = scex::CMD_PING;
// These two fields are the packet counter and the total packet count. Those are 1 and 1 for each
// telecommand so far
tmpCmdBuf[1] = 1;
tmpCmdBuf[2] = 1;
uint16_t userDataLen = 0;
tmpCmdBuf[3] = (userDataLen >> 8) & 0xff;
tmpCmdBuf[4] = userDataLen & 0xff;
uint16_t crc = CRC::crc16ccitt(tmpCmdBuf.data(), 5);
tmpCmdBuf[5] = (crc >> 8) & 0xff;
tmpCmdBuf[6] = crc & 0xff;
ReturnValue_t result =
dleEncoder.encode(tmpCmdBuf.data(), 7, cmdBuf.data(), cmdBuf.size(), &encodedLen, true);
if (result != HasReturnvaluesIF::RETURN_OK) {
sif::warning << "UartTestClass::scexInit: Encoding failed" << std::endl;
return -1;
}
return 0;
}

View File

@ -1,6 +1,7 @@
#ifndef LINUX_BOARDTEST_UARTTESTCLASS_H_
#define LINUX_BOARDTEST_UARTTESTCLASS_H_
#include <fsfw/globalfunctions/DleEncoder.h>
#include <termios.h> // Contains POSIX terminal control definitions
#include <array>
@ -28,7 +29,10 @@ class UartTestClass : public TestTask {
void scexInit();
void scexPeriodic();
int prepareScexPing();
TestModes mode = TestModes::GPS;
DleEncoder dleEncoder = DleEncoder();
size_t encodedLen = 0;
lwgps_t gpsData = {};
struct termios tty = {};
int serialPort = 0;

View File

@ -1,4 +1,7 @@
target_sources(${OBSW_NAME} PRIVATE
SolarArrayDeploymentHandler.cpp
SusHandler.cpp
)
if(EIVE_BUILD_GPSD_GPS_HANDLER)
target_sources(${OBSW_NAME} PRIVATE
GPSHyperionLinuxController.cpp
)
endif()
add_subdirectory(startracker)

View File

@ -0,0 +1,177 @@
#include "GPSHyperionLinuxController.h"
#include "fsfw/datapool/PoolReadGuard.h"
#include "fsfw/timemanager/Clock.h"
#if FSFW_DEV_HYPERION_GPS_CREATE_NMEA_CSV == 1
#include <filesystem>
#include <fstream>
#endif
#include <cmath>
GPSHyperionLinuxController::GPSHyperionLinuxController(object_id_t objectId, object_id_t parentId,
bool debugHyperionGps)
: ExtendedControllerBase(objectId, objects::NO_OBJECT),
gpsSet(this),
myGpsmm(GPSD_SHARED_MEMORY, nullptr),
debugHyperionGps(debugHyperionGps) {}
GPSHyperionLinuxController::~GPSHyperionLinuxController() {}
void GPSHyperionLinuxController::performControlOperation() {
#ifdef FSFW_OSAL_LINUX
readGpsDataFromGpsd();
#endif
}
LocalPoolDataSetBase *GPSHyperionLinuxController::getDataSetHandle(sid_t sid) { return &gpsSet; }
ReturnValue_t GPSHyperionLinuxController::checkModeCommand(Mode_t mode, Submode_t submode,
uint32_t *msToReachTheMode) {
return HasReturnvaluesIF::RETURN_OK;
}
ReturnValue_t GPSHyperionLinuxController::executeAction(ActionId_t actionId,
MessageQueueId_t commandedBy,
const uint8_t *data, size_t size) {
switch (actionId) {
case (GpsHyperion::TRIGGER_RESET_PIN): {
if (resetCallback != nullptr) {
PoolReadGuard pg(&gpsSet);
// Set HK entries invalid
gpsSet.setValidity(false, true);
resetCallback(resetCallbackArgs);
return HasActionsIF::EXECUTION_FINISHED;
}
return DeviceHandlerIF::COMMAND_NOT_IMPLEMENTED;
}
}
return HasReturnvaluesIF::RETURN_OK;
}
ReturnValue_t GPSHyperionLinuxController::initializeLocalDataPool(
localpool::DataPool &localDataPoolMap, LocalDataPoolManager &poolManager) {
localDataPoolMap.emplace(GpsHyperion::ALTITUDE, new PoolEntry<double>({0.0}));
localDataPoolMap.emplace(GpsHyperion::LONGITUDE, new PoolEntry<double>({0.0}));
localDataPoolMap.emplace(GpsHyperion::LATITUDE, new PoolEntry<double>({0.0}));
localDataPoolMap.emplace(GpsHyperion::SPEED, new PoolEntry<double>({0.0}));
localDataPoolMap.emplace(GpsHyperion::YEAR, new PoolEntry<uint16_t>());
localDataPoolMap.emplace(GpsHyperion::MONTH, new PoolEntry<uint8_t>());
localDataPoolMap.emplace(GpsHyperion::DAY, new PoolEntry<uint8_t>());
localDataPoolMap.emplace(GpsHyperion::HOURS, new PoolEntry<uint8_t>());
localDataPoolMap.emplace(GpsHyperion::MINUTES, new PoolEntry<uint8_t>());
localDataPoolMap.emplace(GpsHyperion::SECONDS, new PoolEntry<uint8_t>());
localDataPoolMap.emplace(GpsHyperion::UNIX_SECONDS, new PoolEntry<uint32_t>());
localDataPoolMap.emplace(GpsHyperion::SATS_IN_USE, new PoolEntry<uint8_t>());
localDataPoolMap.emplace(GpsHyperion::SATS_IN_VIEW, new PoolEntry<uint8_t>());
localDataPoolMap.emplace(GpsHyperion::FIX_MODE, new PoolEntry<uint8_t>());
#if OBSW_ENABLE_PERIODIC_HK == 1
poolManager.subscribeForPeriodicPacket(gpsSet.getSid(), true, 2.0, false);
#endif
return HasReturnvaluesIF::RETURN_OK;
}
void GPSHyperionLinuxController::setResetPinTriggerFunction(gpioResetFunction_t resetCallback,
void *args) {
this->resetCallback = resetCallback;
resetCallbackArgs = args;
}
ReturnValue_t GPSHyperionLinuxController::initialize() {
ReturnValue_t result = ExtendedControllerBase::initialize();
if (result != HasReturnvaluesIF::RETURN_OK) {
return result;
}
return result;
}
ReturnValue_t GPSHyperionLinuxController::handleCommandMessage(CommandMessage *message) {
return ExtendedControllerBase::handleCommandMessage(message);
}
#ifdef FSFW_OSAL_LINUX
void GPSHyperionLinuxController::readGpsDataFromGpsd() {
// The data from the device will generally be read all at once. Therefore, we
// can set all field here
if (not myGpsmm.is_open()) {
// Opening failed
#if FSFW_VERBOSE_LEVEL >= 1
sif::warning << "GPSHyperionHandler::readGpsDataFromGpsd: Opening GPSMM failed" << std::endl;
#endif
}
gps_data_t *gps = nullptr;
gps = myGpsmm.read();
if (gps == nullptr) {
sif::warning << "GPSHyperionHandler::readGpsDataFromGpsd: Reading GPS data failed" << std::endl;
}
PoolReadGuard pg(&gpsSet);
if (pg.getReadResult() != HasReturnvaluesIF::RETURN_OK) {
#if FSFW_VERBOSE_LEVEL >= 1
sif::warning << "GPSHyperionHandler::readGpsDataFromGpsd: Reading dataset failed" << std::endl;
#endif
}
// 0: Not seen, 1: No fix, 2: 2D-Fix, 3: 3D-Fix
gpsSet.fixMode.value = gps->fix.mode;
if (gps->fix.mode == 0 or gps->fix.mode == 1) {
gpsSet.setValidity(false, true);
} else if (gps->satellites_used > 0) {
gpsSet.setValidity(true, true);
}
gpsSet.satInUse.value = gps->satellites_used;
gpsSet.satInView.value = gps->satellites_visible;
if (std::isfinite(gps->fix.latitude)) {
// Negative latitude -> South direction
gpsSet.latitude.value = gps->fix.latitude;
} else {
gpsSet.latitude.setValid(false);
}
if (std::isfinite(gps->fix.longitude)) {
// Negative longitude -> West direction
gpsSet.longitude.value = gps->fix.longitude;
} else {
gpsSet.longitude.setValid(false);
}
if (std::isfinite(gps->fix.altitude)) {
gpsSet.altitude.value = gps->fix.altitude;
} else {
gpsSet.altitude.setValid(false);
}
if (std::isfinite(gps->fix.speed)) {
gpsSet.speed.value = gps->fix.speed;
} else {
gpsSet.speed.setValid(false);
}
gpsSet.unixSeconds.value = gps->fix.time.tv_sec;
timeval time = {};
time.tv_sec = gpsSet.unixSeconds.value;
time.tv_usec = gps->fix.time.tv_nsec / 1000;
Clock::TimeOfDay_t timeOfDay = {};
Clock::convertTimevalToTimeOfDay(&time, &timeOfDay);
gpsSet.year = timeOfDay.year;
gpsSet.month = timeOfDay.month;
gpsSet.day = timeOfDay.day;
gpsSet.hours = timeOfDay.hour;
gpsSet.minutes = timeOfDay.minute;
gpsSet.seconds = timeOfDay.second;
if (debugHyperionGps) {
sif::info << "-- Hyperion GPS Data --" << std::endl;
time_t timeRaw = gps->fix.time.tv_sec;
std::tm *time = gmtime(&timeRaw);
std::cout << "Time: " << std::put_time(time, "%c %Z") << std::endl;
std::cout << "Visible satellites: " << gps->satellites_visible << std::endl;
std::cout << "Satellites used: " << gps->satellites_used << std::endl;
std::cout << "Fix (0:Not Seen|1:No Fix|2:2D|3:3D): " << gps->fix.mode << std::endl;
std::cout << "Latitude: " << gps->fix.latitude << std::endl;
std::cout << "Longitude: " << gps->fix.longitude << std::endl;
std::cout << "Altitude(MSL): " << gps->fix.altMSL << std::endl;
std::cout << "Speed(m/s): " << gps->fix.speed << std::endl;
}
}
#endif

View File

@ -0,0 +1,55 @@
#ifndef MISSION_DEVICES_GPSHYPERIONHANDLER_H_
#define MISSION_DEVICES_GPSHYPERIONHANDLER_H_
#include "fsfw/FSFW.h"
#include "fsfw/controller/ExtendedControllerBase.h"
#include "fsfw/devicehandlers/DeviceHandlerBase.h"
#include "mission/devices/devicedefinitions/GPSDefinitions.h"
#ifdef FSFW_OSAL_LINUX
#include <gps.h>
#include <libgpsmm.h>
#endif
/**
* @brief Device handler for the Hyperion HT-GPS200 device
* @details
* Flight manual:
* https://egit.irs.uni-stuttgart.de/redmine/projects/eive-flight-manual/wiki/Hyperion_HT-GPS200
* This device handler can only be used on Linux system where the gpsd daemon with shared memory
* export is running.
*/
class GPSHyperionLinuxController : public ExtendedControllerBase {
public:
GPSHyperionLinuxController(object_id_t objectId, object_id_t parentId,
bool debugHyperionGps = false);
virtual ~GPSHyperionLinuxController();
using gpioResetFunction_t = ReturnValue_t (*)(void* args);
void setResetPinTriggerFunction(gpioResetFunction_t resetCallback, void* args);
ReturnValue_t handleCommandMessage(CommandMessage* message) override;
void performControlOperation() override;
LocalPoolDataSetBase* getDataSetHandle(sid_t sid) override;
ReturnValue_t checkModeCommand(Mode_t mode, Submode_t submode,
uint32_t* msToReachTheMode) override;
ReturnValue_t executeAction(ActionId_t actionId, MessageQueueId_t commandedBy,
const uint8_t* data, size_t size) override;
ReturnValue_t initialize() override;
protected:
gpioResetFunction_t resetCallback = nullptr;
void* resetCallbackArgs = nullptr;
ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap,
LocalDataPoolManager& poolManager) override;
private:
GpsPrimaryDataset gpsSet;
gpsmm myGpsmm;
bool debugHyperionGps = false;
void readGpsDataFromGpsd();
};
#endif /* MISSION_DEVICES_GPSHYPERIONHANDLER_H_ */

View File

@ -1,209 +0,0 @@
#include "SolarArrayDeploymentHandler.h"
#include <devices/gpioIds.h>
#include <devices/powerSwitcherList.h>
#include <fsfw/ipc/QueueFactory.h>
#include <fsfw/objectmanager/ObjectManager.h>
#include <fsfw_hal/common/gpio/GpioCookie.h>
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::instance()->get<GpioIF>(gpioDriverId);
if (gpioInterface == nullptr) {
sif::error << "SolarArrayDeploymentHandler::initialize: Invalid Gpio interface." << std::endl;
return ObjectManagerIF::CHILD_INIT_FAILED;
}
result = gpioInterface->addGpios(dynamic_cast<GpioCookie*>(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::instance()->get<PowerSwitchIF>(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(false, 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(false, 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(false, 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(true, 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();
}

View File

@ -1,156 +0,0 @@
#ifndef MISSION_DEVICES_SOLARARRAYDEPLOYMENT_H_
#define MISSION_DEVICES_SOLARARRAYDEPLOYMENT_H_
#include <fsfw/action/HasActionsIF.h>
#include <fsfw/devicehandlers/CookieIF.h>
#include <fsfw/devicehandlers/DeviceHandlerIF.h>
#include <fsfw/objectmanager/SystemObject.h>
#include <fsfw/power/PowerSwitchIF.h>
#include <fsfw/returnvalues/HasReturnvaluesIF.h>
#include <fsfw/tasks/ExecutableObjectIF.h>
#include <fsfw/timemanager/Countdown.h>
#include <fsfw_hal/common/gpio/GpioIF.h>
#include <unordered_map>
/**
* @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_ */

View File

@ -1,214 +0,0 @@
#include "SusHandler.h"
#include <fsfw/datapool/PoolReadGuard.h>
#include <fsfw_hal/linux/spi/SpiComIF.h>
#include "OBSWConfig.h"
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 OBSW_SWITCH_TO_NORMAL_MODE_AFTER_STARTUP == 1
setMode(MODE_NORMAL);
#else
setMode(_MODE_TO_ON);
#endif
}
void SusHandler::doShutDown() { setMode(_MODE_POWER_DOWN); }
ReturnValue_t SusHandler::buildNormalDeviceCommand(DeviceCommandId_t *id) {
if (communicationStep == CommunicationStep::IDLE) {
return NOTHING_TO_SEND;
}
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::IDLE;
}
return buildCommandFromCommand(*id, nullptr, 0);
}
ReturnValue_t SusHandler::buildTransitionDeviceCommand(DeviceCommandId_t *id) {
return HasReturnvaluesIF::RETURN_OK;
}
ReturnValue_t SusHandler::buildCommandFromCommand(DeviceCommandId_t deviceCommand,
const uint8_t *commandData,
size_t commandDataLen) {
switch (deviceCommand) {
case (SUS::WRITE_SETUP): {
/**
* 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 = 1;
return RETURN_OK;
}
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): {
std::memset(cmdBuffer, 0, sizeof(cmdBuffer));
rawPacket = cmdBuffer;
rawPacketLen = SUS::SIZE_READ_CONVERSIONS;
return RETURN_OK;
}
default:
return DeviceHandlerIF::COMMAND_NOT_IMPLEMENTED;
}
return HasReturnvaluesIF::RETURN_FAILED;
}
void SusHandler::fillCommandAndReplyMap() {
this->insertInCommandMap(SUS::WRITE_SETUP);
this->insertInCommandMap(SUS::START_CONVERSIONS);
this->insertInCommandAndReplyMap(SUS::READ_CONVERSIONS, 1, &dataset, SUS::SIZE_READ_CONVERSIONS);
}
ReturnValue_t SusHandler::scanForReply(const uint8_t *start, size_t remainingSize,
DeviceCommandId_t *foundId, size_t *foundLen) {
*foundId = this->getPendingCommand();
*foundLen = remainingSize;
return HasReturnvaluesIF::RETURN_OK;
}
ReturnValue_t SusHandler::interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) {
switch (id) {
case SUS::READ_CONVERSIONS: {
PoolReadGuard readSet(&dataset);
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 && OBSW_DEBUG_SUS
sif::info << "SUS object id 0x" << std::hex << this->getObjectId()
<< ", Temperature: " << dataset.temperatureCelcius << " °C" << 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: {
sif::debug << "SusHandler::interpretDeviceReply: Unknown reply id" << std::endl;
return DeviceHandlerIF::UNKNOWN_DEVICE_REPLY;
}
}
return HasReturnvaluesIF::RETURN_OK;
}
void SusHandler::setNormalDatapoolEntriesInvalid() {}
uint32_t SusHandler::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { return 1000; }
ReturnValue_t SusHandler::initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
LocalDataPoolManager &poolManager) {
localDataPoolMap.emplace(SUS::TEMPERATURE_C, new PoolEntry<float>({0.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

@ -1,73 +0,0 @@
#ifndef MISSION_DEVICES_SUSHANDLER_H_
#define MISSION_DEVICES_SUSHANDLER_H_
#include <fsfw/devicehandlers/DeviceHandlerBase.h>
#include <fsfw_hal/linux/gpio/LinuxLibgpioIF.h>
#include "devicedefinitions/SusDefinitions.h"
/**
* @brief This is the device handler class for the SUS sensor. The sensor is
* based on the MAX1227 ADC. Details about the SUS electronic can be found at
* https://egit.irs.uni-stuttgart.de/eive/eive_dokumente/src/branch/master/400_Raumsegment/443_SunSensorDocumentation/release
*
* @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,
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;
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:
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 { IDLE, WRITE_SETUP, START_CONVERSIONS, READ_CONVERSIONS };
LinuxLibgpioIF* gpioComIF = nullptr;
gpioId_t chipSelectId = gpio::NO_GPIO;
SUS::SusDataset dataset;
uint8_t cmdBuffer[SUS::MAX_CMD_SIZE];
CommunicationStep communicationStep = CommunicationStep::IDLE;
MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING;
uint32_t timeoutMs = 20;
MutexIF* spiMutex = nullptr;
};
#endif /* MISSION_DEVICES_SUSHANDLER_H_ */

File diff suppressed because it is too large Load Diff

View File

@ -1,89 +0,0 @@
#ifndef MISSION_DEVICES_DEVICEDEFINITIONS_SUS_H_
#define MISSION_DEVICES_DEVICEDEFINITIONS_SUS_H_
#include <fsfw/datapoollocal/StaticLocalDataSet.h>
#include <fsfw/devicehandlers/DeviceHandlerIF.h>
#include <cstdint>
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
static const DeviceCommandId_t WRITE_SETUP = 0x1;
/**
* 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): 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 = 0b01101000;
/**
* @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, 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 = 0b10101001;
static const uint8_t SUS_DATA_SET_ID = READ_CONVERSIONS;
/** 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,
AIN0,
AIN1,
AIN2,
AIN3,
AIN4,
AIN5,
};
class SusDataset : public StaticLocalDataSet<POOL_ENTRIES> {
public:
SusDataset(HasLocalDataPoolIF* owner) : StaticLocalDataSet(owner, SUS_DATA_SET_ID) {}
SusDataset(object_id_t objectId) : StaticLocalDataSet(sid_t(objectId, SUS_DATA_SET_ID)) {}
lp_var_t<float> temperatureCelcius = lp_var_t<float>(sid.objectId, TEMPERATURE_C, 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);
};
} // namespace SUS
#endif /* MISSION_DEVICES_DEVICEDEFINITIONS_SUS_H_ */

View File

@ -0,0 +1,62 @@
#include "ArcsecDatalinkLayer.h"
ArcsecDatalinkLayer::ArcsecDatalinkLayer() { slipInit(); }
ArcsecDatalinkLayer::~ArcsecDatalinkLayer() {}
void ArcsecDatalinkLayer::slipInit() {
slipInfo.buffer = rxBuffer;
slipInfo.maxlength = startracker::MAX_FRAME_SIZE;
slipInfo.length = 0;
slipInfo.unescape_next = 0;
slipInfo.prev_state = SLIP_COMPLETE;
}
ReturnValue_t ArcsecDatalinkLayer::decodeFrame(const uint8_t* rawData, size_t rawDataSize,
size_t* bytesLeft) {
size_t bytePos = 0;
for (bytePos = 0; bytePos < rawDataSize; bytePos++) {
enum arc_dec_result decResult =
arc_transport_decode_body(*(rawData + bytePos), &slipInfo, decodedFrame, &decFrameSize);
*bytesLeft = rawDataSize - bytePos - 1;
switch (decResult) {
case ARC_DEC_INPROGRESS: {
if (bytePos == rawDataSize - 1) {
return DEC_IN_PROGRESS;
}
continue;
}
case ARC_DEC_ERROR_FRAME_SHORT:
return REPLY_TOO_SHORT;
case ARC_DEC_ERROR_CHECKSUM:
return CRC_FAILURE;
case ARC_DEC_ASYNC:
case ARC_DEC_SYNC: {
// Reset length of SLIP struct for next frame
slipInfo.length = 0;
return RETURN_OK;
}
default:
sif::debug << "ArcsecDatalinkLayer::decodeFrame: Unknown result code" << std::endl;
break;
return RETURN_FAILED;
}
}
return RETURN_FAILED;
}
uint8_t ArcsecDatalinkLayer::getReplyFrameType() { return decodedFrame[0]; }
const uint8_t* ArcsecDatalinkLayer::getReply() { return &decodedFrame[1]; }
void ArcsecDatalinkLayer::encodeFrame(const uint8_t* data, uint32_t length) {
arc_transport_encode_body(data, length, encBuffer, &encFrameSize);
}
uint8_t* ArcsecDatalinkLayer::getEncodedFrame() { return encBuffer; }
uint32_t ArcsecDatalinkLayer::getEncodedLength() { return encFrameSize; }
uint8_t ArcsecDatalinkLayer::getStatusField() { return *(decodedFrame + STATUS_OFFSET); }
uint8_t ArcsecDatalinkLayer::getId() { return *(decodedFrame + ID_OFFSET); }

View File

@ -0,0 +1,98 @@
#ifndef BSP_Q7S_DEVICES_ARCSECDATALINKLAYER_H_
#define BSP_Q7S_DEVICES_ARCSECDATALINKLAYER_H_
#include "fsfw/returnvalues/HasReturnvaluesIF.h"
#include "linux/devices/devicedefinitions/StarTrackerDefinitions.h"
extern "C" {
#include "common/misc.h"
}
/**
* @brief Helper class to handle the datalinklayer of replies from the star tracker of arcsec.
*/
class ArcsecDatalinkLayer : public HasReturnvaluesIF {
public:
static const uint8_t INTERFACE_ID = CLASS_ID::STR_HANDLER;
//! [EXPORT] : [COMMENT] More data required to complete frame
static const ReturnValue_t DEC_IN_PROGRESS = MAKE_RETURN_CODE(0xA0);
//! [EXPORT] : [COMMENT] Data too short to represent a valid frame
static const ReturnValue_t REPLY_TOO_SHORT = MAKE_RETURN_CODE(0xA1);
//! [EXPORT] : [COMMENT] Detected CRC failure in received frame
static const ReturnValue_t CRC_FAILURE = MAKE_RETURN_CODE(0xA2);
static const uint8_t STATUS_OK = 0;
ArcsecDatalinkLayer();
virtual ~ArcsecDatalinkLayer();
/**
* @brief Applies decoding to data referenced by rawData pointer
*
* @param rawData Pointer to raw data received from star tracker
* @param rawDataSize Size of raw data stream
* @param remainingBytes Number of bytes left
*/
ReturnValue_t decodeFrame(const uint8_t* rawData, size_t rawDataSize, size_t* bytesLeft);
/**
* @brief SLIP encodes data pointed to by data pointer.
*
* @param data Pointer to data to encode
* @param length Length of buffer to encode
*/
void encodeFrame(const uint8_t* data, uint32_t length);
/**
* @brief Returns the frame type field of a decoded frame.
*/
uint8_t getReplyFrameType();
/**
* @brief Returns pointer to reply packet (first entry normally action ID, telemetry ID etc.)
*/
const uint8_t* getReply();
/**
* @brief Returns size of encoded frame
*/
uint32_t getEncodedLength();
/**
* @brief Returns pointer to encoded frame
*/
uint8_t* getEncodedFrame();
/**
* @brief Returns status of reply
*/
uint8_t getStatusField();
/**
* @brief Returns ID of reply
*/
uint8_t getId();
private:
static const uint8_t ID_OFFSET = 1;
static const uint8_t STATUS_OFFSET = 2;
// Used by arcsec slip decoding function process received data
uint8_t rxBuffer[startracker::MAX_FRAME_SIZE];
// Decoded frame will be copied to this buffer
uint8_t decodedFrame[startracker::MAX_FRAME_SIZE];
// Buffer where encoded frames will be stored. First byte of encoded frame represents type of
// reply
uint8_t encBuffer[startracker::MAX_FRAME_SIZE * 2 + 2];
// Size of decoded frame
uint32_t decFrameSize = 0;
// Size of encoded frame
uint32_t encFrameSize = 0;
slip_decode_state slipInfo;
void slipInit();
};
#endif /* BSP_Q7S_DEVICES_ARCSECDATALINKLAYER_H_ */

View File

@ -0,0 +1,181 @@
#ifndef BSP_Q7S_DEVICES_DEVICEDEFINITIONS_ARCSECJSONKEYS_H_
#define BSP_Q7S_DEVICES_DEVICEDEFINITIONS_ARCSECJSONKEYS_H_
/**
* @brief Keys used in JSON file of ARCSEC.
*/
namespace arcseckeys {
static const char PROPERTIES[] = "properties";
static const char NAME[] = "name";
static const char VALUE[] = "value";
static const char LIMITS[] = "limits";
static const char ACTION[] = "action";
static const char FPGA18CURRENT[] = "FPGA18Current";
static const char FPGA25CURRENT[] = "FPGA25Current";
static const char FPGA10CURRENT[] = "FPGA10Current";
static const char MCUCURRENT[] = "MCUCurrent";
static const char CMOS21CURRENT[] = "CMOS21Current";
static const char CMOSPIXCURRENT[] = "CMOSPixCurrent";
static const char CMOS33CURRENT[] = "CMOS33Current";
static const char CMOSVRESCURRENT[] = "CMOSVResCurrent";
static const char CMOS_TEMPERATURE[] = "CMOSTemperature";
static const char MCU_TEMPERATURE[] = "MCUTemperature";
static const char MOUNTING[] = "mounting";
static const char qw[] = "qw";
static const char qx[] = "qx";
static const char qy[] = "qy";
static const char qz[] = "qz";
static const char IMAGE_PROCESSOR[] = "imageprocessor";
static const char IMAGE_PROCESSOR_MODE[] = "mode";
static const char STORE[] = "store";
static const char SIGNAL_THRESHOLD[] = "signalThreshold";
static const char IMAGE_PROCESSOR_DARK_THRESHOLD[] = "darkThreshold";
static const char BACKGROUND_COMPENSATION[] = "backgroundcompensation";
static const char CAMERA[] = "camera";
static const char MODE[] = "mode";
static const char FOCALLENGTH[] = "focallength";
static const char EXPOSURE[] = "exposure";
static const char INTERVAL[] = "interval";
static const char OFFSET[] = "offset";
static const char PGAGAIN[] = "PGAGain";
static const char ADCGAIN[] = "ADCGain";
static const char REG_1[] = "reg1";
static const char VAL_1[] = "val1";
static const char REG_2[] = "reg2";
static const char VAL_2[] = "val2";
static const char REG_3[] = "reg3";
static const char VAL_3[] = "val3";
static const char REG_4[] = "reg4";
static const char VAL_4[] = "val4";
static const char REG_5[] = "reg5";
static const char VAL_5[] = "val5";
static const char REG_6[] = "reg6";
static const char VAL_6[] = "val6";
static const char REG_7[] = "reg7";
static const char VAL_7[] = "val7";
static const char REG_8[] = "reg8";
static const char VAL_8[] = "val8";
static const char FREQ_1[] = "freq1";
static const char BLOB[] = "blob";
static const char MIN_VALUE[] = "minValue";
static const char MIN_DISTANCE[] = "minDistance";
static const char NEIGHBOUR_DISTANCE[] = "neighbourDistance";
static const char NEIGHBOUR_BRIGHT_PIXELS[] = "neighbourBrightPixels";
static const char MIN_TOTAL_VALUE[] = "minTotalValue";
static const char MAX_TOTAL_VALUE[] = "maxTotalValue";
static const char MIN_BRIGHT_NEIGHBOURS[] = "minBrightNeighbours";
static const char MAX_BRIGHT_NEIGHBOURS[] = "maxBrightNeighbours";
static const char MAX_PIXEL_TO_CONSIDER[] = "maxPixelsToConsider";
// static const char SIGNAL_THRESHOLD[] = "signalThreshold";
static const char BLOB_DARK_THRESHOLD[] = "darkThreshold";
static const char ENABLE_HISTOGRAM[] = "enableHistogram";
static const char ENABLE_CONTRAST[] = "enableContrast";
static const char BIN_MODE[] = "binMode";
static const char CENTROIDING[] = "centroiding";
static const char ENABLE_FILTER[] = "enableFilter";
static const char MAX_QUALITY[] = "maxquality";
static const char DARK_THRESHOLD[] = "darkthreshold";
static const char MIN_QUALITY[] = "minquality";
static const char MAX_INTENSITY[] = "maxintensity";
static const char MIN_INTENSITY[] = "minintensity";
static const char MAX_MAGNITUDE[] = "maxmagnitude";
static const char GAUSSIAN_CMAX[] = "gaussianCmax";
static const char GAUSSIAN_CMIN[] = "gaussianCmin";
static const char TRANSMATRIX_00[] = "transmatrix00";
static const char TRANSMATRIX_01[] = "transmatrix01";
static const char TRANSMATRIX_10[] = "transmatrix10";
static const char TRANSMATRIX_11[] = "transmatrix11";
static const char LISA[] = "lisa";
static const char LISA_MODE[] = "mode";
static const char PREFILTER_DIST_THRESHOLD[] = "prefilterDistThreshold";
static const char PREFILTER_ANGLE_THRESHOLD[] = "prefilterAngleThreshold";
static const char FOV_WIDTH[] = "fov_width";
static const char FOV_HEIGHT[] = "fov_height";
static const char FLOAT_STAR_LIMIT[] = "float_star_limit";
static const char CLOSE_STAR_LIMIT[] = "close_star_limit";
static const char RATING_WEIGHT_CLOSE_STAR_COUNT[] = "rating_weight_close_star_count";
static const char RATING_WEIGHT_FRACTION_CLOSE[] = "rating_weight_fraction_close";
static const char RATING_WEIGHT_MEAN_SUM[] = "rating_weight_mean_sum";
static const char RATING_WEIGHT_DB_STAR_COUNT[] = "rating_weight_db_star_count";
static const char MAX_COMBINATIONS[] = "max_combinations";
static const char NR_STARS_STOP[] = "nr_stars_stop";
static const char FRACTION_CLOSE_STOP[] = "fraction_close_stop";
static const char MATCHING[] = "matching";
static const char SQUARED_DISTANCE_LIMIT[] = "squaredDistanceLimit";
static const char SQUARED_SHIFT_LIMIT[] = "squaredShiftLimit";
static const char VALIDATION[] = "validation";
static const char STABLE_COUNT[] = "stable_count";
static const char MAX_DIFFERENCE[] = "max_difference";
static const char MIN_TRACKER_CONFIDENCE[] = "min_trackerConfidence";
static const char MIN_MATCHED_STARS[] = "min_matchedStars";
static const char TRACKING[] = "tracking";
static const char THIN_LIMIT[] = "thinLimit";
static const char OUTLIER_THRESHOLD[] = "outlierThreshold";
static const char OUTLIER_THRESHOLD_QUEST[] = "outlierThresholdQUEST";
static const char TRACKER_CHOICE[] = "trackerChoice";
static const char ALGO[] = "algo";
static const char L2T_MIN_CONFIDENCE[] = "l2t_minConfidence";
static const char L2T_MIN_MATCHED[] = "l2t_minMatched";
static const char T2L_MIN_CONFIDENCE[] = "t2l_minConfidence";
static const char T2L_MIN_MATCHED[] = "t2l_minMatched";
static const char LOGLEVEL[] = "loglevel";
static const char LOGLEVEL1[] = "loglevel1";
static const char LOGLEVEL2[] = "loglevel2";
static const char LOGLEVEL3[] = "loglevel3";
static const char LOGLEVEL4[] = "loglevel4";
static const char LOGLEVEL5[] = "loglevel5";
static const char LOGLEVEL6[] = "loglevel6";
static const char LOGLEVEL7[] = "loglevel7";
static const char LOGLEVEL8[] = "loglevel8";
static const char LOGLEVEL9[] = "loglevel9";
static const char LOGLEVEL10[] = "loglevel10";
static const char LOGLEVEL11[] = "loglevel11";
static const char LOGLEVEL12[] = "loglevel12";
static const char LOGLEVEL13[] = "loglevel13";
static const char LOGLEVEL14[] = "loglevel14";
static const char LOGLEVEL15[] = "loglevel15";
static const char LOGLEVEL16[] = "loglevel16";
static const char SUBSCRIPTION[] = "subscription";
static const char TELEMETRY_1[] = "telemetry1";
static const char TELEMETRY_2[] = "telemetry2";
static const char TELEMETRY_3[] = "telemetry3";
static const char TELEMETRY_4[] = "telemetry4";
static const char TELEMETRY_5[] = "telemetry5";
static const char TELEMETRY_6[] = "telemetry6";
static const char TELEMETRY_7[] = "telemetry7";
static const char TELEMETRY_8[] = "telemetry8";
static const char TELEMETRY_9[] = "telemetry9";
static const char TELEMETRY_10[] = "telemetry10";
static const char TELEMETRY_11[] = "telemetry11";
static const char TELEMETRY_12[] = "telemetry12";
static const char TELEMETRY_13[] = "telemetry13";
static const char TELEMETRY_14[] = "telemetry14";
static const char TELEMETRY_15[] = "telemetry15";
static const char TELEMETRY_16[] = "telemetry16";
static const char LOG_SUBSCRIPTION[] = "logsubscription";
static const char LEVEL1[] = "level1";
static const char MODULE1[] = "module1";
static const char LEVEL2[] = "level2";
static const char MODULE2[] = "module2";
static const char DEBUG_CAMERA[] = "debugcamera";
static const char TIMING[] = "timing";
static const char TEST[] = "test";
} // namespace arcseckeys
#endif /* BSP_Q7S_DEVICES_DEVICEDEFINITIONS_ARCSECJSONKEYS_H_ */

View File

@ -0,0 +1,103 @@
#include "ArcsecJsonParamBase.h"
#include "ArcsecJsonKeys.h"
ArcsecJsonParamBase::ArcsecJsonParamBase(std::string setName) : setName(setName) {}
ReturnValue_t ArcsecJsonParamBase::create(std::string fullname, uint8_t* buffer) {
ReturnValue_t result = RETURN_OK;
result = init(fullname);
if (result != RETURN_OK) {
sif::warning << "ArcsecJsonParamBase::create: Failed to init parameter command for set "
<< setName << std::endl;
return result;
}
result = createCommand(buffer);
if (result != RETURN_OK) {
sif::warning << "ArcsecJsonParamBase::create: Failed to create parameter command for set "
<< setName << std::endl;
}
return result;
}
ReturnValue_t ArcsecJsonParamBase::getParam(const std::string name, std::string& value) {
for (json::iterator it = set.begin(); it != set.end(); ++it) {
if ((*it)[arcseckeys::NAME] == name) {
value = (*it)[arcseckeys::VALUE];
convertEmpty(value);
return RETURN_OK;
}
}
return PARAM_NOT_EXISTS;
}
void ArcsecJsonParamBase::convertEmpty(std::string& value) {
if (value == "") {
value = "0";
}
}
void ArcsecJsonParamBase::addfloat(const std::string value, uint8_t* buffer) {
float param = std::stof(value);
std::memcpy(buffer, &param, sizeof(param));
}
void ArcsecJsonParamBase::adduint8(const std::string value, uint8_t* buffer) {
uint8_t param = std::stoi(value);
std::memcpy(buffer, &param, sizeof(param));
}
void ArcsecJsonParamBase::addint16(const std::string value, uint8_t* buffer) {
int16_t param = std::stoi(value);
std::memcpy(buffer, &param, sizeof(param));
}
void ArcsecJsonParamBase::adduint16(const std::string value, uint8_t* buffer) {
uint16_t param = std::stoi(value);
std::memcpy(buffer, &param, sizeof(param));
}
void ArcsecJsonParamBase::adduint32(const std::string value, uint8_t* buffer) {
uint32_t param = std::stoi(value);
std::memcpy(buffer, &param, sizeof(param));
}
void ArcsecJsonParamBase::addSetParamHeader(uint8_t* buffer, uint8_t setId) {
*buffer = static_cast<uint8_t>(TMTC_SETPARAMREQ);
*(buffer + 1) = setId;
}
ReturnValue_t ArcsecJsonParamBase::init(const std::string filename) {
ReturnValue_t result = RETURN_OK;
if (not std::filesystem::exists(filename)) {
sif::warning << "ArcsecJsonParamBase::init: JSON file " << filename << " does not exist"
<< std::endl;
return JSON_FILE_NOT_EXISTS;
}
createJsonObject(filename);
result = initSet();
if (result != RETURN_OK) {
return result;
}
return RETURN_OK;
}
void ArcsecJsonParamBase::createJsonObject(const std::string fullname) {
json j;
std::ifstream file(fullname);
file >> j;
file.close();
properties = j[arcseckeys::PROPERTIES];
}
ReturnValue_t ArcsecJsonParamBase::initSet() {
for (json::iterator it = properties.begin(); it != properties.end(); ++it) {
if ((*it)["name"] == setName) {
set = (*it)["fields"];
return RETURN_OK;
}
}
sif::warning << "ArcsecJsonParamBase::initSet: Set " << setName << "not present in json file"
<< std::endl;
return SET_NOT_EXISTS;
}

View File

@ -0,0 +1,146 @@
#ifndef BSP_Q7S_DEVICES_STARTRACKER_ARCSECJSONPARAMBASE_H_
#define BSP_Q7S_DEVICES_STARTRACKER_ARCSECJSONPARAMBASE_H_
#include <filesystem>
#include <fstream>
#include <nlohmann/json.hpp>
#include "fsfw/returnvalues/HasReturnvaluesIF.h"
#include "linux/devices/devicedefinitions/StarTrackerDefinitions.h"
extern "C" {
#include "thirdparty/arcsec_star_tracker/common/generated/tmtcstructs.h"
#include "thirdparty/arcsec_star_tracker/common/genericstructs.h"
}
using json = nlohmann::json;
/**
* @brief Base class for creation of parameter configuration commands. Reads parameter set
* from a json file located on the filesystem and generates the appropriate command
* to apply the parameters to the star tracker software.
*
* @author J. Meier
*/
class ArcsecJsonParamBase : public HasReturnvaluesIF {
public:
static const uint8_t INTERFACE_ID = CLASS_ID::ARCSEC_JSON_BASE;
//! [EXPORT] : [COMMENT] Specified json file does not exist
static const ReturnValue_t JSON_FILE_NOT_EXISTS = MAKE_RETURN_CODE(1);
//! [EXPORT] : [COMMENT] Requested set does not exist in json file
static const ReturnValue_t SET_NOT_EXISTS = MAKE_RETURN_CODE(2);
//! [EXPORT] : [COMMENT] Requested parameter does not exist in json file
static const ReturnValue_t PARAM_NOT_EXISTS = MAKE_RETURN_CODE(3);
/**
* @brief Constructor
*
* @param fullname Name with absolute path of json file containing the parameters to set.
*/
ArcsecJsonParamBase(std::string setName);
/**
* @brief Fills a buffer with a parameter set
*
* @param fullname The name including the absolute path of the json file containing the
* parameter set.
* @param buffer Pointer to the buffer the command will be written to
*/
ReturnValue_t create(std::string fullname, uint8_t* buffer);
/**
* @brief Returns the size of the parameter command.
*/
virtual size_t getSize() = 0;
protected:
/**
* @brief Reads the value of a parameter from a json set
*
* @param name The name of the parameter
* @param value The string representation of the read value
*
* @return RETURN_OK if successful, otherwise PARAM_NOT_EXISTS
*/
ReturnValue_t getParam(const std::string name, std::string& value);
/**
* @brief Converts empty string which is equal to define a value as zero.
*/
void convertEmpty(std::string& value);
/**
* @brief This function adds a float represented as string to a buffer
*
* @param value The float in string representation to add
* @param buffer Pointer to the buffer the float will be written to
*/
void addfloat(const std::string value, uint8_t* buffer);
/**
* @brief This function adds a uint8_t represented as string to a buffer
*
* @param value The uint8_t in string representation to add
* @param buffer Pointer to the buffer the uint8_t will be written to
*/
void adduint8(const std::string value, uint8_t* buffer);
/**
* @brief This function adds a int16_t represented as string to a buffer
*
* @param value The int16_t in string representation to add
* @param buffer Pointer to the buffer the int16_t will be written to
*/
void addint16(const std::string value, uint8_t* buffer);
/**
* @brief This function adds a uint16_t represented as string to a buffer
*
* @param value The uint16_t in string representation to add
* @param buffer Pointer to the buffer the uint16_t will be written to
*/
void adduint16(const std::string value, uint8_t* buffer);
/**
* @brief This function adds a uint32_t represented as string to a buffer
*
* @param value The uint32_t in string representation to add
* @param buffer Pointer to the buffer the uint32_t will be written to
*/
void adduint32(const std::string value, uint8_t* buffer);
void addSetParamHeader(uint8_t* buffer, uint8_t setId);
private:
json properties;
json set;
std::string setName;
/**
* @brief This function must be implemented by the derived class to define creation of a
* parameter command.
*/
virtual ReturnValue_t createCommand(uint8_t* buffer) = 0;
/**
* @brief Initializes the properties json object and the set json object
*
* @param fullname Name including absolute path to json file
* @param setName The name of the set to work on
*
* @param return JSON_FILE_NOT_EXISTS if specified file does not exist, otherwise
* RETURN_OK
*/
ReturnValue_t init(const std::string filename);
void createJsonObject(const std::string fullname);
/**
* @brief Extracts the json set object form the json file
*
* @param setName The name of the set to create the json object from
*/
ReturnValue_t initSet();
};
#endif /* BSP_Q7S_DEVICES_STARTRACKER_ARCSECJSONPARAMBASE_H_ */

View File

@ -0,0 +1,7 @@
target_sources(${OBSW_NAME} PRIVATE
StarTrackerHandler.cpp
StarTrackerJsonCommands.cpp
ArcsecDatalinkLayer.cpp
ArcsecJsonParamBase.cpp
StrHelper.cpp
)

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,474 @@
#ifndef MISSION_DEVICES_STARTRACKERHANDLER_H_
#define MISSION_DEVICES_STARTRACKERHANDLER_H_
#include <fsfw/datapool/PoolReadGuard.h>
#include "ArcsecDatalinkLayer.h"
#include "ArcsecJsonParamBase.h"
#include "OBSWConfig.h"
#include "StrHelper.h"
#include "fsfw/devicehandlers/DeviceHandlerBase.h"
#include "fsfw/src/fsfw/serialize/SerializeAdapter.h"
#include "fsfw/timemanager/Countdown.h"
#include "linux/devices/devicedefinitions/StarTrackerDefinitions.h"
#include "thirdparty/arcsec_star_tracker/common/SLIP.h"
/**
* @brief This is the device handler for the star tracker from arcsec.
*
* @details Datasheet: https://eive-cloud.irs.uni-stuttgart.de/index.php/apps/files/?dir=/EIVE_IRS/
* Arbeitsdaten/08_Used%20Components/ArcSec_KULeuven_Startracker/
* Sagitta%201.0%20Datapack&fileid=659181
* @author J. Meier
*/
class StarTrackerHandler : public DeviceHandlerBase {
public:
/**
* @brief Constructor
*
* @param objectId
* @param comIF
* @param comCookie
* @param gpioComIF Pointer to gpio communication interface
* @param enablePin GPIO connected to the enable pin of the reaction wheels. Must be pulled
* to high to enable the device.
*/
StarTrackerHandler(object_id_t objectId, object_id_t comIF, CookieIF* comCookie,
StrHelper* strHelper);
virtual ~StarTrackerHandler();
ReturnValue_t initialize() override;
/**
* @brief Overwrite this function from DHB to handle commands executed by the str image
* loader task.
*/
ReturnValue_t executeAction(ActionId_t actionId, MessageQueueId_t commandedBy,
const uint8_t* data, size_t size) override;
void performOperationHook() override;
Submode_t getInitialSubmode() override;
static const Submode_t SUBMODE_BOOTLOADER = 1;
static const Submode_t SUBMODE_FIRMWARE = 2;
protected:
void doStartUp() override;
void doShutDown() override;
void doOffActivity() 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 isModeCombinationValid(Mode_t mode, Submode_t submode) 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;
/**
* @brief Overwritten here to always read all available data from the UartComIF.
*/
virtual size_t getNextReplyLength(DeviceCommandId_t deviceCommand) override;
virtual ReturnValue_t doSendReadHook() override;
virtual void doTransition(Mode_t modeFrom, Submode_t subModeFrom) override;
private:
static const uint8_t INTERFACE_ID = CLASS_ID::STR_HANDLER;
//! [EXPORT] : [COMMENT] Status in temperature reply signals error
static const ReturnValue_t TEMPERATURE_REQ_FAILED = MAKE_RETURN_CODE(0xA0);
//! [EXPORT] : [COMMENT] Ping command failed
static const ReturnValue_t PING_FAILED = MAKE_RETURN_CODE(0xA1);
//! [EXPORT] : [COMMENT] Status in version reply signals error
static const ReturnValue_t VERSION_REQ_FAILED = MAKE_RETURN_CODE(0xA2);
//! [EXPORT] : [COMMENT] Status in interface reply signals error
static const ReturnValue_t INTERFACE_REQ_FAILED = MAKE_RETURN_CODE(0xA3);
//! [EXPORT] : [COMMENT] Status in power reply signals error
static const ReturnValue_t POWER_REQ_FAILED = MAKE_RETURN_CODE(0xA4);
//! [EXPORT] : [COMMENT] Status of reply to parameter set command signals error
static const ReturnValue_t SET_PARAM_FAILED = MAKE_RETURN_CODE(0xA5);
//! [EXPORT] : [COMMENT] Status of reply to action command signals error
static const ReturnValue_t ACTION_FAILED = MAKE_RETURN_CODE(0xA6);
//! [EXPORT] : [COMMENT] Received invalid path string. Exceeds allowed length
static const ReturnValue_t FILE_PATH_TOO_LONG = MAKE_RETURN_CODE(0xA7);
//! [EXPORT] : [COMMENT] Name of file received with command is too long
static const ReturnValue_t FILENAME_TOO_LONG = MAKE_RETURN_CODE(0xA8);
//! [EXPORT] : [COMMENT] Received version reply with invalid program ID
static const ReturnValue_t INVALID_PROGRAM = MAKE_RETURN_CODE(0xA9);
//! [EXPORT] : [COMMENT] Status field reply signals error
static const ReturnValue_t REPLY_ERROR = MAKE_RETURN_CODE(0xAA);
//! [EXPORT] : [COMMENT] Received command which is too short (some data is missing for proper
//! execution)
static const ReturnValue_t COMMAND_TOO_SHORT = MAKE_RETURN_CODE(0xAB);
//! [EXPORT] : [COMMENT] Received command with invalid length (too few or too many parameters)
static const ReturnValue_t INVALID_LENGTH = MAKE_RETURN_CODE(0xAC);
//! [EXPORT] : [COMMENT] Region mismatch between send and received data
static const ReturnValue_t REGION_MISMATCH = MAKE_RETURN_CODE(0xAD);
//! [EXPORT] : [COMMENT] Address mismatch between send and received data
static const ReturnValue_t ADDRESS_MISMATCH = MAKE_RETURN_CODE(0xAE);
//! [EXPORT] : [COMMENT] Length field mismatch between send and received data
static const ReturnValue_t lENGTH_MISMATCH = MAKE_RETURN_CODE(0xAF);
//! [EXPORT] : [COMMENT] Specified file does not exist
static const ReturnValue_t FILE_NOT_EXISTS = MAKE_RETURN_CODE(0xB0);
//! [EXPORT] : [COMMENT] Download blob pixel command has invalid type field
static const ReturnValue_t INVALID_TYPE = MAKE_RETURN_CODE(0xB1);
//! [EXPORT] : [COMMENT] Received FPGA action command with invalid ID
static const ReturnValue_t INVALID_ID = MAKE_RETURN_CODE(0xB2);
//! [EXPORT] : [COMMENT] Received reply is too short
static const ReturnValue_t REPLY_TOO_SHORT = MAKE_RETURN_CODE(0xB3);
//! [EXPORT] : [COMMENT] Received reply with invalid CRC
static const ReturnValue_t CRC_FAILURE = MAKE_RETURN_CODE(0xB4);
//! [EXPORT] : [COMMENT] Star tracker handler currently executing a command and using the
//! communication interface
static const ReturnValue_t STR_HELPER_EXECUTING = MAKE_RETURN_CODE(0xB5);
//! [EXPORT] : [COMMENT] Star tracker is already in firmware mode
static const ReturnValue_t STARTRACKER_ALREADY_BOOTED = MAKE_RETURN_CODE(0xB6);
//! [EXPORT] : [COMMENT] Star tracker is in firmware mode but must be in bootloader mode to
//! execute this command
static const ReturnValue_t STARTRACKER_RUNNING_FIRMWARE = MAKE_RETURN_CODE(0xB7);
//! [EXPORT] : [COMMENT] Star tracker is in bootloader mode but must be in firmware mode to
//! execute this command
static const ReturnValue_t STARTRACKER_RUNNING_BOOTLOADER = MAKE_RETURN_CODE(0xB8);
static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::STR_HANDLER;
//! [EXPORT] : [COMMENT] Failed to boot firmware
static const Event BOOTING_FIRMWARE_FAILED = MAKE_EVENT(1, severity::LOW);
//! [EXPORT] : [COMMENT] Failed to boot star tracker into bootloader mode
static const Event BOOTING_BOOTLOADER_FAILED = MAKE_EVENT(2, severity::LOW);
static const size_t MAX_PATH_SIZE = 50;
static const size_t MAX_FILE_NAME = 30;
static const uint8_t STATUS_OFFSET = 1;
static const uint8_t PARAMS_OFFSET = 1;
static const uint8_t TICKS_OFFSET = 2;
static const uint8_t TIME_OFFSET = 6;
static const uint8_t TM_DATA_FIELD_OFFSET = 14;
static const uint8_t PARAMETER_ID_OFFSET = 0;
static const uint8_t ACTION_ID_OFFSET = 0;
static const uint8_t ACTION_DATA_OFFSET = 2;
// Ping request will reply ping with this ID (data field)
static const uint32_t PING_ID = 0x55;
static const uint32_t BOOT_REGION_ID = 1;
static const MutexIF::TimeoutType TIMEOUT_TYPE = MutexIF::TimeoutType::WAITING;
static const uint32_t MUTEX_TIMEOUT = 20;
static const uint32_t BOOT_TIMEOUT = 1000;
static const uint32_t DEFAULT_TRANSITION_DELAY = 15000;
class FlashReadCmd {
public:
// Minimum length of a read command (region, length and filename)
static const size_t MIN_LENGTH = 7;
};
class ChecksumCmd {
public:
static const uint8_t ADDRESS_OFFSET = 1;
static const uint8_t LENGTH_OFFSET = 5;
// Length of checksum command
static const size_t LENGTH = 9;
uint8_t rememberRegion = 0;
uint32_t rememberAddress = 0;
uint32_t rememberLength = 0;
};
ChecksumCmd checksumCmd;
MessageQueueIF* eventQueue = nullptr;
ArcsecDatalinkLayer dataLinkLayer;
startracker::TemperatureSet temperatureSet;
startracker::VersionSet versionSet;
startracker::PowerSet powerSet;
startracker::InterfaceSet interfaceSet;
startracker::TimeSet timeSet;
startracker::SolutionSet solutionSet;
startracker::HistogramSet histogramSet;
startracker::ChecksumSet checksumSet;
startracker::CameraSet cameraSet;
startracker::LimitsSet limitsSet;
startracker::LogLevelSet loglevelSet;
startracker::MountingSet mountingSet;
startracker::ImageProcessorSet imageProcessorSet;
startracker::CentroidingSet centroidingSet;
startracker::LisaSet lisaSet;
startracker::MatchingSet matchingSet;
startracker::TrackingSet trackingSet;
startracker::ValidationSet validationSet;
startracker::AlgoSet algoSet;
startracker::SubscriptionSet subscriptionSet;
startracker::LogSubscriptionSet logSubscriptionSet;
startracker::DebugCameraSet debugCameraSet;
// Pointer to object responsible for uploading and downloading images to/from the star tracker
StrHelper* strHelper = nullptr;
uint8_t commandBuffer[startracker::MAX_FRAME_SIZE];
// Countdown to insert delay for star tracker to switch from bootloader to firmware program
// Loading firmware requires some time and the command will not trigger a reply when executed
Countdown bootCountdown;
#ifdef EGSE
std::string paramJsonFile = "/home/pi/arcsec/json/flight-config.json";
#else
#if OBSW_STAR_TRACKER_GROUND_CONFIG == 1
std::string paramJsonFile = "/mnt/sd0/startracker/ground-config.json";
#else
std::string paramJsonFile = "/mnt/sd0/startracker/flight-config.json";
#endif
#endif
enum class NormalState { TEMPERATURE_REQUEST, SOLUTION_REQUEST };
NormalState normalState = NormalState::TEMPERATURE_REQUEST;
enum class InternalState {
IDLE,
BOOT,
REQ_VERSION,
VERIFY_BOOT,
STARTUP_CHECK,
BOOT_DELAY,
FIRMWARE_CHECK,
LOGLEVEL,
LIMITS,
TRACKING,
MOUNTING,
IMAGE_PROCESSOR,
CAMERA,
BLOB,
CENTROIDING,
LISA,
MATCHING,
VALIDATION,
ALGO,
LOG_SUBSCRIPTION,
DEBUG_CAMERA,
WAIT_FOR_EXECUTION,
DONE,
FAILED_FIRMWARE_BOOT,
BOOT_BOOTLOADER,
BOOTLOADER_CHECK,
BOOTING_BOOTLOADER_FAILED
};
InternalState internalState = InternalState::IDLE;
enum class StartupState { IDLE, CHECK_PROGRAM, WAIT_CHECK_PROGRAM, BOOT_BOOTLOADER, DONE };
StartupState startupState = StartupState::IDLE;
bool strHelperExecuting = false;
/**
* @brief Handles internal state
*/
void handleInternalState();
/**
* @brief Checks mode for commands requiring MODE_ON of MODE_NORMAL for execution.
*
* @param actionId Action id of command to execute
*/
ReturnValue_t checkMode(ActionId_t actionId);
/**
* @brief This function initializes the serial link ip protocol struct slipInfo.
*/
void slipInit();
ReturnValue_t scanForActionReply(DeviceCommandId_t* foundId);
ReturnValue_t scanForSetParameterReply(DeviceCommandId_t* foundId);
ReturnValue_t scanForGetParameterReply(DeviceCommandId_t* foundId);
ReturnValue_t scanForTmReply(DeviceCommandId_t* foundId);
/**
* @brief Fills command buffer with data to ping the star tracker
*/
void preparePingRequest();
/**
* @brief Fills command buffer with data to request the time telemetry.
*/
void prepareTimeRequest();
/**
* @brief Handles all received event messages
*/
void handleEvent(EventMessage* eventMessage);
/**
* @brief Extracts information for flash-read-command from TC data and starts execution of
* flash-read-procedure
*
* @param commandData Pointer to received command data
* @param commandDataLen Size of received command data
*
* @return RETURN_OK if start of execution was successful, otherwise error return value
*/
ReturnValue_t executeFlashReadCommand(const uint8_t* commandData, size_t commandDataLen);
/**
* @brief Fills command buffer with data to boot image (works only when star tracker is
* in bootloader mode).
*/
void prepareBootCommand();
/**
* @brief Fills command buffer with command to get the checksum of a flash part
*/
ReturnValue_t prepareChecksumCommand(const uint8_t* commandData, size_t commandDataLen);
/**
* @brief Fills the command buffer with the command to take an image.
*/
void prepareTakeImageCommand(const uint8_t* commandData);
/**
* @brief Fills command buffer with data to request the version telemetry packet
*/
void prepareVersionRequest();
/**
* @brief Fills the command buffer with data to request the interface telemetry packet.
*/
void prepareInterfaceRequest();
/**
* @brief Fills the command buffer with data to request the power telemetry packet.
*/
void preparePowerRequest();
/**
* @brief Fills command buffer with data to reboot star tracker.
*/
void prepareSwitchToBootloaderCmd();
/**
* @brief Fills command buffer with data to subscribe to a telemetry packet.
*
* @param tmId The ID of the telemetry packet to subscribe to
*/
void prepareSubscriptionCommand(const uint8_t* tmId);
/**
* @brief Fills command buffer with data to request solution telemtry packet (contains
* attitude information)
*/
void prepareSolutionRequest();
/**
* @brief Fills command buffer with data to request temperature from star tracker
*/
void prepareTemperatureRequest();
/**
* @brief Fills command buffer with data to request histogram
*/
void prepareHistogramRequest();
/**
* @brief Reads parameters from json file specified by string in commandData and
* prepares the command to apply the parameter set to the star tracker
*
* @param commandData Contains string with file name
* @param commandDataLen Length of command
* @param paramSet The object defining the command generation
*
* @return RETURN_OK if successful, otherwise error return Value
*/
ReturnValue_t prepareParamCommand(const uint8_t* commandData, size_t commandDataLen,
ArcsecJsonParamBase& paramSet);
/**
* @brief The following function will fill the command buffer with the command to request
* a parameter set.
*/
ReturnValue_t prepareRequestCameraParams();
ReturnValue_t prepareRequestLimitsParams();
ReturnValue_t prepareRequestLogLevelParams();
ReturnValue_t prepareRequestMountingParams();
ReturnValue_t prepareRequestImageProcessorParams();
ReturnValue_t prepareRequestCentroidingParams();
ReturnValue_t prepareRequestLisaParams();
ReturnValue_t prepareRequestMatchingParams();
ReturnValue_t prepareRequestTrackingParams();
ReturnValue_t prepareRequestValidationParams();
ReturnValue_t prepareRequestAlgoParams();
ReturnValue_t prepareRequestSubscriptionParams();
ReturnValue_t prepareRequestLogSubscriptionParams();
ReturnValue_t prepareRequestDebugCameraParams();
/**
* @brief Handles action replies with datasets.
*/
ReturnValue_t handleActionReplySet(LocalPoolDataSetBase& dataset, size_t size);
/**
* @brief Default function to handle action replies
*/
ReturnValue_t handleActionReply();
/**
* @brief Handles reply to upload centroid command
*/
ReturnValue_t handleUploadCentroidReply();
/**
* @brief Handles reply to checksum command
*/
ReturnValue_t handleChecksumReply();
/**
* @brief Handles all set parameter replies
*/
ReturnValue_t handleSetParamReply();
ReturnValue_t handlePingReply();
ReturnValue_t handleParamRequest(LocalPoolDataSetBase& dataset, size_t size);
/**
* @brief Checks the loaded program by means of the version set
*/
ReturnValue_t checkProgram();
/**
* @brief Handles the startup state machine
*/
void handleStartup(const uint8_t* parameterId);
/**
* @brief Handles telemtry replies and fills the appropriate dataset
*
* @param dataset Dataset where reply data will be written to
* @param size Size of the dataset
*
* @return RETURN_OK if successful, otherwise error return value
*/
ReturnValue_t handleTm(LocalPoolDataSetBase& dataset, size_t size);
/**
* @brief Checks if star tracker is in valid mode for executing the received command.
*
* @param actioId Id of received command
*
* @return RETURN_OK if star tracker is in valid mode, otherwise error return value
*/
ReturnValue_t checkCommand(ActionId_t actionId);
void doOnTransition(Submode_t subModeFrom);
void doNormalTransition(Mode_t modeFrom, Submode_t subModeFrom);
void bootFirmware(Mode_t toMode);
void bootBootloader();
};
#endif /* MISSION_DEVICES_STARTRACKERHANDLER_H_ */

View File

@ -0,0 +1,917 @@
#include "StarTrackerJsonCommands.h"
#include "ArcsecJsonKeys.h"
Limits::Limits() : ArcsecJsonParamBase(arcseckeys::LIMITS) {}
size_t Limits::getSize() { return COMMAND_SIZE; }
ReturnValue_t Limits::createCommand(uint8_t* buffer) {
ReturnValue_t result = RETURN_OK;
uint8_t offset = 0;
std::string param;
addSetParamHeader(buffer, startracker::ID::LIMITS);
offset = 2;
result = getParam(arcseckeys::ACTION, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::FPGA18CURRENT, param);
if (result != RETURN_OK) {
return result;
}
addfloat(param, buffer + offset);
offset += sizeof(float);
result = getParam(arcseckeys::FPGA25CURRENT, param);
if (result != RETURN_OK) {
return result;
}
addfloat(param, buffer + offset);
offset += sizeof(float);
result = getParam(arcseckeys::FPGA10CURRENT, param);
if (result != RETURN_OK) {
return result;
}
addfloat(param, buffer + offset);
offset += sizeof(float);
result = getParam(arcseckeys::MCUCURRENT, param);
if (result != RETURN_OK) {
return result;
}
addfloat(param, buffer + offset);
offset += sizeof(float);
result = getParam(arcseckeys::CMOS21CURRENT, param);
if (result != RETURN_OK) {
return result;
}
addfloat(param, buffer + offset);
offset += sizeof(float);
result = getParam(arcseckeys::CMOSPIXCURRENT, param);
if (result != RETURN_OK) {
return result;
}
addfloat(param, buffer + offset);
offset += sizeof(float);
result = getParam(arcseckeys::CMOS33CURRENT, param);
if (result != RETURN_OK) {
return result;
}
addfloat(param, buffer + offset);
offset += sizeof(float);
result = getParam(arcseckeys::CMOSVRESCURRENT, param);
if (result != RETURN_OK) {
return result;
}
addfloat(param, buffer + offset);
offset += sizeof(float);
result = getParam(arcseckeys::CMOS_TEMPERATURE, param);
if (result != RETURN_OK) {
return result;
}
addfloat(param, buffer + offset);
offset += sizeof(float);
result = getParam(arcseckeys::MCU_TEMPERATURE, param);
if (result != RETURN_OK) {
return result;
}
addfloat(param, buffer + offset);
return RETURN_OK;
}
Tracking::Tracking() : ArcsecJsonParamBase(arcseckeys::TRACKING) {}
size_t Tracking::getSize() { return COMMAND_SIZE; }
ReturnValue_t Tracking::createCommand(uint8_t* buffer) {
ReturnValue_t result = RETURN_OK;
uint8_t offset = 0;
std::string param;
addSetParamHeader(buffer, startracker::ID::TRACKING);
offset = 2;
result = getParam(arcseckeys::THIN_LIMIT, param);
if (result != RETURN_OK) {
return result;
}
addfloat(param, buffer + offset);
offset += sizeof(float);
result = getParam(arcseckeys::OUTLIER_THRESHOLD, param);
if (result != RETURN_OK) {
return result;
}
addfloat(param, buffer + offset);
offset += sizeof(float);
result = getParam(arcseckeys::OUTLIER_THRESHOLD_QUEST, param);
if (result != RETURN_OK) {
return result;
}
addfloat(param, buffer + offset);
offset += sizeof(float);
result = getParam(arcseckeys::TRACKER_CHOICE, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
return RETURN_OK;
}
Mounting::Mounting() : ArcsecJsonParamBase(arcseckeys::MOUNTING) {}
size_t Mounting::getSize() { return COMMAND_SIZE; }
ReturnValue_t Mounting::createCommand(uint8_t* buffer) {
ReturnValue_t result = RETURN_OK;
uint8_t offset = 0;
std::string param;
addSetParamHeader(buffer, startracker::ID::MOUNTING);
offset = 2;
result = getParam(arcseckeys::qw, param);
if (result != RETURN_OK) {
return result;
}
addfloat(param, buffer + offset);
offset += sizeof(float);
result = getParam(arcseckeys::qx, param);
if (result != RETURN_OK) {
return result;
}
addfloat(param, buffer + offset);
offset += sizeof(float);
result = getParam(arcseckeys::qy, param);
if (result != RETURN_OK) {
return result;
}
addfloat(param, buffer + offset);
offset += sizeof(float);
result = getParam(arcseckeys::qz, param);
if (result != RETURN_OK) {
return result;
}
addfloat(param, buffer + offset);
return RETURN_OK;
}
ImageProcessor::ImageProcessor() : ArcsecJsonParamBase(arcseckeys::IMAGE_PROCESSOR) {}
size_t ImageProcessor::getSize() { return COMMAND_SIZE; }
ReturnValue_t ImageProcessor::createCommand(uint8_t* buffer) {
ReturnValue_t result = RETURN_OK;
uint8_t offset = 0;
std::string param;
addSetParamHeader(buffer, startracker::ID::IMAGE_PROCESSOR);
offset = 2;
result = getParam(arcseckeys::IMAGE_PROCESSOR_MODE, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::STORE, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::SIGNAL_THRESHOLD, param);
if (result != RETURN_OK) {
return result;
}
adduint16(param, buffer + offset);
offset += sizeof(uint16_t);
result = getParam(arcseckeys::IMAGE_PROCESSOR_DARK_THRESHOLD, param);
if (result != RETURN_OK) {
return result;
}
adduint16(param, buffer + offset);
offset += sizeof(uint16_t);
result = getParam(arcseckeys::BACKGROUND_COMPENSATION, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
return RETURN_OK;
}
Camera::Camera() : ArcsecJsonParamBase(arcseckeys::CAMERA) {}
size_t Camera::getSize() { return COMMAND_SIZE; }
ReturnValue_t Camera::createCommand(uint8_t* buffer) {
ReturnValue_t result = RETURN_OK;
uint8_t offset = 0;
std::string param;
addSetParamHeader(buffer, startracker::ID::CAMERA);
offset = 2;
result = getParam(arcseckeys::MODE, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::FOCALLENGTH, param);
if (result != RETURN_OK) {
return result;
}
addfloat(param, buffer + offset);
offset += sizeof(float);
result = getParam(arcseckeys::EXPOSURE, param);
if (result != RETURN_OK) {
return result;
}
addfloat(param, buffer + offset);
offset += sizeof(float);
result = getParam(arcseckeys::INTERVAL, param);
if (result != RETURN_OK) {
return result;
}
addfloat(param, buffer + offset);
offset += sizeof(float);
result = getParam(arcseckeys::OFFSET, param);
if (result != RETURN_OK) {
return result;
}
addint16(param, buffer + offset);
offset += sizeof(int16_t);
result = getParam(arcseckeys::PGAGAIN, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::ADCGAIN, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::REG_1, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::VAL_1, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::REG_2, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::VAL_2, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::REG_3, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::VAL_3, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::REG_4, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::VAL_4, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::REG_5, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::VAL_5, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::REG_6, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::VAL_6, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::REG_7, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::VAL_7, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::REG_8, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::VAL_8, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::FREQ_1, param);
if (result != RETURN_OK) {
return result;
}
adduint32(param, buffer + offset);
return RETURN_OK;
}
Centroiding::Centroiding() : ArcsecJsonParamBase(arcseckeys::CENTROIDING) {}
size_t Centroiding::getSize() { return COMMAND_SIZE; }
ReturnValue_t Centroiding::createCommand(uint8_t* buffer) {
ReturnValue_t result = RETURN_OK;
uint8_t offset = 0;
std::string param;
addSetParamHeader(buffer, startracker::ID::CENTROIDING);
offset = 2;
result = getParam(arcseckeys::ENABLE_FILTER, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::MAX_QUALITY, param);
if (result != RETURN_OK) {
return result;
}
addfloat(param, buffer + offset);
offset += sizeof(float);
result = getParam(arcseckeys::DARK_THRESHOLD, param);
if (result != RETURN_OK) {
return result;
}
addfloat(param, buffer + offset);
offset += sizeof(float);
result = getParam(arcseckeys::MIN_QUALITY, param);
if (result != RETURN_OK) {
return result;
}
addfloat(param, buffer + offset);
offset += sizeof(float);
result = getParam(arcseckeys::MAX_INTENSITY, param);
if (result != RETURN_OK) {
return result;
}
addfloat(param, buffer + offset);
offset += sizeof(float);
result = getParam(arcseckeys::MIN_INTENSITY, param);
if (result != RETURN_OK) {
return result;
}
addfloat(param, buffer + offset);
offset += sizeof(float);
result = getParam(arcseckeys::MAX_MAGNITUDE, param);
if (result != RETURN_OK) {
return result;
}
addfloat(param, buffer + offset);
offset += sizeof(float);
result = getParam(arcseckeys::GAUSSIAN_CMAX, param);
if (result != RETURN_OK) {
return result;
}
addfloat(param, buffer + offset);
offset += sizeof(float);
result = getParam(arcseckeys::GAUSSIAN_CMIN, param);
if (result != RETURN_OK) {
return result;
}
addfloat(param, buffer + offset);
offset += sizeof(float);
result = getParam(arcseckeys::TRANSMATRIX_00, param);
if (result != RETURN_OK) {
return result;
}
addfloat(param, buffer + offset);
offset += sizeof(float);
result = getParam(arcseckeys::TRANSMATRIX_01, param);
if (result != RETURN_OK) {
return result;
}
addfloat(param, buffer + offset);
offset += sizeof(float);
result = getParam(arcseckeys::TRANSMATRIX_10, param);
if (result != RETURN_OK) {
return result;
}
addfloat(param, buffer + offset);
offset += sizeof(float);
result = getParam(arcseckeys::TRANSMATRIX_11, param);
if (result != RETURN_OK) {
return result;
}
addfloat(param, buffer + offset);
return RETURN_OK;
}
Lisa::Lisa() : ArcsecJsonParamBase(arcseckeys::LISA) {}
size_t Lisa::getSize() { return COMMAND_SIZE; }
ReturnValue_t Lisa::createCommand(uint8_t* buffer) {
ReturnValue_t result = RETURN_OK;
uint8_t offset = 0;
std::string param;
addSetParamHeader(buffer, startracker::ID::LISA);
offset = 2;
result = getParam(arcseckeys::LISA_MODE, param);
if (result != RETURN_OK) {
return result;
}
adduint32(param, buffer + offset);
offset += sizeof(uint32_t);
result = getParam(arcseckeys::PREFILTER_DIST_THRESHOLD, param);
if (result != RETURN_OK) {
return result;
}
addfloat(param, buffer + offset);
offset += sizeof(float);
result = getParam(arcseckeys::PREFILTER_ANGLE_THRESHOLD, param);
if (result != RETURN_OK) {
return result;
}
addfloat(param, buffer + offset);
offset += sizeof(float);
result = getParam(arcseckeys::FOV_WIDTH, param);
if (result != RETURN_OK) {
return result;
}
addfloat(param, buffer + offset);
offset += sizeof(float);
result = getParam(arcseckeys::FOV_HEIGHT, param);
if (result != RETURN_OK) {
return result;
}
addfloat(param, buffer + offset);
offset += sizeof(float);
result = getParam(arcseckeys::FLOAT_STAR_LIMIT, param);
if (result != RETURN_OK) {
return result;
}
addfloat(param, buffer + offset);
offset += sizeof(float);
result = getParam(arcseckeys::CLOSE_STAR_LIMIT, param);
if (result != RETURN_OK) {
return result;
}
addfloat(param, buffer + offset);
offset += sizeof(float);
result = getParam(arcseckeys::RATING_WEIGHT_CLOSE_STAR_COUNT, param);
if (result != RETURN_OK) {
return result;
}
addfloat(param, buffer + offset);
offset += sizeof(float);
result = getParam(arcseckeys::RATING_WEIGHT_FRACTION_CLOSE, param);
if (result != RETURN_OK) {
return result;
}
addfloat(param, buffer + offset);
offset += sizeof(float);
result = getParam(arcseckeys::RATING_WEIGHT_MEAN_SUM, param);
if (result != RETURN_OK) {
return result;
}
addfloat(param, buffer + offset);
offset += sizeof(float);
result = getParam(arcseckeys::RATING_WEIGHT_DB_STAR_COUNT, param);
if (result != RETURN_OK) {
return result;
}
addfloat(param, buffer + offset);
offset += sizeof(float);
result = getParam(arcseckeys::MAX_COMBINATIONS, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::NR_STARS_STOP, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::FRACTION_CLOSE_STOP, param);
if (result != RETURN_OK) {
return result;
}
addfloat(param, buffer + offset);
offset += sizeof(float);
return RETURN_OK;
}
Matching::Matching() : ArcsecJsonParamBase(arcseckeys::MATCHING) {}
size_t Matching::getSize() { return COMMAND_SIZE; }
ReturnValue_t Matching::createCommand(uint8_t* buffer) {
ReturnValue_t result = RETURN_OK;
uint8_t offset = 0;
std::string param;
addSetParamHeader(buffer, startracker::ID::MATCHING);
offset = 2;
result = getParam(arcseckeys::SQUARED_DISTANCE_LIMIT, param);
if (result != RETURN_OK) {
return result;
}
addfloat(param, buffer + offset);
offset += sizeof(float);
result = getParam(arcseckeys::SQUARED_SHIFT_LIMIT, param);
if (result != RETURN_OK) {
return result;
}
addfloat(param, buffer + offset);
return RETURN_OK;
}
Validation::Validation() : ArcsecJsonParamBase(arcseckeys::VALIDATION) {}
size_t Validation::getSize() { return COMMAND_SIZE; }
ReturnValue_t Validation::createCommand(uint8_t* buffer) {
ReturnValue_t result = RETURN_OK;
uint8_t offset = 0;
std::string param;
addSetParamHeader(buffer, startracker::ID::VALIDATION);
offset = 2;
result = getParam(arcseckeys::STABLE_COUNT, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::MAX_DIFFERENCE, param);
if (result != RETURN_OK) {
return result;
}
addfloat(param, buffer + offset);
offset += sizeof(float);
result = getParam(arcseckeys::MIN_TRACKER_CONFIDENCE, param);
if (result != RETURN_OK) {
return result;
}
addfloat(param, buffer + offset);
offset += sizeof(float);
result = getParam(arcseckeys::MIN_MATCHED_STARS, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
return RETURN_OK;
}
Algo::Algo() : ArcsecJsonParamBase(arcseckeys::ALGO) {}
size_t Algo::getSize() { return COMMAND_SIZE; }
ReturnValue_t Algo::createCommand(uint8_t* buffer) {
ReturnValue_t result = RETURN_OK;
uint8_t offset = 0;
std::string param;
addSetParamHeader(buffer, startracker::ID::ALGO);
offset = 2;
result = getParam(arcseckeys::MODE, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::L2T_MIN_CONFIDENCE, param);
if (result != RETURN_OK) {
return result;
}
addfloat(param, buffer + offset);
offset += sizeof(float);
result = getParam(arcseckeys::L2T_MIN_MATCHED, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::T2L_MIN_CONFIDENCE, param);
if (result != RETURN_OK) {
return result;
}
addfloat(param, buffer + offset);
offset += sizeof(float);
result = getParam(arcseckeys::T2L_MIN_MATCHED, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
return RETURN_OK;
}
LogLevel::LogLevel() : ArcsecJsonParamBase(arcseckeys::LOGLEVEL) {}
size_t LogLevel::getSize() { return COMMAND_SIZE; }
ReturnValue_t LogLevel::createCommand(uint8_t* buffer) {
ReturnValue_t result = RETURN_OK;
uint8_t offset = 0;
std::string param;
addSetParamHeader(buffer, startracker::ID::LOG_LEVEL);
offset = 2;
result = getParam(arcseckeys::LOGLEVEL1, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::LOGLEVEL2, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::LOGLEVEL3, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::LOGLEVEL4, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::LOGLEVEL5, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::LOGLEVEL6, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::LOGLEVEL7, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::LOGLEVEL8, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::LOGLEVEL9, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::LOGLEVEL10, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::LOGLEVEL11, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::LOGLEVEL12, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::LOGLEVEL13, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::LOGLEVEL14, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::LOGLEVEL15, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::LOGLEVEL16, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
return RETURN_OK;
}
Subscription::Subscription() : ArcsecJsonParamBase(arcseckeys::SUBSCRIPTION) {}
size_t Subscription::getSize() { return COMMAND_SIZE; }
ReturnValue_t Subscription::createCommand(uint8_t* buffer) {
ReturnValue_t result = RETURN_OK;
uint8_t offset = 0;
std::string param;
addSetParamHeader(buffer, startracker::ID::SUBSCRIPTION);
offset = 2;
result = getParam(arcseckeys::TELEMETRY_1, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::TELEMETRY_2, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::TELEMETRY_3, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::TELEMETRY_4, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::TELEMETRY_5, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::TELEMETRY_6, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::TELEMETRY_7, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::TELEMETRY_8, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::TELEMETRY_9, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::TELEMETRY_10, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::TELEMETRY_11, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::TELEMETRY_12, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::TELEMETRY_13, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::TELEMETRY_14, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::TELEMETRY_15, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::TELEMETRY_16, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
return RETURN_OK;
}
LogSubscription::LogSubscription() : ArcsecJsonParamBase(arcseckeys::LOG_SUBSCRIPTION) {}
size_t LogSubscription::getSize() { return COMMAND_SIZE; }
ReturnValue_t LogSubscription::createCommand(uint8_t* buffer) {
ReturnValue_t result = RETURN_OK;
uint8_t offset = 0;
std::string param;
addSetParamHeader(buffer, startracker::ID::LOG_SUBSCRIPTION);
offset = 2;
result = getParam(arcseckeys::LEVEL1, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::MODULE1, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::LEVEL2, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
offset += sizeof(uint8_t);
result = getParam(arcseckeys::MODULE2, param);
if (result != RETURN_OK) {
return result;
}
adduint8(param, buffer + offset);
return RETURN_OK;
}
DebugCamera::DebugCamera() : ArcsecJsonParamBase(arcseckeys::DEBUG_CAMERA) {}
size_t DebugCamera::getSize() { return COMMAND_SIZE; }
ReturnValue_t DebugCamera::createCommand(uint8_t* buffer) {
ReturnValue_t result = RETURN_OK;
uint8_t offset = 0;
std::string param;
addSetParamHeader(buffer, startracker::ID::DEBUG_CAMERA);
offset = 2;
result = getParam(arcseckeys::TIMING, param);
if (result != RETURN_OK) {
return result;
}
adduint32(param, buffer + offset);
offset += sizeof(uint32_t);
result = getParam(arcseckeys::TEST, param);
if (result != RETURN_OK) {
return result;
}
adduint32(param, buffer + offset);
return RETURN_OK;
}

View File

@ -0,0 +1,240 @@
#ifndef BSP_Q7S_DEVICES_DEVICEDEFINITIONS_STARTRACKERJSONCOMMANDS_H_
#define BSP_Q7S_DEVICES_DEVICEDEFINITIONS_STARTRACKERJSONCOMMANDS_H_
/**
* @brief This file defines a few helper classes to generate commands by means of the parameters
* defined in the arcsec json files.
* @author J. Meier
*/
#include <string>
#include "ArcsecJsonParamBase.h"
#include "fsfw/serviceinterface/ServiceInterface.h"
/**
* @brief Generates command to set the limit parameters
*
*/
class Limits : public ArcsecJsonParamBase {
public:
Limits();
size_t getSize();
private:
static const size_t COMMAND_SIZE = 43;
virtual ReturnValue_t createCommand(uint8_t* buffer) override;
};
/**
* @brief Generates the command to configure the tracking algorithm.
*
*/
class Tracking : public ArcsecJsonParamBase {
public:
Tracking();
size_t getSize();
private:
static const size_t COMMAND_SIZE = 15;
ReturnValue_t createCommand(uint8_t* buffer) override;
};
/**
* @brief Generates the command to set the mounting quaternion
*
*/
class Mounting : public ArcsecJsonParamBase {
public:
Mounting();
size_t getSize();
private:
static const size_t COMMAND_SIZE = 18;
ReturnValue_t createCommand(uint8_t* buffer) override;
};
/**
* @brief Generates the command to configure the image processor
*
*/
class ImageProcessor : public ArcsecJsonParamBase {
public:
ImageProcessor();
size_t getSize();
private:
static const size_t COMMAND_SIZE = 9;
ReturnValue_t createCommand(uint8_t* buffer) override;
};
/**
* @brief Generates the command to set the mounting quaternion
*
*/
class Camera : public ArcsecJsonParamBase {
public:
Camera();
size_t getSize();
private:
static const size_t COMMAND_SIZE = 39;
ReturnValue_t createCommand(uint8_t* buffer) override;
};
/**
* @brief Generates the command to configure the centroiding algorithm
*
*/
class Centroiding : public ArcsecJsonParamBase {
public:
Centroiding();
size_t getSize();
private:
static const size_t COMMAND_SIZE = 51;
ReturnValue_t createCommand(uint8_t* buffer) override;
};
/**
* @brief Generates the command to configure the LISA (lost in space algorithm)
*
*/
class Lisa : public ArcsecJsonParamBase {
public:
Lisa();
size_t getSize();
private:
static const size_t COMMAND_SIZE = 52;
ReturnValue_t createCommand(uint8_t* buffer) override;
};
/**
* @brief Generates the command to configure the matching algorithm
*
*/
class Matching : public ArcsecJsonParamBase {
public:
Matching();
size_t getSize();
private:
static const size_t COMMAND_SIZE = 10;
ReturnValue_t createCommand(uint8_t* buffer) override;
};
/**
* @brief Generates the command to configure the validation parameters
*
*/
class Validation : public ArcsecJsonParamBase {
public:
Validation();
size_t getSize();
private:
static const size_t COMMAND_SIZE = 12;
ReturnValue_t createCommand(uint8_t* buffer) override;
};
/**
* @brief Generates command to configure the mechanism of automatically switching between the
* LISA and other algorithms.
*
*/
class Algo : public ArcsecJsonParamBase {
public:
Algo();
size_t getSize();
private:
static const size_t COMMAND_SIZE = 13;
ReturnValue_t createCommand(uint8_t* buffer) override;
};
/**
* @brief Generates command to configure the log level parameters.
*
*/
class LogLevel : public ArcsecJsonParamBase {
public:
LogLevel();
size_t getSize();
private:
static const size_t COMMAND_SIZE = 18;
ReturnValue_t createCommand(uint8_t* buffer) override;
};
/**
* @brief Generates command to set subscription parameters.
*
*/
class Subscription : public ArcsecJsonParamBase {
public:
Subscription();
size_t getSize();
private:
static const size_t COMMAND_SIZE = 18;
ReturnValue_t createCommand(uint8_t* buffer) override;
};
/**
* @brief Generates command to set log subscription parameters.
*
*/
class LogSubscription : public ArcsecJsonParamBase {
public:
LogSubscription();
size_t getSize();
private:
static const size_t COMMAND_SIZE = 6;
ReturnValue_t createCommand(uint8_t* buffer) override;
};
/**
* @brief Generates command to set debug camera parameters
*
*/
class DebugCamera : public ArcsecJsonParamBase {
public:
DebugCamera();
size_t getSize();
private:
static const size_t COMMAND_SIZE = 10;
ReturnValue_t createCommand(uint8_t* buffer) override;
};
#endif /* BSP_Q7S_DEVICES_DEVICEDEFINITIONS_STARTRACKERJSONCOMMANDS_H_ */

View File

@ -0,0 +1,601 @@
#include "StrHelper.h"
#include <filesystem>
#include <fstream>
#include "OBSWConfig.h"
#include "fsfw/timemanager/Countdown.h"
#include "linux/devices/devicedefinitions/StarTrackerDefinitions.h"
#include "mission/utility/Timestamp.h"
#include "mission/utility/ProgressPrinter.h"
StrHelper::StrHelper(object_id_t objectId) : SystemObject(objectId) {}
StrHelper::~StrHelper() {}
ReturnValue_t StrHelper::initialize() {
#ifdef XIPHOS_Q7S
sdcMan = SdCardManager::instance();
if (sdcMan == nullptr) {
sif::warning << "StrHelper::initialize: Invalid SD Card Manager" << std::endl;
return RETURN_FAILED;
}
#endif
return RETURN_OK;
}
ReturnValue_t StrHelper::performOperation(uint8_t operationCode) {
ReturnValue_t result = RETURN_OK;
semaphore.acquire();
while (true) {
switch (internalState) {
case InternalState::IDLE: {
semaphore.acquire();
break;
}
case InternalState::UPLOAD_IMAGE: {
result = performImageUpload();
if (result == RETURN_OK) {
triggerEvent(IMAGE_UPLOAD_SUCCESSFUL);
} else {
triggerEvent(IMAGE_UPLOAD_FAILED);
}
internalState = InternalState::IDLE;
break;
}
case InternalState::DOWNLOAD_IMAGE: {
result = performImageDownload();
if (result == RETURN_OK) {
triggerEvent(IMAGE_DOWNLOAD_SUCCESSFUL);
} else {
triggerEvent(IMAGE_DOWNLOAD_FAILED);
}
internalState = InternalState::IDLE;
break;
}
case InternalState::FLASH_READ: {
result = performFlashRead();
if (result == RETURN_OK) {
triggerEvent(FLASH_READ_SUCCESSFUL);
} else {
triggerEvent(FLASH_READ_FAILED);
}
internalState = InternalState::IDLE;
break;
}
case InternalState::FIRMWARE_UPDATE: {
result = performFirmwareUpdate();
if (result == RETURN_OK) {
triggerEvent(FIRMWARE_UPDATE_SUCCESSFUL);
} else {
triggerEvent(FIRMWARE_UPDATE_FAILED);
}
internalState = InternalState::IDLE;
break;
}
default:
sif::debug << "StrHelper::performOperation: Invalid state" << std::endl;
break;
}
}
}
ReturnValue_t StrHelper::setComIF(DeviceCommunicationIF* communicationInterface_) {
uartComIF = dynamic_cast<UartComIF*>(communicationInterface_);
if (uartComIF == nullptr) {
sif::warning << "StrHelper::initialize: Invalid uart com if" << std::endl;
return RETURN_FAILED;
}
return RETURN_OK;
}
void StrHelper::setComCookie(CookieIF* comCookie_) { comCookie = comCookie_; }
ReturnValue_t StrHelper::startImageUpload(std::string fullname) {
#ifdef XIPHOS_Q7S
ReturnValue_t result = checkPath(fullname);
if (result != RETURN_OK) {
return result;
}
#endif
uploadImage.uploadFile = fullname;
if (not std::filesystem::exists(fullname)) {
return FILE_NOT_EXISTS;
}
internalState = InternalState::UPLOAD_IMAGE;
semaphore.release();
terminate = false;
return RETURN_OK;
}
ReturnValue_t StrHelper::startImageDownload(std::string path) {
#ifdef XIPHOS_Q7S
ReturnValue_t result = checkPath(path);
if (result != RETURN_OK) {
return result;
}
#endif
if (not std::filesystem::exists(path)) {
return PATH_NOT_EXISTS;
}
downloadImage.path = path;
internalState = InternalState::DOWNLOAD_IMAGE;
terminate = false;
semaphore.release();
return RETURN_OK;
}
void StrHelper::stopProcess() { terminate = true; }
void StrHelper::setDownloadImageName(std::string filename) { downloadImage.filename = filename; }
void StrHelper::setFlashReadFilename(std::string filename) { flashRead.filename = filename; }
ReturnValue_t StrHelper::startFirmwareUpdate(std::string fullname) {
#ifdef XIPHOS_Q7S
ReturnValue_t result = checkPath(fullname);
if (result != RETURN_OK) {
return result;
}
#endif
flashWrite.fullname = fullname;
if (not std::filesystem::exists(flashWrite.fullname)) {
return FILE_NOT_EXISTS;
}
flashWrite.firstRegion = static_cast<uint8_t>(startracker::FirmwareRegions::FIRST);
flashWrite.lastRegion = static_cast<uint8_t>(startracker::FirmwareRegions::LAST);
internalState = InternalState::FIRMWARE_UPDATE;
semaphore.release();
terminate = false;
return RETURN_OK;
}
ReturnValue_t StrHelper::startFlashRead(std::string path, uint8_t startRegion, uint32_t length) {
#ifdef XIPHOS_Q7S
ReturnValue_t result = checkPath(path);
if (result != RETURN_OK) {
return result;
}
#endif
flashRead.path = path;
if (not std::filesystem::exists(flashRead.path)) {
return FILE_NOT_EXISTS;
}
flashRead.startRegion = startRegion;
flashRead.size = length;
internalState = InternalState::FLASH_READ;
semaphore.release();
terminate = false;
return RETURN_OK;
}
void StrHelper::disableTimestamping() { timestamping = false; }
void StrHelper::enableTimestamping() { timestamping = true; }
ReturnValue_t StrHelper::performImageDownload() {
ReturnValue_t result;
#if OBSW_DEBUG_STARTRACKER == 1
ProgressPrinter progressPrinter("Image download", ImageDownload::LAST_POSITION);
#endif /* OBSW_DEBUG_STARTRACKER == 1 */
struct DownloadActionRequest downloadReq;
uint32_t size = 0;
uint32_t retries = 0;
std::string image = makeFullFilename(downloadImage.path, downloadImage.filename);
std::ofstream file(image, std::ios_base::out);
if (not std::filesystem::exists(image)) {
return FILE_CREATION_FAILED;
}
downloadReq.position = 0;
while (downloadReq.position < ImageDownload::LAST_POSITION) {
if (terminate) {
file.close();
return RETURN_OK;
}
arc_pack_download_action_req(&downloadReq, commandBuffer, &size);
result = sendAndRead(size, downloadReq.position);
if (result != RETURN_OK) {
if (retries < CONFIG_MAX_DOWNLOAD_RETRIES) {
uartComIF->flushUartRxBuffer(comCookie);
retries++;
continue;
}
file.close();
return result;
}
result = checkActionReply();
if (result != RETURN_OK) {
if (retries < CONFIG_MAX_DOWNLOAD_RETRIES) {
uartComIF->flushUartRxBuffer(comCookie);
retries++;
continue;
}
file.close();
return result;
}
result = checkReplyPosition(downloadReq.position);
if (result != RETURN_OK) {
if (retries < CONFIG_MAX_DOWNLOAD_RETRIES) {
uartComIF->flushUartRxBuffer(comCookie);
retries++;
continue;
}
file.close();
return result;
}
file.write(reinterpret_cast<const char*>(datalinkLayer.getReply() + IMAGE_DATA_OFFSET),
CHUNK_SIZE);
#if OBSW_DEBUG_STARTRACKER == 1
progressPrinter.print(downloadReq.position);
#endif /* OBSW_DEBUG_STARTRACKER == 1 */
downloadReq.position++;
retries = 0;
}
file.close();
return RETURN_OK;
}
ReturnValue_t StrHelper::performImageUpload() {
ReturnValue_t result = RETURN_OK;
uint32_t size = 0;
uint32_t imageSize = 0;
struct UploadActionRequest uploadReq;
uploadReq.position = 0;
std::memset(&uploadReq.data, 0, sizeof(uploadReq.data));
if (not std::filesystem::exists(uploadImage.uploadFile)) {
triggerEvent(STR_HELPER_FILE_NOT_EXISTS, static_cast<uint32_t>(internalState));
internalState = InternalState::IDLE;
return RETURN_FAILED;
}
std::ifstream file(uploadImage.uploadFile, std::ifstream::binary);
// Set position of next character to end of file input stream
file.seekg(0, file.end);
// tellg returns position of character in input stream
imageSize = file.tellg();
#if OBSW_DEBUG_STARTRACKER == 1
ProgressPrinter progressPrinter("Image upload", imageSize);
#endif /* OBSW_DEBUG_STARTRACKER == 1 */
while ((uploadReq.position + 1) * SIZE_IMAGE_PART < imageSize) {
if (terminate) {
file.close();
return RETURN_OK;
}
file.seekg(uploadReq.position * SIZE_IMAGE_PART, file.beg);
file.read(reinterpret_cast<char*>(uploadReq.data), SIZE_IMAGE_PART);
arc_pack_upload_action_req(&uploadReq, commandBuffer, &size);
result = sendAndRead(size, uploadReq.position);
if (result != RETURN_OK) {
file.close();
return RETURN_FAILED;
}
result = checkActionReply();
if (result != RETURN_OK) {
file.close();
return result;
}
#if OBSW_DEBUG_STARTRACKER == 1
progressPrinter.print((uploadReq.position + 1) * SIZE_IMAGE_PART);
#endif /* OBSW_DEBUG_STARTRACKER == 1 */
uploadReq.position++;
}
std::memset(uploadReq.data, 0, sizeof(uploadReq.data));
uint32_t remainder = imageSize - uploadReq.position * SIZE_IMAGE_PART;
file.seekg(uploadReq.position * SIZE_IMAGE_PART, file.beg);
file.read(reinterpret_cast<char*>(uploadReq.data), remainder);
file.close();
uploadReq.position++;
arc_pack_upload_action_req(&uploadReq, commandBuffer, &size);
result = sendAndRead(size, uploadReq.position);
if (result != RETURN_OK) {
return RETURN_FAILED;
}
result = checkActionReply();
if (result != RETURN_OK) {
return result;
}
#if OBSW_DEBUG_STARTRACKER == 1
progressPrinter.print((uploadReq.position + 1) * SIZE_IMAGE_PART);
#endif /* OBSW_DEBUG_STARTRACKER == 1 */
return RETURN_OK;
}
ReturnValue_t StrHelper::performFirmwareUpdate() {
using namespace startracker;
ReturnValue_t result = RETURN_OK;
result = unlockAndEraseRegions(static_cast<uint32_t>(startracker::FirmwareRegions::FIRST),
static_cast<uint32_t>(startracker::FirmwareRegions::LAST));
if (result != RETURN_OK) {
return result;
}
result = performFlashWrite();
return result;
}
ReturnValue_t StrHelper::performFlashWrite() {
ReturnValue_t result = RETURN_OK;
uint32_t size = 0;
uint32_t bytesWritten = 0;
uint32_t fileSize = 0;
struct WriteActionRequest req;
if (not std::filesystem::exists(flashWrite.fullname)) {
triggerEvent(STR_HELPER_FILE_NOT_EXISTS, static_cast<uint32_t>(internalState));
internalState = InternalState::IDLE;
return RETURN_FAILED;
}
std::ifstream file(flashWrite.fullname, std::ifstream::binary);
file.seekg(0, file.end);
fileSize = file.tellg();
if (fileSize > FLASH_REGION_SIZE * (flashWrite.lastRegion - flashWrite.firstRegion)) {
sif::warning << "StrHelper::performFlashWrite: Invalid file" << std::endl;
return RETURN_FAILED;
}
#if OBSW_DEBUG_STARTRACKER == 1
ProgressPrinter progressPrinter("Flash write", fileSize);
#endif /* OBSW_DEBUG_STARTRACKER == 1 */
uint32_t fileChunks = fileSize / CHUNK_SIZE;
bytesWritten = 0;
req.region = flashWrite.firstRegion;
req.length = CHUNK_SIZE;
for (uint32_t idx = 0; idx < fileChunks; idx++) {
if (terminate) {
file.close();
return RETURN_OK;
}
file.seekg(idx * CHUNK_SIZE, file.beg);
file.read(reinterpret_cast<char*>(req.data), CHUNK_SIZE);
if (bytesWritten + CHUNK_SIZE > FLASH_REGION_SIZE) {
req.region++;
bytesWritten = 0;
}
req.address = bytesWritten;
arc_pack_write_action_req(&req, commandBuffer, &size);
result = sendAndRead(size, req.address);
if (result != RETURN_OK) {
file.close();
return result;
}
result = checkActionReply();
if (result != RETURN_OK) {
file.close();
return result;
}
bytesWritten += CHUNK_SIZE;
#if OBSW_DEBUG_STARTRACKER == 1
progressPrinter.print(idx * CHUNK_SIZE);
#endif /* OBSW_DEBUG_STARTRACKER == 1 */
}
uint32_t remainingBytes = fileSize - fileChunks * CHUNK_SIZE;
file.seekg((fileChunks - 1) * CHUNK_SIZE, file.beg);
file.read(reinterpret_cast<char*>(req.data), remainingBytes);
file.close();
if (bytesWritten + CHUNK_SIZE > FLASH_REGION_SIZE) {
req.region++;
bytesWritten = 0;
}
req.address = bytesWritten;
req.length = remainingBytes;
bytesWritten += remainingBytes;
arc_pack_write_action_req(&req, commandBuffer, &size);
result = sendAndRead(size, req.address);
if (result != RETURN_OK) {
return result;
}
result = checkActionReply();
if (result != RETURN_OK) {
return result;
}
#if OBSW_DEBUG_STARTRACKER == 1
progressPrinter.print(fileSize);
#endif /* OBSW_DEBUG_STARTRACKER == 1 */
return RETURN_OK;
}
ReturnValue_t StrHelper::performFlashRead() {
ReturnValue_t result;
#if OBSW_DEBUG_STARTRACKER == 1
ProgressPrinter progressPrinter("Flash read", flashRead.size);
#endif /* OBSW_DEBUG_STARTRACKER == 1 */
struct ReadActionRequest req;
uint32_t bytesRead = 0;
uint32_t size = 0;
uint32_t retries = 0;
Timestamp timestamp;
std::string fullname = makeFullFilename(flashRead.path, flashRead.filename);
std::ofstream file(fullname, std::ios_base::app | std::ios_base::out);
if (not std::filesystem::exists(fullname)) {
return FILE_CREATION_FAILED;
}
req.region = flashRead.startRegion;
req.address = 0;
while (bytesRead < flashRead.size) {
if (terminate) {
return RETURN_OK;
}
if ((flashRead.size - bytesRead) < CHUNK_SIZE) {
req.length = flashRead.size - bytesRead;
} else {
req.length = CHUNK_SIZE;
}
arc_pack_read_action_req(&req, commandBuffer, &size);
result = sendAndRead(size, req.address);
if (result != RETURN_OK) {
if (retries < CONFIG_MAX_DOWNLOAD_RETRIES) {
uartComIF->flushUartRxBuffer(comCookie);
retries++;
continue;
}
file.close();
return result;
}
result = checkActionReply();
if (result != RETURN_OK) {
if (retries < CONFIG_MAX_DOWNLOAD_RETRIES) {
uartComIF->flushUartRxBuffer(comCookie);
retries++;
continue;
}
file.close();
return result;
}
file.write(reinterpret_cast<const char*>(datalinkLayer.getReply() + FLASH_READ_DATA_OFFSET),
req.length);
bytesRead += req.length;
req.address += req.length;
if (req.address >= FLASH_REGION_SIZE) {
req.address = 0;
req.region++;
}
retries = 0;
#if OBSW_DEBUG_STARTRACKER == 1
progressPrinter.print(bytesRead);
#endif /* OBSW_DEBUG_STARTRACKER == 1 */
}
file.close();
return RETURN_OK;
}
ReturnValue_t StrHelper::sendAndRead(size_t size, uint32_t parameter, uint32_t delayMs) {
ReturnValue_t result = RETURN_OK;
ReturnValue_t decResult = RETURN_OK;
size_t receivedDataLen = 0;
uint8_t* receivedData = nullptr;
size_t bytesLeft = 0;
uint32_t missedReplies = 0;
datalinkLayer.encodeFrame(commandBuffer, size);
result = uartComIF->sendMessage(comCookie, datalinkLayer.getEncodedFrame(),
datalinkLayer.getEncodedLength());
if (result != RETURN_OK) {
sif::warning << "StrHelper::sendAndRead: Failed to send packet" << std::endl;
triggerEvent(STR_HELPER_SENDING_PACKET_FAILED, result, parameter);
return RETURN_FAILED;
}
decResult = ArcsecDatalinkLayer::DEC_IN_PROGRESS;
while (decResult == ArcsecDatalinkLayer::DEC_IN_PROGRESS) {
Countdown delay(delayMs);
delay.resetTimer();
while (delay.isBusy()) {
}
result = uartComIF->requestReceiveMessage(comCookie, startracker::MAX_FRAME_SIZE * 2 + 2);
if (result != RETURN_OK) {
sif::warning << "StrHelper::sendAndRead: Failed to request reply" << std::endl;
triggerEvent(STR_HELPER_REQUESTING_MSG_FAILED, result, parameter);
return RETURN_FAILED;
}
result = uartComIF->readReceivedMessage(comCookie, &receivedData, &receivedDataLen);
if (result != RETURN_OK) {
sif::warning << "StrHelper::sendAndRead: Failed to read received message" << std::endl;
triggerEvent(STR_HELPER_READING_REPLY_FAILED, result, parameter);
return RETURN_FAILED;
}
if (receivedDataLen == 0 && missedReplies < MAX_POLLS) {
missedReplies++;
continue;
} else if ((receivedDataLen == 0) && (missedReplies >= MAX_POLLS)) {
triggerEvent(STR_HELPER_NO_REPLY, parameter);
return RETURN_FAILED;
} else {
missedReplies = 0;
}
decResult = datalinkLayer.decodeFrame(receivedData, receivedDataLen, &bytesLeft);
if (bytesLeft != 0) {
// This should never happen
sif::warning << "StrHelper::sendAndRead: Bytes left after decoding" << std::endl;
triggerEvent(STR_HELPER_COM_ERROR, result, parameter);
return RETURN_FAILED;
}
}
if (decResult != RETURN_OK) {
triggerEvent(STR_HELPER_DEC_ERROR, decResult, parameter);
return RETURN_FAILED;
}
return RETURN_OK;
}
ReturnValue_t StrHelper::checkActionReply() {
uint8_t type = datalinkLayer.getReplyFrameType();
if (type != TMTC_ACTIONREPLY) {
sif::warning << "StrHelper::checkActionReply: Received reply with invalid type ID" << std::endl;
return INVALID_TYPE_ID;
}
uint8_t status = datalinkLayer.getStatusField();
if (status != ArcsecDatalinkLayer::STATUS_OK) {
sif::warning << "StrHelper::checkActionReply: Status failure: "
<< static_cast<unsigned int>(status) << std::endl;
return STATUS_ERROR;
}
return RETURN_OK;
}
ReturnValue_t StrHelper::checkReplyPosition(uint32_t expectedPosition) {
uint32_t receivedPosition = 0;
std::memcpy(&receivedPosition, datalinkLayer.getReply() + POS_OFFSET, sizeof(receivedPosition));
if (receivedPosition != expectedPosition) {
triggerEvent(POSITION_MISMATCH, receivedPosition);
return RETURN_FAILED;
}
return RETURN_OK;
}
#ifdef XIPHOS_Q7S
ReturnValue_t StrHelper::checkPath(std::string name) {
if (name.substr(0, sizeof(SdCardManager::SD_0_MOUNT_POINT)) ==
std::string(SdCardManager::SD_0_MOUNT_POINT)) {
if (!sdcMan->isSdCardMounted(sd::SLOT_0)) {
sif::warning << "StrHelper::checkPath: SD card 0 not mounted" << std::endl;
return SD_NOT_MOUNTED;
}
} else if (name.substr(0, sizeof(SdCardManager::SD_1_MOUNT_POINT)) ==
std::string(SdCardManager::SD_1_MOUNT_POINT)) {
if (!sdcMan->isSdCardMounted(sd::SLOT_0)) {
sif::warning << "StrHelper::checkPath: SD card 1 not mounted" << std::endl;
return SD_NOT_MOUNTED;
}
}
return RETURN_OK;
}
#endif
ReturnValue_t StrHelper::unlockAndEraseRegions(uint32_t from, uint32_t to) {
ReturnValue_t result = RETURN_OK;
#if OBSW_DEBUG_STARTRACKER == 1
ProgressPrinter progressPrinter("Unlock and erase", to - from);
#endif /* OBSW_DEBUG_STARTRACKER == 1 */
struct UnlockActionRequest unlockReq;
struct EraseActionRequest eraseReq;
uint32_t size = 0;
for (uint32_t idx = from; idx <= to; idx++) {
unlockReq.region = idx;
unlockReq.code = startracker::region_secrets::secret[idx];
arc_pack_unlock_action_req(&unlockReq, commandBuffer, &size);
sendAndRead(size, unlockReq.region);
result = checkActionReply();
if (result != RETURN_OK) {
sif::warning << "StrHelper::unlockAndEraseRegions: Failed to unlock region with id "
<< static_cast<unsigned int>(unlockReq.region) << std::endl;
return result;
}
eraseReq.region = idx;
arc_pack_erase_action_req(&eraseReq, commandBuffer, &size);
result = sendAndRead(size, eraseReq.region, FLASH_ERASE_DELAY);
if (result != RETURN_OK) {
sif::warning << "StrHelper::unlockAndEraseRegions: Failed to erase region with id "
<< static_cast<unsigned int>(eraseReq.region) << std::endl;
return result;
}
#if OBSW_DEBUG_STARTRACKER == 1
progressPrinter.print(idx - from);
#endif /* OBSW_DEBUG_STARTRACKER == 1 */
}
return result;
}
std::string StrHelper::makeFullFilename(std::string path, std::string filename) {
std::string image;
Timestamp timestamp;
if (timestamping) {
image = path + "/" + timestamp.str() + filename;
} else {
image = path + "/" + filename;
}
return image;
}

View File

@ -0,0 +1,364 @@
#ifndef BSP_Q7S_DEVICES_STRHELPER_H_
#define BSP_Q7S_DEVICES_STRHELPER_H_
#include <string>
#include "ArcsecDatalinkLayer.h"
#include "OBSWConfig.h"
#ifdef XIPHOS_Q7S
#include "bsp_q7s/memory/SdCardManager.h"
#endif
#include "fsfw/devicehandlers/CookieIF.h"
#include "fsfw/objectmanager/SystemObject.h"
#include "fsfw/osal/linux/BinarySemaphore.h"
#include "fsfw/returnvalues/HasReturnvaluesIF.h"
#include "fsfw/tasks/ExecutableObjectIF.h"
#include "fsfw_hal/linux/uart/UartComIF.h"
extern "C" {
#include "thirdparty/arcsec_star_tracker/client/generated/actionreq.h"
#include "thirdparty/arcsec_star_tracker/common/generated/tmtcstructs.h"
}
/**
* @brief Helper class for the star tracker handler to accelerate large data transfers.
*
* @author J. Meier
*/
class StrHelper : public SystemObject, public ExecutableObjectIF, public HasReturnvaluesIF {
public:
static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::STR_HELPER;
//! [EXPORT] : [COMMENT] Image upload failed
static const Event IMAGE_UPLOAD_FAILED = MAKE_EVENT(0, severity::LOW);
//! [EXPORT] : [COMMENT] Image download failed
static const Event IMAGE_DOWNLOAD_FAILED = MAKE_EVENT(1, severity::LOW);
//! [EXPORT] : [COMMENT] Uploading image to star tracker was successfulop
static const Event IMAGE_UPLOAD_SUCCESSFUL = MAKE_EVENT(2, severity::LOW);
//! [EXPORT] : [COMMENT] Image download was successful
static const Event IMAGE_DOWNLOAD_SUCCESSFUL = MAKE_EVENT(3, severity::LOW);
//! [EXPORT] : [COMMENT] Finished flash write procedure successfully
static const Event FLASH_WRITE_SUCCESSFUL = MAKE_EVENT(4, severity::LOW);
//! [EXPORT] : [COMMENT] Finished flash read procedure successfully
static const Event FLASH_READ_SUCCESSFUL = MAKE_EVENT(5, severity::LOW);
//! [EXPORT] : [COMMENT] Flash read procedure failed
static const Event FLASH_READ_FAILED = MAKE_EVENT(6, severity::LOW);
//! [EXPORT] : [COMMENT] Firmware update was successful
static const Event FIRMWARE_UPDATE_SUCCESSFUL = MAKE_EVENT(7, severity::LOW);
//! [EXPORT] : [COMMENT] Firmware update failed
static const Event FIRMWARE_UPDATE_FAILED = MAKE_EVENT(8, severity::LOW);
//! [EXPORT] : [COMMENT] Failed to read communication interface reply data
//! P1: Return code of failed communication interface read call
//! P1: Upload/download position for which the read call failed
static const Event STR_HELPER_READING_REPLY_FAILED = MAKE_EVENT(9, severity::LOW);
//! [EXPORT] : [COMMENT] Unexpected stop of decoding sequence
//! P1: Return code of failed communication interface read call
//! P1: Upload/download position for which the read call failed
static const Event STR_HELPER_COM_ERROR = MAKE_EVENT(10, severity::LOW);
//! [EXPORT] : [COMMENT] Star tracker did not send replies (maybe device is powered off)
//! P1: Position of upload or download packet for which no reply was sent
static const Event STR_HELPER_NO_REPLY = MAKE_EVENT(11, severity::LOW);
//! [EXPORT] : [COMMENT] Error during decoding of received reply occurred
// P1: Return value of decoding function
// P2: Position of upload/download packet, or address of flash write/read request
static const Event STR_HELPER_DEC_ERROR = MAKE_EVENT(12, severity::LOW);
//! [EXPORT] : [COMMENT] Position mismatch
//! P1: The expected position and thus the position for which the image upload/download failed
static const Event POSITION_MISMATCH = MAKE_EVENT(13, severity::LOW);
//! [EXPORT] : [COMMENT] Specified file does not exist
//! P1: Internal state of str helper
static const Event STR_HELPER_FILE_NOT_EXISTS = MAKE_EVENT(14, severity::LOW);
//! [EXPORT] : [COMMENT] Sending packet to star tracker failed
//! P1: Return code of communication interface sendMessage function
//! P2: Position of upload/download packet, or address of flash write/read request for which
//! sending failed
static const Event STR_HELPER_SENDING_PACKET_FAILED = MAKE_EVENT(15, severity::LOW);
//! [EXPORT] : [COMMENT] Communication interface requesting reply failed
//! P1: Return code of failed request
//! P1: Upload/download position, or address of flash write/read request for which transmission
//! failed
static const Event STR_HELPER_REQUESTING_MSG_FAILED = MAKE_EVENT(16, severity::LOW);
StrHelper(object_id_t objectId);
virtual ~StrHelper();
ReturnValue_t initialize() override;
ReturnValue_t performOperation(uint8_t operationCode = 0) override;
ReturnValue_t setComIF(DeviceCommunicationIF* communicationInterface_);
void setComCookie(CookieIF* comCookie_);
/**
* @brief Starts sequence to upload image to star tracker
*
* @param uploadImage_ Name including absolute path of the image to upload. Must be previously
* transferred to the OBC with the CFDP protocol.
*/
ReturnValue_t startImageUpload(std::string uploadImage_);
/**
* @brief Calling this function initiates the download of an image from the star tracker.
*
* @param path Path where downloaded image will be stored
*/
ReturnValue_t startImageDownload(std::string path);
/**
* @brief Will start the firmware update
*
* @param fullname Full name including absolute path of file containing firmware
* update.
*/
ReturnValue_t startFirmwareUpdate(std::string fullname);
/**
* @brief Starts the flash read procedure
*
* @param path Path where file with read flash data will be created
* @param startRegion Region form where to start reading
* @param length Number of bytes to read from flash
*/
ReturnValue_t startFlashRead(std::string path, uint8_t startRegion, uint32_t length);
/**
* @brief Can be used to interrupt a running data transfer.
*/
void stopProcess();
/**
* @brief Changes the dafault name of downloaded images
*/
void setDownloadImageName(std::string filename);
/**
* @brief Sets the name of the file which will be created to store the data read from flash
*/
void setFlashReadFilename(std::string filename);
/**
* @brief Disables timestamp generation when new file is created
*/
void disableTimestamping();
/**
* @brief Enables timestamp generation when new file is created
*/
void enableTimestamping();
private:
static const uint8_t INTERFACE_ID = CLASS_ID::STR_HELPER;
//! [EXPORT] : [COMMENT] SD card specified in path string not mounted
static const ReturnValue_t SD_NOT_MOUNTED = MAKE_RETURN_CODE(0xA0);
//! [EXPORT] : [COMMENT] Specified file does not exist on filesystem
static const ReturnValue_t FILE_NOT_EXISTS = MAKE_RETURN_CODE(0xA1);
//! [EXPORT] : [COMMENT] Specified path does not exist
static const ReturnValue_t PATH_NOT_EXISTS = MAKE_RETURN_CODE(0xA2);
//! [EXPORT] : [COMMENT] Failed to create download image or read flash file
static const ReturnValue_t FILE_CREATION_FAILED = MAKE_RETURN_CODE(0xA3);
//! [EXPORT] : [COMMENT] Region in flash write/read reply does not match expected region
static const ReturnValue_t REGION_MISMATCH = MAKE_RETURN_CODE(0xA4);
//! [EXPORT] : [COMMENT] Address in flash write/read reply does not match expected address
static const ReturnValue_t ADDRESS_MISMATCH = MAKE_RETURN_CODE(0xA5);
//! [EXPORT] : [COMMENT] Length in flash write/read reply does not match expected length
static const ReturnValue_t LENGTH_MISMATCH = MAKE_RETURN_CODE(0xA6);
//! [EXPORT] : [COMMENT] Status field in reply signals error
static const ReturnValue_t STATUS_ERROR = MAKE_RETURN_CODE(0xA7);
//! [EXPORT] : [COMMENT] Reply has invalid type ID (should be of action reply type)
static const ReturnValue_t INVALID_TYPE_ID = MAKE_RETURN_CODE(0xA8);
// Size of one image part which can be sent per action request
static const size_t SIZE_IMAGE_PART = 1024;
static const uint32_t FLASH_REGION_SIZE = 0x20000;
class ImageDownload {
public:
static const uint32_t LAST_POSITION = 4095;
};
static const uint32_t MAX_POLLS = 10000;
static const uint8_t ACTION_DATA_OFFSET = 2;
static const uint8_t POS_OFFSET = 2;
static const uint8_t IMAGE_DATA_OFFSET = 5;
static const uint8_t FLASH_READ_DATA_OFFSET = 8;
static const uint8_t REGION_OFFSET = 2;
static const uint8_t ADDRESS_OFFSET = 3;
static const uint8_t LENGTH_OFFSET = 7;
static const size_t CHUNK_SIZE = 1024;
static const size_t CONFIG_MAX_DOWNLOAD_RETRIES = 3;
static const uint32_t FLASH_ERASE_DELAY = 500;
enum class InternalState { IDLE, UPLOAD_IMAGE, DOWNLOAD_IMAGE, FLASH_READ, FIRMWARE_UPDATE };
InternalState internalState = InternalState::IDLE;
ArcsecDatalinkLayer datalinkLayer;
BinarySemaphore semaphore;
class UploadImage {
public:
// Name including absolute path of image to upload
std::string uploadFile;
};
UploadImage uploadImage;
class DownloadImage {
public:
// Path where the downloaded image will be stored
std::string path;
// Default name of downloaded image, can be changed via command
std::string filename = "image.bin";
};
DownloadImage downloadImage;
class FlashWrite {
public:
// File which contains data to write when executing the flash write command
std::string fullname;
// The first region to write to
uint8_t firstRegion = 0;
// Maximum region the flash write command is allowed to write to
uint8_t lastRegion = 0;
// Will be set with the flash write command and specifies the start address where to write the
// flash data to
uint32_t address = 0;
};
FlashWrite flashWrite;
class FlashRead {
public:
// Path where the file containing the read data will be stored
std::string path = "";
// Default name of file containing the data read from flash, can be changed via command
std::string filename = "flashread.bin";
// Will be set with the flash read command
uint8_t startRegion = 0;
// Number of bytes to read from flash
uint32_t size = 0;
};
FlashRead flashRead;
#ifdef XIPHOS_Q7S
SdCardManager* sdcMan = nullptr;
#endif
uint8_t commandBuffer[startracker::MAX_FRAME_SIZE];
bool terminate = false;
#ifdef EGSE
bool timestamping = false;
#else
bool timestamping = true;
#endif
/**
* UART communication object responsible for low level access of star tracker
* Must be set by star tracker handler
*/
UartComIF* uartComIF = nullptr;
// Communication cookie. Must be set by the star tracker handler
CookieIF* comCookie = nullptr;
// Queue id of raw data receiver
MessageQueueId_t rawDataReceiver = MessageQueueIF::NO_QUEUE;
/**
* @brief Performs image uploading
*/
ReturnValue_t performImageUpload();
/**
* @brief Performs firmware update
*
* @return RETURN_OK if successful, otherwise error return value
*/
ReturnValue_t performFirmwareUpdate();
/**
* @brief Performs download of last taken image from the star tracker.
*
* @details Download is split over multiple packets transporting each a maximum of 1024 bytes.
* In case the download of one position fails, the same packet will be again
* requested. If the download of the packet fails CONFIG_MAX_DOWNLOAD_RETRIES times,
* the download will be stopped.
*/
ReturnValue_t performImageDownload();
/**
* @brief Handles flash write procedure
*
* @param ID of first region to write to
*
* @return RETURN_OK if successful, otherwise RETURN_FAILED
*/
ReturnValue_t performFlashWrite();
/**
* @brief Sends a sequence of commands to the star tracker to read larger parts from the
* flash memory.
*/
ReturnValue_t performFlashRead();
/**
* @brief Sends packet to the star tracker and reads reply by using the communication
* interface
*
* @param size Size of data beforehand written to the commandBuffer
* @param parameter Parameter 2 of trigger event function
* @param delayMs Delay in milliseconds between send and receive call
*
* @return RETURN_OK if successful, otherwise RETURN_FAILED
*/
ReturnValue_t sendAndRead(size_t size, uint32_t parameter, uint32_t delayMs = 0);
/**
* @brief Checks the header (type id and status fields) of the action reply
*
* @return RETURN_OK if reply confirms success of packet transfer, otherwise REUTRN_FAILED
*/
ReturnValue_t checkActionReply();
/**
* @brief Checks the position field in a star tracker upload/download reply.
*
* @param expectedPosition Value of expected position
*
* @return RETURN_OK if received position matches expected position, otherwise RETURN_FAILED
*/
ReturnValue_t checkReplyPosition(uint32_t expectedPosition);
#ifdef XIPHOS_Q7S
/**
* @brief Checks if a path points to an sd card and whether the SD card is monuted.
*
* @return SD_NOT_MOUNTED id SD card is not mounted, otherwise RETURN_OK
*/
ReturnValue_t checkPath(std::string name);
#endif
/**
* @brief Unlocks a range of flash regions
*
* @param from First region in range to unlock
* @param to Last region in range to unlock
*
*/
ReturnValue_t unlockAndEraseRegions(uint32_t from, uint32_t to);
/**
* @brief Creates full filename either with timestamp or without
*
* @param path Path where to create the file
* @param filename Name fo the file
*
* @return Full filename
*/
std::string makeFullFilename(std::string path, std::string filename);
};
#endif /* BSP_Q7S_DEVICES_STRHELPER_H_ */

View File

@ -9,6 +9,7 @@
#cmakedefine RASPBERRY_PI
#cmakedefine XIPHOS_Q7S
#cmakedefine BEAGLEBONEBLACK
#cmakedefine EGSE
#ifdef RASPBERRY_PI
#include "rpiConfig.h"
@ -35,9 +36,9 @@ debugging. */
#define OBSW_USE_CCSDS_IP_CORE 1
// Set to 1 if all telemetry should be sent to the PTME IP Core
#define OBSW_TM_TO_PTME 1
#define OBSW_TM_TO_PTME 0
// Set to 1 if telecommands are received via the PDEC IP Core
#define OBSW_TC_FROM_PDEC 1
#define OBSW_TC_FROM_PDEC 0
#define OBSW_ENABLE_TIMERS 1
#define OBSW_ADD_MGT 1
@ -52,17 +53,24 @@ debugging. */
#define OBSW_ADD_RTD_DEVICES 0
#define OBSW_ADD_TMP_DEVICES 0
#define OBSW_ADD_RAD_SENSORS 0
#define OBSW_ADD_PL_PCDU 0
#define OBSW_ADD_SYRLINKS 0
#define OBSW_ENABLE_SYRLINKS_TRANSMIT_TIMEOUT 0
#define OBSW_SYRLINKS_SIMULATED 1
#define OBSW_STAR_TRACKER_GROUND_CONFIG 1
#define OBSW_ENABLE_PERIODIC_HK 0
#endif
#ifdef EGSE
#define OBSW_ADD_STAR_TRACKER 1
#endif
/*******************************************************************/
/** All of the following flags should be disabled for mission code */
/*******************************************************************/
//! /* Can be used to switch device to NORMAL mode immediately */
// Can be used to switch device to NORMAL mode immediately
#define OBSW_SWITCH_TO_NORMAL_MODE_AFTER_STARTUP 1
#define OBSW_PRINT_MISSED_DEADLINES 1
@ -76,9 +84,17 @@ debugging. */
#define OBSW_ADD_I2C_TEST_CODE 0
#define OBSW_ADD_UART_TEST_CODE 0
#define OBSW_TEST_ACS 0
#define OBSW_DEBUG_ACS 0
#define OBSW_TEST_SUS 0
#define OBSW_DEBUG_SUS 0
#define OBSW_TEST_RTD 0
#define OBSW_DEBUG_RTD 0
#define OBSW_TEST_RAD_SENSOR 0
#define OBSW_DEBUG_RAD_SENSOR 0
#define OBSW_TEST_PL_PCDU 0
#define OBSW_DEBUG_PL_PCDU 0
#define OBSW_TEST_LIBGPIOD 0
#define OBSW_TEST_RADIATION_SENSOR_HANDLER 0
#define OBSW_TEST_SUS_HANDLER 0
#define OBSW_TEST_PLOC_HANDLER 0
#define OBSW_TEST_BPX_BATT 0
#define OBSW_TEST_CCSDS_BRIDGE 0
@ -86,7 +102,6 @@ debugging. */
#define OBSW_TEST_TE7020_HEATER 0
#define OBSW_TEST_GPIO_OPEN_BY_LABEL 0
#define OBSW_TEST_GPIO_OPEN_BY_LINE_NAME 0
#define OBSW_DEBUG_P60DOCK 0
#define OBSW_DEBUG_BPX_BATT 0
#define OBSW_DEBUG_PDU1 0
@ -95,15 +110,17 @@ debugging. */
#define OBSW_DEBUG_ACU 0
#define OBSW_DEBUG_SYRLINKS 0
#define OBSW_DEBUG_IMTQ 0
#define OBSW_DEBUG_RAD_SENSOR 0
#define OBSW_DEBUG_SUS 0
#define OBSW_DEBUG_RTD 0
#define OBSW_DEBUG_RW 0
#define OBSW_DEBUG_STARTRACKER 0
#define OBSW_DEBUG_PLOC_MPSOC 0
#define OBSW_DEBUG_PLOC_SUPERVISOR 0
#define OBSW_DEBUG_PDEC_HANDLER 0
#ifdef EGSE
#define OBSW_DEBUG_STARTRACKER 1
#else
#define OBSW_DEBUG_STARTRACKER 0
#endif
#ifdef RASPBERRY_PI
#define OBSW_ENABLE_TIMERS 1

View File

@ -1,7 +1 @@
/**
* \file logicalAddresses.cpp
*
* \date 06.11.2019
*/
#include "addresses.h"

View File

@ -24,6 +24,7 @@ enum logicalAddresses : address_t {
RAD_SENSOR = objects::RAD_SENSOR,
SUS_0 = objects::SUS_0,
SUS_1 = objects::SUS_1,
SUS_2 = objects::SUS_2,
SUS_3 = objects::SUS_3,
@ -35,8 +36,6 @@ enum logicalAddresses : address_t {
SUS_9 = objects::SUS_9,
SUS_10 = objects::SUS_10,
SUS_11 = objects::SUS_11,
SUS_12 = objects::SUS_12,
SUS_13 = objects::SUS_13,
/* Dummy and Test Addresses */
DUMMY_ECHO = 129,
@ -71,7 +70,8 @@ enum spiAddresses : address_t {
RW1,
RW2,
RW3,
RW4
RW4,
PLPCDU_ADC
};
/* Addresses of devices supporting the CSP protocol */

View File

@ -54,6 +54,7 @@ enum gpioId_t {
RTD_IC_17,
RTD_IC_18,
CS_SUS_0,
CS_SUS_1,
CS_SUS_2,
CS_SUS_3,
@ -65,17 +66,16 @@ enum gpioId_t {
CS_SUS_9,
CS_SUS_10,
CS_SUS_11,
CS_SUS_12,
CS_SUS_13,
SPI_MUX_BIT_0,
SPI_MUX_BIT_1,
SPI_MUX_BIT_2,
SPI_MUX_BIT_3,
SPI_MUX_BIT_4,
SPI_MUX_BIT_5,
SPI_MUX_BIT_6,
CS_RAD_SENSOR,
ENABLE_RADFET,
PAPB_BUSY_N,
PAPB_EMPTY,
@ -110,7 +110,16 @@ enum gpioId_t {
RS485_EN_RX_DATA,
RS485_EN_RX_CLOCK,
BIT_RATE_SEL
BIT_RATE_SEL,
PLPCDU_ENB_VBAT0,
PLPCDU_ENB_VBAT1,
PLPCDU_ENB_DRO,
PLPCDU_ENB_X8,
PLPCDU_ENB_TX,
PLPCDU_ENB_HPA,
PLPCDU_ENB_MPA,
PLPCDU_ADC_CS
};
}

View File

@ -1,7 +1,7 @@
/**
* @brief Auto-generated event translation file. Contains 140 translations.
* @brief Auto-generated event translation file. Contains 139 translations.
* @details
* Generated on: 2022-02-03 17:30:40
* Generated on: 2022-02-27 15:36:42
*/
#include "translateEvents.h"
@ -107,6 +107,8 @@ const char *SELF_TEST_MTM_RANGE_FAILURE_STRING = "SELF_TEST_MTM_RANGE_FAILURE";
const char *SELF_TEST_COIL_CURRENT_FAILURE_STRING = "SELF_TEST_COIL_CURRENT_FAILURE";
const char *INVALID_ERROR_BYTE_STRING = "INVALID_ERROR_BYTE";
const char *ERROR_STATE_STRING = "ERROR_STATE";
const char *BOOTING_FIRMWARE_FAILED_STRING = "BOOTING_FIRMWARE_FAILED";
const char *BOOTING_BOOTLOADER_FAILED_STRING = "BOOTING_BOOTLOADER_FAILED";
const char *SUPV_MEMORY_READ_RPT_CRC_FAILURE_STRING = "SUPV_MEMORY_READ_RPT_CRC_FAILURE";
const char *SUPV_ACK_FAILURE_STRING = "SUPV_ACK_FAILURE";
const char *SUPV_EXE_FAILURE_STRING = "SUPV_EXE_FAILURE";
@ -131,12 +133,9 @@ const char *IMAGE_UPLOAD_SUCCESSFUL_STRING = "IMAGE_UPLOAD_SUCCESSFUL";
const char *IMAGE_DOWNLOAD_SUCCESSFUL_STRING = "IMAGE_DOWNLOAD_SUCCESSFUL";
const char *FLASH_WRITE_SUCCESSFUL_STRING = "FLASH_WRITE_SUCCESSFUL";
const char *FLASH_READ_SUCCESSFUL_STRING = "FLASH_READ_SUCCESSFUL";
const char *FLASH_WRITE_FAILED_STRING = "FLASH_WRITE_FAILED";
const char *FLASH_READ_FAILED_STRING = "FLASH_READ_FAILED";
const char *FPGA_DOWNLOAD_SUCCESSFUL_STRING = "FPGA_DOWNLOAD_SUCCESSFUL";
const char *FPGA_DOWNLOAD_FAILED_STRING = "FPGA_DOWNLOAD_FAILED";
const char *FPGA_UPLOAD_SUCCESSFUL_STRING = "FPGA_UPLOAD_SUCCESSFUL";
const char *FPGA_UPLOAD_FAILED_STRING = "FPGA_UPLOAD_FAILED";
const char *FIRMWARE_UPDATE_SUCCESSFUL_STRING = "FIRMWARE_UPDATE_SUCCESSFUL";
const char *FIRMWARE_UPDATE_FAILED_STRING = "FIRMWARE_UPDATE_FAILED";
const char *STR_HELPER_READING_REPLY_FAILED_STRING = "STR_HELPER_READING_REPLY_FAILED";
const char *STR_HELPER_COM_ERROR_STRING = "STR_HELPER_COM_ERROR";
const char *STR_HELPER_NO_REPLY_STRING = "STR_HELPER_NO_REPLY";
@ -352,6 +351,10 @@ const char *translateEvents(Event event) {
return INVALID_ERROR_BYTE_STRING;
case (11301):
return ERROR_STATE_STRING;
case (11401):
return BOOTING_FIRMWARE_FAILED_STRING;
case (11402):
return BOOTING_BOOTLOADER_FAILED_STRING;
case (11501):
return SUPV_MEMORY_READ_RPT_CRC_FAILURE_STRING;
case (11502):
@ -401,32 +404,26 @@ const char *translateEvents(Event event) {
case (12005):
return FLASH_READ_SUCCESSFUL_STRING;
case (12006):
return FLASH_WRITE_FAILED_STRING;
case (12007):
return FLASH_READ_FAILED_STRING;
case (12007):
return FIRMWARE_UPDATE_SUCCESSFUL_STRING;
case (12008):
return FPGA_DOWNLOAD_SUCCESSFUL_STRING;
return FIRMWARE_UPDATE_FAILED_STRING;
case (12009):
return FPGA_DOWNLOAD_FAILED_STRING;
case (12010):
return FPGA_UPLOAD_SUCCESSFUL_STRING;
case (12011):
return FPGA_UPLOAD_FAILED_STRING;
case (12012):
return STR_HELPER_READING_REPLY_FAILED_STRING;
case (12013):
case (12010):
return STR_HELPER_COM_ERROR_STRING;
case (12014):
case (12011):
return STR_HELPER_NO_REPLY_STRING;
case (12015):
case (12012):
return STR_HELPER_DEC_ERROR_STRING;
case (12016):
case (12013):
return POSITION_MISMATCH_STRING;
case (12017):
case (12014):
return STR_HELPER_FILE_NOT_EXISTS_STRING;
case (12018):
case (12015):
return STR_HELPER_SENDING_PACKET_FAILED_STRING;
case (12019):
case (12016):
return STR_HELPER_REQUESTING_MSG_FAILED_STRING;
default:
return "UNKNOWN_EVENT";

View File

@ -1,8 +1,8 @@
/**
* @brief Auto-generated object translation file.
* @details
* Contains 110 translations.
* Generated on: 2022-02-03 12:01:36
* Contains 112 translations.
* Generated on: 2022-02-27 15:36:48
*/
#include "translateObjects.h"
@ -12,6 +12,7 @@ const char *ACS_CONTROLLER_STRING = "ACS_CONTROLLER";
const char *THERMAL_CONTROLLER_STRING = "THERMAL_CONTROLLER";
const char *MGM_0_LIS3_HANDLER_STRING = "MGM_0_LIS3_HANDLER";
const char *GYRO_0_ADIS_HANDLER_STRING = "GYRO_0_ADIS_HANDLER";
const char *SUS_0_STRING = "SUS_0";
const char *SUS_1_STRING = "SUS_1";
const char *SUS_2_STRING = "SUS_2";
const char *SUS_3_STRING = "SUS_3";
@ -23,8 +24,6 @@ const char *SUS_8_STRING = "SUS_8";
const char *SUS_9_STRING = "SUS_9";
const char *SUS_10_STRING = "SUS_10";
const char *SUS_11_STRING = "SUS_11";
const char *SUS_12_STRING = "SUS_12";
const char *SUS_13_STRING = "SUS_13";
const char *RW1_STRING = "RW1";
const char *MGM_1_RM3100_HANDLER_STRING = "MGM_1_RM3100_HANDLER";
const char *GYRO_1_L3G_HANDLER_STRING = "GYRO_1_L3G_HANDLER";
@ -44,6 +43,7 @@ const char *PDU1_HANDLER_STRING = "PDU1_HANDLER";
const char *PDU2_HANDLER_STRING = "PDU2_HANDLER";
const char *ACU_HANDLER_STRING = "ACU_HANDLER";
const char *BPX_BATT_HANDLER_STRING = "BPX_BATT_HANDLER";
const char *PLPCDU_HANDLER_STRING = "PLPCDU_HANDLER";
const char *RAD_SENSOR_STRING = "RAD_SENSOR";
const char *PLOC_UPDATER_STRING = "PLOC_UPDATER";
const char *PLOC_MEMORY_DUMPER_STRING = "PLOC_MEMORY_DUMPER";
@ -82,6 +82,7 @@ const char *PUS_PACKET_DISTRIBUTOR_STRING = "PUS_PACKET_DISTRIBUTOR";
const char *TMTC_BRIDGE_STRING = "TMTC_BRIDGE";
const char *TMTC_POLLING_TASK_STRING = "TMTC_POLLING_TASK";
const char *FILE_SYSTEM_HANDLER_STRING = "FILE_SYSTEM_HANDLER";
const char *SDC_MANAGER_STRING = "SDC_MANAGER";
const char *PTME_STRING = "PTME";
const char *PDEC_HANDLER_STRING = "PDEC_HANDLER";
const char *CCSDS_HANDLER_STRING = "CCSDS_HANDLER";
@ -109,6 +110,7 @@ const char *TIME_STAMPER_STRING = "TIME_STAMPER";
const char *FSFW_OBJECTS_END_STRING = "FSFW_OBJECTS_END";
const char *SPI_TEST_STRING = "SPI_TEST";
const char *UART_TEST_STRING = "UART_TEST";
const char *I2C_TEST_STRING = "I2C_TEST";
const char *DUMMY_HANDLER_STRING = "DUMMY_HANDLER";
const char *DUMMY_INTERFACE_STRING = "DUMMY_INTERFACE";
const char *LIBGPIOD_TEST_STRING = "LIBGPIOD_TEST";
@ -132,31 +134,29 @@ const char *translateObject(object_id_t object) {
case 0x44120010:
return GYRO_0_ADIS_HANDLER_STRING;
case 0x44120032:
return SUS_1_STRING;
return SUS_0_STRING;
case 0x44120033:
return SUS_2_STRING;
return SUS_1_STRING;
case 0x44120034:
return SUS_3_STRING;
return SUS_2_STRING;
case 0x44120035:
return SUS_4_STRING;
return SUS_3_STRING;
case 0x44120036:
return SUS_5_STRING;
return SUS_4_STRING;
case 0x44120037:
return SUS_6_STRING;
return SUS_5_STRING;
case 0x44120038:
return SUS_7_STRING;
return SUS_6_STRING;
case 0x44120039:
return SUS_8_STRING;
return SUS_7_STRING;
case 0x44120040:
return SUS_9_STRING;
return SUS_8_STRING;
case 0x44120041:
return SUS_10_STRING;
return SUS_9_STRING;
case 0x44120042:
return SUS_11_STRING;
return SUS_10_STRING;
case 0x44120043:
return SUS_12_STRING;
case 0x44120044:
return SUS_13_STRING;
return SUS_11_STRING;
case 0x44120047:
return RW1_STRING;
case 0x44120107:
@ -195,6 +195,8 @@ const char *translateObject(object_id_t object) {
return ACU_HANDLER_STRING;
case 0x44260000:
return BPX_BATT_HANDLER_STRING;
case 0x44300000:
return PLPCDU_HANDLER_STRING;
case 0x443200A5:
return RAD_SENSOR_STRING;
case 0x44330000:
@ -271,6 +273,8 @@ const char *translateObject(object_id_t object) {
return TMTC_POLLING_TASK_STRING;
case 0x50000500:
return FILE_SYSTEM_HANDLER_STRING;
case 0x50000550:
return SDC_MANAGER_STRING;
case 0x50000600:
return PTME_STRING;
case 0x50000700:
@ -325,6 +329,8 @@ const char *translateObject(object_id_t object) {
return SPI_TEST_STRING;
case 0x54000020:
return UART_TEST_STRING;
case 0x54000030:
return I2C_TEST_STRING;
case 0x5400AFFE:
return DUMMY_HANDLER_STRING;
case 0x5400CAFE:

View File

@ -5,10 +5,6 @@
#include <fsfw/serviceinterface/ServiceInterfaceStream.h>
#include <fsfw/tasks/FixedTimeslotTaskIF.h>
#include "OBSWConfig.h"
#include "linux/devices/SusHandler.h"
#include "objects/systemObjectList.h"
ReturnValue_t pst::pstGpio(FixedTimeslotTaskIF *thisSequence) {
// Length of a communication cycle
uint32_t length = thisSequence->getPeriodMs();
@ -153,6 +149,19 @@ ReturnValue_t pst::pstSpi(FixedTimeslotTaskIF *thisSequence) {
#endif
#if OBSW_ADD_SUN_SENSORS == 1
bool addSus0 = true;
bool addSus1 = true;
bool addSus2 = true;
bool addSus3 = true;
bool addSus4 = true;
bool addSus5 = true;
bool addSus6 = true;
bool addSus7 = true;
bool addSus8 = true;
bool addSus9 = true;
bool addSus10 = true;
bool addSus11 = true;
/**
* 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
@ -161,253 +170,157 @@ ReturnValue_t pst::pstSpi(FixedTimeslotTaskIF *thisSequence) {
* 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_1, length * 0.9, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_1, length * 0.9, SusHandler::FIRST_WRITE);
thisSequence->addSlot(objects::SUS_1, length * 0.9, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_1, length * 0.9, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_1, length * 0.9, DeviceHandlerIF::GET_READ);
/* Write setup */
thisSequence->addSlot(objects::SUS_1, length * 0.901, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_1, length * 0.901, SusHandler::FIRST_WRITE);
thisSequence->addSlot(objects::SUS_1, length * 0.901, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_1, length * 0.901, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_1, length * 0.901, DeviceHandlerIF::GET_READ);
/* Write setup */
thisSequence->addSlot(objects::SUS_1, length * 0.902, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_1, length * 0.902, SusHandler::FIRST_WRITE);
thisSequence->addSlot(objects::SUS_1, length * 0.902, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_1, length * 0.902, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_1, length * 0.902, DeviceHandlerIF::GET_READ);
if (addSus0) {
/* Write setup */
thisSequence->addSlot(objects::SUS_0, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_0, length * 0, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_0, length * 0, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_0, length * 0, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_0, length * 0, DeviceHandlerIF::GET_READ);
/* Write setup */
thisSequence->addSlot(objects::SUS_2, length * 0.903, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_2, length * 0.903, SusHandler::FIRST_WRITE);
thisSequence->addSlot(objects::SUS_2, length * 0.903, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_2, length * 0.903, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_2, length * 0.903, DeviceHandlerIF::GET_READ);
/* Write setup */
thisSequence->addSlot(objects::SUS_2, length * 0.904, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_2, length * 0.904, SusHandler::SEND_WRITE);
thisSequence->addSlot(objects::SUS_2, length * 0.904, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_2, length * 0.904, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_2, length * 0.904, DeviceHandlerIF::GET_READ);
/* Write setup */
thisSequence->addSlot(objects::SUS_2, length * 0.905, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_2, length * 0.905, SusHandler::SEND_WRITE);
thisSequence->addSlot(objects::SUS_2, length * 0.905, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_2, length * 0.905, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_2, length * 0.905, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::SUS_0, length * 0.4, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_0, length * 0.4, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_0, length * 0.4, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_0, length * 0.4, DeviceHandlerIF::GET_READ);
}
if (addSus1) {
thisSequence->addSlot(objects::SUS_1, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_1, length * 0, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_1, length * 0, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_1, length * 0, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_1, length * 0, DeviceHandlerIF::GET_READ);
/* Write setup */
thisSequence->addSlot(objects::SUS_3, length * 0.8, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_3, length * 0.8, SusHandler::FIRST_WRITE);
thisSequence->addSlot(objects::SUS_3, length * 0.8, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_3, length * 0.8, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_3, length * 0.8, DeviceHandlerIF::GET_READ);
/* Write setup */
thisSequence->addSlot(objects::SUS_3, length * 0.91, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_3, length * 0.91, SusHandler::SEND_WRITE);
thisSequence->addSlot(objects::SUS_3, length * 0.91, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_3, length * 0.91, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_3, length * 0.91, DeviceHandlerIF::GET_READ);
/* Write setup */
thisSequence->addSlot(objects::SUS_3, length * 0.93, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_3, length * 0.93, SusHandler::SEND_WRITE);
thisSequence->addSlot(objects::SUS_3, length * 0.93, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_3, length * 0.93, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_3, length * 0.93, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::SUS_1, length * 0.4, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_1, length * 0.4, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_1, length * 0.4, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_1, length * 0.4, DeviceHandlerIF::GET_READ);
}
if (addSus2) {
thisSequence->addSlot(objects::SUS_2, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_2, length * 0, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_2, length * 0, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_2, length * 0, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_2, length * 0, DeviceHandlerIF::GET_READ);
/* Write setup */
thisSequence->addSlot(objects::SUS_4, length * 0.909, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_4, length * 0.909, SusHandler::FIRST_WRITE);
thisSequence->addSlot(objects::SUS_4, length * 0.909, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_4, length * 0.909, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_4, length * 0.909, DeviceHandlerIF::GET_READ);
/* Write setup */
thisSequence->addSlot(objects::SUS_4, length * 0.91, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_4, length * 0.91, SusHandler::FIRST_WRITE);
thisSequence->addSlot(objects::SUS_4, length * 0.91, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_4, length * 0.91, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_4, length * 0.91, DeviceHandlerIF::GET_READ);
/* Write setup */
thisSequence->addSlot(objects::SUS_4, length * 0.911, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_4, length * 0.911, SusHandler::FIRST_WRITE);
thisSequence->addSlot(objects::SUS_4, length * 0.911, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_4, length * 0.911, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_4, length * 0.911, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::SUS_2, length * 0.4, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_2, length * 0.4, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_2, length * 0.4, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_2, length * 0.4, DeviceHandlerIF::GET_READ);
}
if (addSus3) {
thisSequence->addSlot(objects::SUS_3, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_3, length * 0, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_3, length * 0, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_3, length * 0, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_3, length * 0, DeviceHandlerIF::GET_READ);
/* Write setup */
thisSequence->addSlot(objects::SUS_5, length * 0.912, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_5, length * 0.912, SusHandler::FIRST_WRITE);
thisSequence->addSlot(objects::SUS_5, length * 0.912, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_5, length * 0.912, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_5, length * 0.912, DeviceHandlerIF::GET_READ);
/* Write setup */
thisSequence->addSlot(objects::SUS_5, length * 0.913, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_5, length * 0.913, SusHandler::FIRST_WRITE);
thisSequence->addSlot(objects::SUS_5, length * 0.913, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_5, length * 0.913, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_5, length * 0.913, DeviceHandlerIF::GET_READ);
/* Write setup */
thisSequence->addSlot(objects::SUS_5, length * 0.914, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_5, length * 0.914, SusHandler::FIRST_WRITE);
thisSequence->addSlot(objects::SUS_5, length * 0.914, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_5, length * 0.914, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_5, length * 0.914, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::SUS_3, length * 0.4, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_3, length * 0.4, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_3, length * 0.4, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_3, length * 0.4, DeviceHandlerIF::GET_READ);
}
if (addSus4) {
thisSequence->addSlot(objects::SUS_4, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_4, length * 0, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_4, length * 0, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_4, length * 0, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_4, length * 0, DeviceHandlerIF::GET_READ);
/* Write setup */
thisSequence->addSlot(objects::SUS_6, length * 0.915, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_6, length * 0.915, SusHandler::FIRST_WRITE);
thisSequence->addSlot(objects::SUS_6, length * 0.915, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_6, length * 0.915, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_6, length * 0.915, DeviceHandlerIF::GET_READ);
/* Start ADC conversions */
thisSequence->addSlot(objects::SUS_6, length * 0.916, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_6, length * 0.916, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_6, length * 0.916, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_6, length * 0.916, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_6, length * 0.916, DeviceHandlerIF::GET_READ);
/* Read ADC conversions from inernal FIFO */
thisSequence->addSlot(objects::SUS_6, length * 0.917, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_6, length * 0.917, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_6, length * 0.917, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_6, length * 0.917, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_6, length * 0.917, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::SUS_4, length * 0.4, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_4, length * 0.4, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_4, length * 0.4, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_4, length * 0.4, DeviceHandlerIF::GET_READ);
}
if (addSus5) {
thisSequence->addSlot(objects::SUS_5, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_5, length * 0, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_5, length * 0, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_5, length * 0, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_5, length * 0, DeviceHandlerIF::GET_READ);
/* Write setup */
thisSequence->addSlot(objects::SUS_7, length * 0.918, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_7, length * 0.918, SusHandler::FIRST_WRITE);
thisSequence->addSlot(objects::SUS_7, length * 0.918, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_7, length * 0.918, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_7, length * 0.918, DeviceHandlerIF::GET_READ);
/* Start ADC conversions */
thisSequence->addSlot(objects::SUS_7, length * 0.919, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_7, length * 0.919, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_7, length * 0.919, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_7, length * 0.919, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_7, length * 0.919, DeviceHandlerIF::GET_READ);
/* Read ADC conversions from inernal FIFO */
thisSequence->addSlot(objects::SUS_7, length * 0.92, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_7, length * 0.92, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_7, length * 0.92, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_7, length * 0.92, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_7, length * 0.92, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::SUS_5, length * 0.4, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_5, length * 0.4, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_5, length * 0.4, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_5, length * 0.4, DeviceHandlerIF::GET_READ);
}
/* Write setup */
thisSequence->addSlot(objects::SUS_8, length * 0.921, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_8, length * 0.921, SusHandler::FIRST_WRITE);
thisSequence->addSlot(objects::SUS_8, length * 0.921, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_8, length * 0.921, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_8, length * 0.921, DeviceHandlerIF::GET_READ);
/* Start ADC conversions */
thisSequence->addSlot(objects::SUS_8, length * 0.922, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_8, length * 0.922, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_8, length * 0.922, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_8, length * 0.922, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_8, length * 0.922, DeviceHandlerIF::GET_READ);
/* Read ADC conversions from inernal FIFO */
thisSequence->addSlot(objects::SUS_8, length * 0.923, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_8, length * 0.923, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_8, length * 0.923, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_8, length * 0.923, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_8, length * 0.923, DeviceHandlerIF::GET_READ);
if (addSus6) {
thisSequence->addSlot(objects::SUS_6, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_6, length * 0, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_6, length * 0, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_6, length * 0, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_6, length * 0, DeviceHandlerIF::GET_READ);
/* Write setup */
thisSequence->addSlot(objects::SUS_9, length * 0.924, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_9, length * 0.924, SusHandler::FIRST_WRITE);
thisSequence->addSlot(objects::SUS_9, length * 0.924, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_9, length * 0.924, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_9, length * 0.924, DeviceHandlerIF::GET_READ);
/* Start ADC conversions */
thisSequence->addSlot(objects::SUS_9, length * 0.925, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_9, length * 0.925, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_9, length * 0.925, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_9, length * 0.925, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_9, length * 0.925, DeviceHandlerIF::GET_READ);
/* Read ADC conversions */
thisSequence->addSlot(objects::SUS_9, length * 0.926, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_9, length * 0.926, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_9, length * 0.926, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_9, length * 0.926, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_9, length * 0.926, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::SUS_6, length * 0.4, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_6, length * 0.4, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_6, length * 0.4, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_6, length * 0.4, DeviceHandlerIF::GET_READ);
}
/* Write setup */
thisSequence->addSlot(objects::SUS_10, length * 0.927, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_10, length * 0.927, SusHandler::FIRST_WRITE);
thisSequence->addSlot(objects::SUS_10, length * 0.927, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_10, length * 0.927, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_10, length * 0.927, DeviceHandlerIF::GET_READ);
/* Start ADC conversions */
thisSequence->addSlot(objects::SUS_10, length * 0.928, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_10, length * 0.928, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_10, length * 0.928, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_10, length * 0.928, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_10, length * 0.928, DeviceHandlerIF::GET_READ);
/* Read ADC conversions */
thisSequence->addSlot(objects::SUS_10, length * 0.929, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_10, length * 0.929, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_10, length * 0.929, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_10, length * 0.929, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_10, length * 0.929, DeviceHandlerIF::GET_READ);
if (addSus7) {
thisSequence->addSlot(objects::SUS_7, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_7, length * 0, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_7, length * 0, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_7, length * 0, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_7, length * 0, DeviceHandlerIF::GET_READ);
/* Write setup */
thisSequence->addSlot(objects::SUS_11, length * 0.93, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_11, length * 0.93, SusHandler::FIRST_WRITE);
thisSequence->addSlot(objects::SUS_11, length * 0.93, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_11, length * 0.93, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_11, length * 0.93, DeviceHandlerIF::GET_READ);
/* Start ADC conversions */
thisSequence->addSlot(objects::SUS_11, length * 0.931, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_11, length * 0.931, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_11, length * 0.931, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_11, length * 0.931, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_11, length * 0.931, DeviceHandlerIF::GET_READ);
/* Read ADC conversions */
thisSequence->addSlot(objects::SUS_11, length * 0.932, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_11, length * 0.932, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_11, length * 0.932, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_11, length * 0.932, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_11, length * 0.932, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::SUS_7, length * 0.4, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_7, length * 0.4, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_7, length * 0.4, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_7, length * 0.4, DeviceHandlerIF::GET_READ);
}
/* Write setup */
thisSequence->addSlot(objects::SUS_12, length * 0.933, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_12, length * 0.933, SusHandler::FIRST_WRITE);
thisSequence->addSlot(objects::SUS_12, length * 0.933, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_12, length * 0.933, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_12, length * 0.933, DeviceHandlerIF::GET_READ);
/* Start ADC conversions */
thisSequence->addSlot(objects::SUS_12, length * 0.934, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_12, length * 0.934, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_12, length * 0.934, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_12, length * 0.934, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_12, length * 0.934, DeviceHandlerIF::GET_READ);
/* Read ADC conversions */
thisSequence->addSlot(objects::SUS_12, length * 0.935, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_12, length * 0.935, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_12, length * 0.935, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_12, length * 0.935, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_12, length * 0.935, DeviceHandlerIF::GET_READ);
if (addSus8) {
thisSequence->addSlot(objects::SUS_8, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_8, length * 0, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_8, length * 0, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_8, length * 0, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_8, length * 0, DeviceHandlerIF::GET_READ);
/* Write setup */
thisSequence->addSlot(objects::SUS_13, length * 0.936, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_13, length * 0.936, SusHandler::FIRST_WRITE);
thisSequence->addSlot(objects::SUS_13, length * 0.936, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_13, length * 0.936, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_13, length * 0.936, DeviceHandlerIF::GET_READ);
/* Start ADC conversions */
thisSequence->addSlot(objects::SUS_13, length * 0.937, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_13, length * 0.937, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_13, length * 0.937, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_13, length * 0.937, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_13, length * 0.937, DeviceHandlerIF::GET_READ);
/* Read ADC conversions */
thisSequence->addSlot(objects::SUS_13, length * 0.938, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_13, length * 0.938, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_13, length * 0.938, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_13, length * 0.938, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_13, length * 0.938, DeviceHandlerIF::GET_READ);
#endif
thisSequence->addSlot(objects::SUS_8, length * 0.4, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_8, length * 0.4, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_8, length * 0.4, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_8, length * 0.4, DeviceHandlerIF::GET_READ);
}
if (addSus9) {
thisSequence->addSlot(objects::SUS_9, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_9, length * 0, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_9, length * 0, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_9, length * 0, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_9, length * 0, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::SUS_9, length * 0.4, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_9, length * 0.4, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_9, length * 0.4, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_9, length * 0.4, DeviceHandlerIF::GET_READ);
}
if (addSus10) {
thisSequence->addSlot(objects::SUS_10, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_10, length * 0, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_10, length * 0, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_10, length * 0, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_10, length * 0, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::SUS_10, length * 0.4, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_10, length * 0.4, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_10, length * 0.4, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_10, length * 0.4, DeviceHandlerIF::GET_READ);
}
if (addSus11) {
thisSequence->addSlot(objects::SUS_11, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_11, length * 0, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_11, length * 0, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_11, length * 0, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_11, length * 0, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::SUS_11, length * 0.4, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_11, length * 0.4, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_11, length * 0.4, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_11, length * 0.4, DeviceHandlerIF::GET_READ);
}
#endif /* OBSW_ADD_SUN_SENSORS == 1 */
#if OBSW_ADD_RW == 1
thisSequence->addSlot(objects::RW1, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
@ -436,8 +349,8 @@ ReturnValue_t pst::pstSpi(FixedTimeslotTaskIF *thisSequence) {
#endif
#if OBSW_ADD_ACS_BOARD == 1 && OBSW_ADD_ACS_HANDLERS == 1
bool enableAside = true;
bool enableBside = false;
bool enableAside = false;
bool enableBside = true;
if (enableAside) {
// A side
thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0,
@ -452,21 +365,21 @@ ReturnValue_t pst::pstSpi(FixedTimeslotTaskIF *thisSequence) {
thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.25,
DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.6, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.75, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.7, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.85, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, length * 0,
DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, length * 0.3, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, length * 0.25, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, length * 0.6, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, length * 0.75, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, length * 0.7, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, length * 0.85, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0,
DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.35, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.25, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.6, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.75, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.7, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.85, DeviceHandlerIF::GET_READ);
}
@ -474,7 +387,7 @@ ReturnValue_t pst::pstSpi(FixedTimeslotTaskIF *thisSequence) {
// B side
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.25, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::MGM_2_LIS3_HANDLER, length * 0.6, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::MGM_2_LIS3_HANDLER, length * 0.7, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::MGM_2_LIS3_HANDLER, length * 0.85, DeviceHandlerIF::GET_READ);
@ -484,21 +397,21 @@ ReturnValue_t pst::pstSpi(FixedTimeslotTaskIF *thisSequence) {
thisSequence->addSlot(objects::MGM_3_RM3100_HANDLER, length * 0.25,
DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::MGM_3_RM3100_HANDLER, length * 0.6, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::MGM_3_RM3100_HANDLER, length * 0.75, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::MGM_3_RM3100_HANDLER, length * 0.7, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::MGM_3_RM3100_HANDLER, length * 0.85, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::GYRO_2_ADIS_HANDLER, length * 0,
DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::GYRO_2_ADIS_HANDLER, length * 0.3, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::GYRO_2_ADIS_HANDLER, length * 0.25, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::GYRO_2_ADIS_HANDLER, length * 0.6, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::GYRO_2_ADIS_HANDLER, length * 0.75, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::GYRO_2_ADIS_HANDLER, length * 0.7, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::GYRO_2_ADIS_HANDLER, length * 0.85, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::GYRO_3_L3G_HANDLER, length * 0,
DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::GYRO_3_L3G_HANDLER, length * 0.35, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::GYRO_3_L3G_HANDLER, length * 0.25, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::GYRO_3_L3G_HANDLER, length * 0.6, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::GYRO_3_L3G_HANDLER, length * 0.75, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::GYRO_3_L3G_HANDLER, length * 0.7, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::GYRO_3_L3G_HANDLER, length * 0.85, DeviceHandlerIF::GET_READ);
}
#endif /* OBSW_ADD_ACS_BOARD == 1 && OBSW_ADD_ACS_HANDLERS == 1 */
@ -519,6 +432,7 @@ ReturnValue_t pst::pstSpi(FixedTimeslotTaskIF *thisSequence) {
ReturnValue_t pst::pstI2c(FixedTimeslotTaskIF *thisSequence) {
// Length of a communication cycle
uint32_t length = thisSequence->getPeriodMs();
static_cast<void>(length);
#if OBSW_ADD_MGT == 1
thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0.2, DeviceHandlerIF::SEND_WRITE);
@ -533,6 +447,7 @@ ReturnValue_t pst::pstI2c(FixedTimeslotTaskIF *thisSequence) {
thisSequence->addSlot(objects::BPX_BATT_HANDLER, length * 0.6, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::BPX_BATT_HANDLER, length * 0.8, DeviceHandlerIF::GET_READ);
#endif
static_cast<void>(length);
if (thisSequence->checkSequence() != HasReturnvaluesIF::RETURN_OK) {
sif::error << "I2C PST initialization failed" << std::endl;
return HasReturnvaluesIF::RETURN_FAILED;
@ -555,9 +470,11 @@ ReturnValue_t pst::pstUart(FixedTimeslotTaskIF *thisSequence) {
thisSequence->addSlot(objects::PLOC_MPSOC_HANDLER, length * 0.8, DeviceHandlerIF::GET_READ);
#endif
#ifdef XIPHOS_Q7S
thisSequence->addSlot(objects::PLOC_UPDATER, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::PLOC_MEMORY_DUMPER, length * 0,
DeviceHandlerIF::PERFORM_OPERATION);
#endif
#if OBSW_ADD_PLOC_SUPERVISOR == 1
thisSequence->addSlot(objects::PLOC_SUPERVISOR_HANDLER, length * 0,
DeviceHandlerIF::PERFORM_OPERATION);
@ -586,7 +503,7 @@ ReturnValue_t pst::pstUart(FixedTimeslotTaskIF *thisSequence) {
thisSequence->addSlot(objects::STAR_TRACKER, length * 0.6, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::STAR_TRACKER, length * 0.8, DeviceHandlerIF::GET_READ);
#endif
static_cast<void>(length);
if (uartPstEmpty) {
return HasReturnvaluesIF::RETURN_OK;
}
@ -685,7 +602,7 @@ ReturnValue_t pst::pollingSequenceTE0720(FixedTimeslotTaskIF *thisSequence) {
thisSequence->addSlot(objects::PLOC_MPSOC_HANDLER, length * 0.8, DeviceHandlerIF::GET_READ);
#endif
#if OBSW_TEST_RADIATION_SENSOR_HANDLER == 1
#if OBSW_TEST_RAD_SENSOR == 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);
@ -693,7 +610,7 @@ ReturnValue_t pst::pollingSequenceTE0720(FixedTimeslotTaskIF *thisSequence) {
thisSequence->addSlot(objects::RAD_SENSOR, length * 0.8, DeviceHandlerIF::GET_READ);
#endif
#if OBSW_TEST_SUS_HANDLER == 1
#if OBSW_TEST_SUS == 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);