fixed conflicts

This commit is contained in:
Jakob Meier
2022-02-08 10:34:23 +01:00
70 changed files with 1957 additions and 609 deletions

View File

@ -1,5 +1,101 @@
#include <linux/boardtest/I2cTestClass.h>
#include "I2cTestClass.h"
I2cTestClass::I2cTestClass(object_id_t objectId) : TestTask(objectId) {}
#include <errno.h>
#include <fsfw_hal/linux/UnixFileGuard.h>
#include <linux/i2c-dev.h>
#include <sys/ioctl.h>
ReturnValue_t I2cTestClass::performPeriodicAction() { return HasReturnvaluesIF::RETURN_OK; }
#include "fsfw/globalfunctions/arrayprinter.h"
#include "fsfw/serviceinterface.h"
I2cTestClass::I2cTestClass(object_id_t objectId, std::string i2cdev)
: TestTask(objectId), i2cdev(i2cdev) {
mode = TestModes::BPX_BATTERY;
}
ReturnValue_t I2cTestClass::initialize() {
if (mode == TestModes::BPX_BATTERY) {
battInit();
}
return HasReturnvaluesIF::RETURN_OK;
}
ReturnValue_t I2cTestClass::performPeriodicAction() {
if (mode == TestModes::BPX_BATTERY) {
battPeriodic();
}
return HasReturnvaluesIF::RETURN_OK;
}
void I2cTestClass::battInit() {
sif::info << "I2cTestClass: BPX Initialization" << std::endl;
UnixFileGuard fileHelper(i2cdev, &bpxInfo.fd, O_RDWR, "I2cTestClass::sendMessage");
if (fileHelper.getOpenResult() != HasReturnvaluesIF::RETURN_OK) {
sif::error << "Opening I2C device" << i2cdev << " failed" << std::endl;
return;
}
if (ioctl(bpxInfo.fd, I2C_SLAVE, bpxInfo.addr) < 0) {
sif::error << "Failed to acquire bus access and/or talk to slave" << std::endl;
}
cmdBuf[0] = BpxBattery::PORT_PING;
cmdBuf[1] = 0x42;
sendLen = 2;
ReturnValue_t result = i2cWrite(bpxInfo.fd, cmdBuf.data(), sendLen);
if (result != HasReturnvaluesIF::RETURN_OK) {
return;
}
// Receive back port, error byte and ping reply
recvLen = 3;
result = i2cRead(bpxInfo.fd, replyBuf.data(), recvLen);
if (result != HasReturnvaluesIF::RETURN_OK) {
return;
}
sif::info << "Ping reply:" << std::endl;
arrayprinter::print(replyBuf.data(), recvLen);
if (replyBuf[2] != 0x42) {
sif::warning << "Received ping reply not expected value 0x42" << std::endl;
}
}
void I2cTestClass::battPeriodic() {
UnixFileGuard fileHelper(i2cdev, &bpxInfo.fd, O_RDWR, "I2cTestClass::sendMessage");
if (fileHelper.getOpenResult() != HasReturnvaluesIF::RETURN_OK) {
sif::error << "Opening I2C device" << i2cdev << " failed" << std::endl;
return;
}
if (ioctl(bpxInfo.fd, I2C_SLAVE, bpxInfo.addr) < 0) {
sif::error << "Failed to acquire bus access and/or talk to slave" << std::endl;
}
cmdBuf[0] = BpxBattery::PORT_GET_HK;
sendLen = 1;
ReturnValue_t result = i2cWrite(bpxInfo.fd, cmdBuf.data(), sendLen);
if (result != HasReturnvaluesIF::RETURN_OK) {
return;
}
// Receive back HK set
recvLen = 23;
result = i2cRead(bpxInfo.fd, replyBuf.data(), recvLen);
if (result != HasReturnvaluesIF::RETURN_OK) {
return;
}
sif::info << "HK reply:" << std::endl;
arrayprinter::print(replyBuf.data(), recvLen);
}
ReturnValue_t I2cTestClass::i2cWrite(int fd, uint8_t* data, size_t len) {
if (write(fd, data, len) != static_cast<ssize_t>(len)) {
sif::error << "Failed to write to I2C bus" << std::endl;
sif::error << "Error " << errno << ": " << strerror(errno) << std::endl;
return HasReturnvaluesIF::RETURN_FAILED;
}
return HasReturnvaluesIF::RETURN_OK;
}
ReturnValue_t I2cTestClass::i2cRead(int fd, uint8_t* data, size_t len) {
if (read(fd, data, len) != static_cast<ssize_t>(len)) {
sif::error << "Failed to read from I2C bus" << std::endl;
sif::error << "Error " << errno << ": " << strerror(errno) << std::endl;
return HasReturnvaluesIF::RETURN_FAILED;
}
return HasReturnvaluesIF::RETURN_OK;
}

View File

@ -3,13 +3,38 @@
#include <test/testtasks/TestTask.h>
#include <array>
#include <string>
#include "mission/devices/devicedefinitions/BpxBatteryDefinitions.h"
class I2cTestClass : public TestTask {
public:
I2cTestClass(object_id_t objectId);
I2cTestClass(object_id_t objectId, std::string i2cdev);
ReturnValue_t initialize() override;
ReturnValue_t performPeriodicAction() override;
private:
enum TestModes { NONE, BPX_BATTERY };
struct I2cInfo {
int addr = 0;
int fd = 0;
};
TestModes mode = TestModes::NONE;
void battInit();
void battPeriodic();
I2cInfo bpxInfo = {.addr = 0x07, .fd = 0};
std::string i2cdev;
size_t sendLen = 0;
size_t recvLen = 0;
std::array<uint8_t, 64> cmdBuf = {};
std::array<uint8_t, 64> replyBuf = {};
ReturnValue_t i2cWrite(int fd, uint8_t* data, size_t len);
ReturnValue_t i2cRead(int fd, uint8_t* data, size_t len);
};
#endif /* LINUX_BOARDTEST_I2CTESTCLASS_H_ */

View File

@ -17,6 +17,23 @@
UartTestClass::UartTestClass(object_id_t objectId) : TestTask(objectId) {}
ReturnValue_t UartTestClass::initialize() {
if (mode == TestModes::GPS) {
gpsInit();
}
return HasReturnvaluesIF::RETURN_OK;
}
ReturnValue_t UartTestClass::performOneShotAction() { return HasReturnvaluesIF::RETURN_OK; }
ReturnValue_t UartTestClass::performPeriodicAction() {
if (mode == TestModes::GPS) {
gpsPeriodic();
}
return HasReturnvaluesIF::RETURN_OK;
}
void UartTestClass::gpsInit() {
#if RPI_TEST_GPS_DEVICE == 1
int result = lwgps_init(&gpsData);
if (result == 0) {
@ -62,16 +79,9 @@ ReturnValue_t UartTestClass::initialize() {
// Flush received and unread data. Those are old NMEA strings which are not relevant anymore
tcflush(serialPort, TCIFLUSH);
#endif
return HasReturnvaluesIF::RETURN_OK;
}
ReturnValue_t UartTestClass::performOneShotAction() {
#if RPI_TEST_GPS_DEVICE == 1
#endif
return HasReturnvaluesIF::RETURN_OK;
}
ReturnValue_t UartTestClass::performPeriodicAction() {
void UartTestClass::gpsPeriodic() {
#if RPI_TEST_GPS_DEVICE == 1
int bytesRead = 0;
do {
@ -107,5 +117,4 @@ ReturnValue_t UartTestClass::performPeriodicAction() {
}
} while (bytesRead > 0);
#endif
return HasReturnvaluesIF::RETURN_OK;
}

View File

@ -17,6 +17,15 @@ class UartTestClass : public TestTask {
ReturnValue_t performPeriodicAction() override;
private:
enum TestModes {
GPS,
// Solar Cell Experiment
SCE
};
void gpsInit();
void gpsPeriodic();
TestModes mode = TestModes::GPS;
lwgps_t gpsData = {};
struct termios tty = {};
int serialPort = 0;

View File

@ -2,3 +2,5 @@ target_sources(${TARGET_NAME} PRIVATE
SolarArrayDeploymentHandler.cpp
SusHandler.cpp
)
add_subdirectory(startracker)

File diff suppressed because it is too large Load Diff

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,134 @@
#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_minConfidence";
static const char T2L_MIN_CONFIDENCE[] = "t2l_minConfidence";
static const char T2L_MIN_MATCHED[] = "t2l_minMatched";
} // 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(${TARGET_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,566 @@
#ifndef MISSION_DEVICES_STARTRACKERHANDLER_H_
#define MISSION_DEVICES_STARTRACKERHANDLER_H_
#include <fsfw/datapool/PoolReadGuard.h>
#include "ArcsecDatalinkLayer.h"
#include "ArcsecJsonParamBase.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;
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 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;
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(0xA3);
//! [EXPORT] : [COMMENT] Status in interface reply signals error
static const ReturnValue_t INTERFACE_REQ_FAILED = MAKE_RETURN_CODE(0xA4);
//! [EXPORT] : [COMMENT] Status in power reply signals error
static const ReturnValue_t POWER_REQ_FAILED = MAKE_RETURN_CODE(0xA5);
//! [EXPORT] : [COMMENT] Status of reply to parameter set command signals error
static const ReturnValue_t SET_PARAM_FAILED = MAKE_RETURN_CODE(0xA6);
//! [EXPORT] : [COMMENT] Status of reply to action command signals error
static const ReturnValue_t ACTION_FAILED = MAKE_RETURN_CODE(0xA7);
//! [EXPORT] : [COMMENT] Received upload image command with invalid length
static const ReturnValue_t UPLOAD_TOO_SHORT = MAKE_RETURN_CODE(0xA8);
//! [EXPORT] : [COMMENT] Received upload image command with invalid position field
static const ReturnValue_t UPLOAD_INVALID_POSITION = MAKE_RETURN_CODE(0xA8);
//! [EXPORT] : [COMMENT] Position value in upload image reply not matching sent position
static const ReturnValue_t UPLOAD_IMAGE_FAILED = MAKE_RETURN_CODE(0xA9);
//! [EXPORT] : [COMMENT] Received upload image command with invalid length
static const ReturnValue_t INVALID_UPLOAD_COMMAND = MAKE_RETURN_CODE(0xAA);
//! [EXPORT] : [COMMENT] Received invalid path string. Exceeds allowed length
static const ReturnValue_t FILE_PATH_TOO_LONG = MAKE_RETURN_CODE(0xAB);
//! [EXPORT] : [COMMENT] Name of file received with command is too long
static const ReturnValue_t FILENAME_TOO_LONG = MAKE_RETURN_CODE(0xAC);
//! [EXPORT] : [COMMENT] Received version reply with invalid program ID
static const ReturnValue_t INVALID_PROGRAM = MAKE_RETURN_CODE(0xAD);
//! [EXPORT] : [COMMENT] Status field reply signals error
static const ReturnValue_t REPLY_ERROR = MAKE_RETURN_CODE(0xAE);
//! [EXPORT] : [COMMENT] Status field of contrast reply signals error
static const ReturnValue_t CONTRAST_REQ_FAILED = MAKE_RETURN_CODE(0xAE);
//! [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(0xAF);
//! [EXPORT] : [COMMENT] Received command with invalid length (too few or too many parameters)
static const ReturnValue_t INVALID_LENGTH = MAKE_RETURN_CODE(0xB0);
//! [EXPORT] : [COMMENT] Region mismatch between send and received data
static const ReturnValue_t REGION_MISMATCH = MAKE_RETURN_CODE(0xB1);
//! [EXPORT] : [COMMENT] Address mismatch between send and received data
static const ReturnValue_t ADDRESS_MISMATCH = MAKE_RETURN_CODE(0xB2);
//! [EXPORT] : [COMMENT] Length field mismatch between send and received data
static const ReturnValue_t lENGTH_MISMATCH = MAKE_RETURN_CODE(0xB3);
//! [EXPORT] : [COMMENT] Specified file does not exist
static const ReturnValue_t FILE_NOT_EXISTS = MAKE_RETURN_CODE(0xB4);
//! [EXPORT] : [COMMENT] Reply to upload centroid does not match commanded centroid id
static const ReturnValue_t UPLOAD_CENTROID_ID_MISMATCH = MAKE_RETURN_CODE(0xB5);
//! [EXPORT] : [COMMENT] Download blob pixel command has invalid type field
static const ReturnValue_t INVALID_TYPE = MAKE_RETURN_CODE(0xB6);
//! [EXPORT] : [COMMENT] Received FPGA action command with invalid ID
static const ReturnValue_t INVALID_ID = MAKE_RETURN_CODE(0xB7);
//! [EXPORT] : [COMMENT] Received reply is too short
static const ReturnValue_t REPLY_TOO_SHORT = MAKE_RETURN_CODE(0xB8);
//! [EXPORT] : [COMMENT] Received reply with invalid CRC
static const ReturnValue_t CRC_FAILURE = MAKE_RETURN_CODE(0xB9);
//! [EXPORT] : [COMMENT] Star tracker handler currently executing a command and using the
//! communication interface
static const ReturnValue_t STR_HELPER_EXECUTING = MAKE_RETURN_CODE(0xBA);
static const size_t MAX_PATH_SIZE = 50;
static const size_t MAX_FILE_NAME = 30;
// position (uint32) + 1024 image data
static const size_t UPLOAD_COMMAND_LEN = 1028;
// Max valid position value in upload image command
static const uint16_t MAX_POSITION = 4095;
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;
class WriteCmd {
public:
static const uint8_t ADDRESS_OFFSET = 1;
static const uint8_t FILE_OFFSET = 5;
// Minimum length of a write command (region, address and filename)
static const size_t MIN_LENGTH = 7;
};
class ReadCmd {
public:
static const uint8_t ADDRESS_OFFSET = 1;
static const uint8_t LENGTH_OFFSET = 5;
static const uint8_t FILE_OFFSET = 9;
// Minimum length of a read command (region, address, length and filename)
static const size_t MIN_LENGTH = 11;
};
class EraseCmd {
public:
static const uint8_t LENGTH = 1;
uint8_t rememberRegion = 0;
};
EraseCmd eraseCmd;
class UnlockCmd {
public:
static const uint8_t CODE_OFFSET = 1;
};
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;
class SetTimeCmd {
public:
static const uint8_t LENGTH = 8;
};
class DownloadCentroidCmd {
public:
static const uint8_t LENGTH = 1;
};
class UploadCentroid {
public:
uint8_t rememberId = 0;
};
UploadCentroid uploadCentroid;
class DownloadMatchedStarCmd {
public:
static const uint8_t LENGTH = 1;
};
class DownloadDbImageCmd {
public:
static const uint8_t LENGTH = 1;
};
class DownloadBlobPixCmd {
public:
static const uint8_t LENGTH = 2;
static const uint8_t NORMAL = 0;
static const uint8_t FAST = 1;
};
class FpgaDownloadCmd {
public:
static const uint8_t MIN_LENGTH = 10;
};
class FpgaActionCmd {
public:
static const uint8_t LENGTH = 1;
static const uint8_t ID = 3;
};
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::ContrastSet contrastSet;
startracker::ChecksumSet checksumSet;
startracker::DownloadCentroidSet downloadCentroidSet;
startracker::DownloadMatchedStar downloadMatchedStar;
startracker::DownloadDBImage downloadDbImage;
startracker::DownloadBlobPixel downloadBlobPixel;
startracker::CameraSet cameraSet;
startracker::LimitsSet limitsSet;
// 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
Countdown bootCountdown;
#ifdef EGSE
std::string paramJsonFile = "/mnt/sd0/startracker/full.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 InternalState { TEMPERATURE_REQUEST };
InternalState internalState = InternalState::TEMPERATURE_REQUEST;
enum class StartupState {
IDLE,
CHECK_BOOT_STATE,
BOOT,
BOOT_DELAY,
LIMITS,
TRACKING,
MOUNTING,
IMAGE_PROCESSOR,
CAMERA,
BLOB,
CENTROIDING,
LISA,
MATCHING,
VALIDATION,
ALGO,
WAIT_FOR_EXECUTION,
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 Executes the write command
*
* @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 executeWriteCommand(const uint8_t* commandData, size_t commandDataLen);
/**
* @brief Starts the execution of the fpga download command
*
* @param commandData Pointer to buffer with command data
* @param commandDataLen Size of received command
*/
ReturnValue_t executeFpgaDownloadCommand(const uint8_t* commandData, size_t commandDataLen);
/**
* @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 executeReadCommand(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 erase a flash region
*/
ReturnValue_t prepareEraseCommand(const uint8_t* commandData, size_t commandDataLen);
/**
* @brief Fills command buffer with command to unlock flash region
*/
ReturnValue_t prepareUnlockCommand(const uint8_t* commandData, size_t commandDataLen);
/**
* @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 command buffer with command to set the unix time
*/
ReturnValue_t prepareSetTimeCommand(const uint8_t* commandData, size_t commandDataLen);
/**
* @brief Fills command buffer with command to request a centroid
*/
ReturnValue_t prepareDownloadCentroidCommand(const uint8_t* commandData, size_t commandDataLen);
/**
* @brief Fills command buffer with command to upload a centroid for testing purpose
*/
ReturnValue_t prepareUploadCentroidCommand(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 prepareRebootCommand();
/**
* @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();
void prepareContrastRequest();
/**
* @brief Fills command buffer with command to reset the error signal of the star tracker
*/
void prepareErrorResetRequest();
/**
* @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 Fills command buffer with data to request matched star.
*/
ReturnValue_t prepareDownloadMatchedStarCommand(const uint8_t* commandData,
size_t commandDataLen);
/**
* @brief Fills command buffer with data to request matched star coordinates.
*/
ReturnValue_t prepareDownloadDbImageCommand(const uint8_t* commandData, size_t commandDataLen);
/**
* @brief Fills command buffer with data to request output of the blob filter algorithm.
*/
ReturnValue_t prepareDownloadBlobPixelCommand(const uint8_t* commandData, size_t commandDataLen);
/**
* @brief With this command the FPGA update will be applied to the star tracker
*/
ReturnValue_t prepareFpgaActionCommand(const uint8_t* commandData, size_t commandDataLen);
/**
* @brief Will fill the command buffer with the command to request the set camera parameters.
*/
ReturnValue_t prepareRequestCameraParams();
/**
* @brief Will fill the command buffer with the command to request the set limits.
*/
ReturnValue_t prepareRequestLimitsParams();
/**
* @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 erase command
*/
ReturnValue_t handleEraseReply();
/**
* @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);
};
#endif /* MISSION_DEVICES_STARTRACKERHANDLER_H_ */

View File

@ -0,0 +1,634 @@
#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_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;
}

View File

@ -0,0 +1,176 @@
#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;
};
#endif /* BSP_Q7S_DEVICES_DEVICEDEFINITIONS_STARTRACKERJSONCOMMANDS_H_ */

View File

@ -0,0 +1,746 @@
#include "StrHelper.h"
#include <filesystem>
#include <fstream>
#include "OBSWConfig.h"
#include "mission/utility/Timestamp.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::DOWNLOAD_FPGA_IMAGE: {
result = performFpgaDownload();
if (result == RETURN_OK) {
triggerEvent(FPGA_DOWNLOAD_SUCCESSFUL);
} else {
triggerEvent(FPGA_DOWNLOAD_FAILED);
}
internalState = InternalState::IDLE;
break;
}
case InternalState::UPLOAD_FPGA_IMAGE: {
result = performFpgaUpload();
if (result == RETURN_OK) {
triggerEvent(FPGA_UPLOAD_SUCCESSFUL);
} else {
triggerEvent(FPGA_UPLOAD_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; }
void StrHelper::setDownloadFpgaImage(std::string filename) { fpgaDownload.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.address = 0;
flashWrite.section = static_cast<uint8_t>(RegionId::MAIN_FIRMWARE_SECTION);
internalState = InternalState::FIRMWARE_UPDATE;
semaphore.release();
terminate = false;
return RETURN_OK;
}
ReturnValue_t StrHelper::startFlashRead(std::string path, uint8_t region, uint32_t address,
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.address = address;
flashRead.region = region;
flashRead.size = length;
internalState = InternalState::FLASH_READ;
semaphore.release();
terminate = false;
return RETURN_OK;
}
ReturnValue_t StrHelper::startFpgaDownload(std::string path, uint32_t startPosition,
uint32_t length) {
fpgaDownload.path = path;
fpgaDownload.startPosition = startPosition;
fpgaDownload.length = length;
internalState = InternalState::DOWNLOAD_FPGA_IMAGE;
semaphore.release();
terminate = false;
return RETURN_OK;
}
ReturnValue_t StrHelper::startFpgaUpload(std::string uploadFile) {
fpgaUpload.uploadFile = uploadFile;
internalState = InternalState::UPLOAD_FPGA_IMAGE;
semaphore.release();
terminate = false;
return RETURN_OK;
}
ReturnValue_t StrHelper::performImageDownload() {
ReturnValue_t result;
struct DownloadActionRequest downloadReq;
uint32_t size = 0;
uint32_t retries = 0;
Timestamp timestamp;
std::string image = downloadImage.path + "/" + timestamp.str() + downloadImage.filename;
std::ofstream file(image, std::ios_base::app | 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) {
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),
IMAGE_DATA_SIZE);
downloadReq.position++;
#if OBSW_DEBUG_STARTRACKER == 1
printProgress(downloadReq.position, ImageDownload::LAST_POSITION);
#endif /* OBSW_DEBUG_STARTRACKER == 1 */
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();
while ((uploadReq.position + 1) * SIZE_IMAGE_PART < imageSize) {
if (terminate) {
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) {
return RETURN_FAILED;
}
result = checkActionReply();
if (result != RETURN_OK) {
return result;
}
#if OBSW_DEBUG_STARTRACKER == 1
printProgress((uploadReq.position + 1) * SIZE_IMAGE_PART, imageSize);
#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
printProgress((uploadReq.position + 1) * SIZE_IMAGE_PART, imageSize);
#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>(FirmwareRegions::START),
static_cast<uint32_t>(FirmwareRegions::END));
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 remainingBytes = 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();
remainingBytes = fileSize;
req.region = flashWrite.section;
req.address = flashWrite.address;
req.length = MAX_FLASH_DATA;
while (remainingBytes >= MAX_FLASH_DATA) {
if (terminate) {
return RETURN_OK;
}
file.seekg(fileSize - remainingBytes, file.beg);
file.read(reinterpret_cast<char*>(req.data), MAX_FLASH_DATA);
arc_pack_write_action_req(&req, commandBuffer, &size);
result = sendAndRead(size, req.address);
if (result != RETURN_OK) {
return result;
}
result = checkFlashActionReply(req.region, req.address, req.length);
if (result != RETURN_OK) {
return result;
}
remainingBytes = remainingBytes - MAX_FLASH_DATA;
}
file.seekg(fileSize - remainingBytes, file.beg);
file.read(reinterpret_cast<char*>(req.data), remainingBytes);
file.close();
arc_pack_write_action_req(&req, commandBuffer, &size);
result = sendAndRead(size, req.address);
if (result != RETURN_OK) {
return result;
}
result = checkFlashActionReply(req.region, req.address, req.length);
if (result != RETURN_OK) {
return result;
}
return RETURN_OK;
}
ReturnValue_t StrHelper::performFlashRead() {
ReturnValue_t result;
struct ReadActionRequest req;
uint32_t bytesRead = 0;
uint32_t size = 0;
uint32_t retries = 0;
Timestamp timestamp;
std::string fullname = flashRead.path + "/" + timestamp.str() + 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.region;
while (bytesRead < flashRead.size) {
if (terminate) {
return RETURN_OK;
}
if ((flashRead.size - bytesRead) < MAX_FLASH_DATA) {
req.length = flashRead.size - bytesRead;
} else {
req.length = MAX_FLASH_DATA;
}
req.address = flashRead.address + bytesRead;
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;
}
result = checkFlashActionReply(req.region, req.address, req.length);
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;
retries = 0;
}
file.close();
return RETURN_OK;
}
ReturnValue_t StrHelper::performFpgaDownload() {
ReturnValue_t result;
struct DownloadFPGAImageActionRequest req;
uint32_t size = 0;
uint32_t retries = 0;
Timestamp timestamp;
std::string image = fpgaDownload.path + "/" + timestamp.str() + fpgaDownload.fileName;
std::ofstream file(image, std::ios_base::app | std::ios_base::out);
if (not std::filesystem::exists(image)) {
return FILE_CREATION_FAILED;
}
req.pos = fpgaDownload.startPosition;
while (req.pos < fpgaDownload.length) {
if (terminate) {
return RETURN_OK;
}
if (fpgaDownload.length - req.pos >= FpgaDownload::MAX_DATA) {
req.length = FpgaDownload::MAX_DATA;
} else {
req.length = fpgaDownload.length - req.pos;
}
arc_pack_downloadfpgaimage_action_req(&req, commandBuffer, &size);
result = sendAndRead(size, req.pos);
if (result != RETURN_OK) {
if (retries < CONFIG_MAX_DOWNLOAD_RETRIES) {
uartComIF->flushUartRxBuffer(comCookie);
retries++;
continue;
}
file.close();
return result;
}
result = checkFpgaActionReply(req.pos, req.length);
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() + FpgaDownload::DATA_OFFSET),
req.length);
req.pos += req.length;
retries = 0;
}
file.close();
return RETURN_OK;
}
ReturnValue_t StrHelper::performFpgaUpload() {
ReturnValue_t result = RETURN_OK;
uint32_t commandSize = 0;
uint32_t bytesUploaded = 0;
uint32_t fileSize = 0;
struct UploadFPGAImageActionRequest req;
if (not std::filesystem::exists(fpgaUpload.uploadFile)) {
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();
req.pos = 0;
while (bytesUploaded <= fileSize) {
if (terminate) {
return RETURN_OK;
}
if (fileSize - bytesUploaded > FpgaUpload::MAX_DATA) {
req.length = FpgaUpload::MAX_DATA;
} else {
req.length = fileSize - bytesUploaded;
}
file.seekg(bytesUploaded, file.beg);
file.read(reinterpret_cast<char*>(req.data), req.length);
arc_pack_uploadfpgaimage_action_req(&req, commandBuffer, &commandSize);
result = sendAndRead(commandSize, req.pos);
if (result != RETURN_OK) {
return RETURN_FAILED;
}
result = checkFpgaActionReply(req.pos, req.length);
if (result != RETURN_OK) {
return result;
}
bytesUploaded += req.length;
}
return RETURN_OK;
}
ReturnValue_t StrHelper::sendAndRead(size_t size, uint32_t parameter) {
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) {
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;
}
ReturnValue_t StrHelper::checkFlashActionReply(uint8_t region_, uint32_t address_,
uint16_t length_) {
ReturnValue_t result = RETURN_OK;
result = checkActionReply();
if (result != RETURN_OK) {
return result;
}
const uint8_t* data = datalinkLayer.getReply();
uint8_t region = *(data + REGION_OFFSET);
uint32_t address;
const uint8_t* addressData = data + ADDRESS_OFFSET;
size_t size = sizeof(address);
result =
SerializeAdapter::deSerialize(&address, &addressData, &size, SerializeIF::Endianness::LITTLE);
if (result != RETURN_OK) {
sif::warning << "StrHelper::checkFlashActionReply: Deserialization of address failed"
<< std::endl;
return result;
}
uint16_t length = 0;
size = sizeof(length);
const uint8_t* lengthData = data + LENGTH_OFFSET;
result =
SerializeAdapter::deSerialize(&length, lengthData, &size, SerializeIF::Endianness::LITTLE);
if (result != RETURN_OK) {
sif::warning << "StrHelper::checkFlashActionReply: Deserialization of length failed"
<< std::endl;
}
if (region != region_) {
return REGION_MISMATCH;
}
if (address != address_) {
return ADDRESS_MISMATCH;
}
if (length != length_) {
return LENGTH_MISMATCH;
}
return RETURN_OK;
}
ReturnValue_t StrHelper::checkFpgaActionReply(uint32_t expectedPosition, uint32_t expectedLength) {
ReturnValue_t result = RETURN_OK;
result = checkActionReply();
if (result != RETURN_OK) {
return result;
}
const uint8_t* data = datalinkLayer.getReply() + ACTION_DATA_OFFSET;
uint32_t position;
size_t size = sizeof(position);
result = SerializeAdapter::deSerialize(&position, &data, &size, SerializeIF::Endianness::LITTLE);
if (result != RETURN_OK) {
sif::warning << "StrHelper::checkFpgaActionReply: Deserialization of position failed"
<< std::endl;
return result;
}
uint32_t length;
size = sizeof(length);
result = SerializeAdapter::deSerialize(&length, &data, &size, SerializeIF::Endianness::LITTLE);
if (result != RETURN_OK) {
sif::warning << "StrHelper::checkFpgaActionReply: Deserialization of length failed"
<< std::endl;
return result;
}
return result;
}
#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
void StrHelper::printProgress(uint32_t itemsTransferred, uint32_t fullNumItems) {
float progressInPercent =
static_cast<float>(itemsTransferred) / static_cast<float>(fullNumItems) * 100;
if (static_cast<uint32_t>(progressInPercent) == nextProgressPrint) {
sif::info << "Str Helper Progress: " << progressInPercent << " %" << std::endl;
nextProgressPrint += FIVE_PERCENT;
}
if (nextProgressPrint > 100) {
nextProgressPrint = 0;
}
}
ReturnValue_t StrHelper::unlockAndEraseRegions(uint32_t from, uint32_t to) {
using namespace startracker::region_secrets;
struct UnlockActionRequest unlockReq;
struct EraseActionRequest eraseReq;
uint32_t size = 0;
for (uint8_t idx = from; idx <= to; idx++) {
unlockReq.region = idx;
unlockReq.code = secret[idx];
arc_pack_unlock_action_req(&req, commandBuffer, &size);
sendAndRead(size, req.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);
if (result != RETURN_OK) {
sif::warning << "StrHelper::unlockAndEraseRegions: Failed to erase region with id "
<< static_cast<unsigned int>(eraseReq.region) << std::endl;
return result;
}
}
return result;
}

View File

@ -0,0 +1,433 @@
#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.
*/
class StrHelper : public SystemObject, public ExecutableObjectIF, public HasReturnvaluesIF {
using namespace startracker;
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 write procedure failed
static const Event FLASH_WRITE_FAILED = MAKE_EVENT(6, severity::LOW);
//! [EXPORT] : [COMMENT] Flash read procedure failed
static const Event FLASH_READ_FAILED = MAKE_EVENT(7, severity::LOW);
//! [EXPORT] : [COMMENT] Download of FPGA image successful
static const Event FPGA_DOWNLOAD_SUCCESSFUL = MAKE_EVENT(8, severity::LOW);
//! [EXPORT] : [COMMENT] Download of FPGA image failed
static const Event FPGA_DOWNLOAD_FAILED = MAKE_EVENT(9, severity::LOW);
//! [EXPORT] : [COMMENT] Upload of FPGA image successful
static const Event FPGA_UPLOAD_SUCCESSFUL = MAKE_EVENT(10, severity::LOW);
//! [EXPORT] : [COMMENT] Upload of FPGA image failed
static const Event FPGA_UPLOAD_FAILED = MAKE_EVENT(11, severity::LOW);
//! [EXPORT] : [COMMENT] Firmware update was successful
static const Event FIRMWARE_UPDATE_SUCCESSFUL = MAKE_EVENT(12, severity::LOW);
//! [EXPORT] : [COMMENT] Firmware update failed
static const Event FIRMWARE_UPDATE_FAILED = MAKE_EVENT(13, 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(14, 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(15, 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(16, 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(17, 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(18, 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(19, 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(20, 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(21, 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 region Region ID of flash region to read from
* @param address Start address of flash section to read
* @param length Number of bytes to read from flash
*/
ReturnValue_t startFlashRead(std::string path, uint8_t region, uint32_t address, uint32_t length);
/**
* @brief Starts the download of the FPGA image
*
* @param path The path where the file with the downloaded data will be created
* @param startPosition Offset in fpga image to read from
* @param length Number of bytes to dwonload from the FPGA image
*
*/
ReturnValue_t startFpgaDownload(std::string path, uint32_t startPosition, uint32_t length);
/**
* @brief Starts upload of new image to FPGA
*
* @param uploadFile Full name of file containing FPGA image data
*/
ReturnValue_t startFpgaUpload(std::string uploadFile);
/**
* @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 Set download FPGA image name
*/
void setDownloadFpgaImage(std::string filename);
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 constexpr uint32_t FIVE_PERCENT = 5;
class ImageDownload {
public:
static const uint32_t LAST_POSITION = 4095;
};
class FpgaDownload {
public:
static const uint16_t MAX_DATA = 1024;
static const uint8_t DATA_OFFSET = 10;
// Start position of fpga image part to download
uint32_t startPosition = 0;
// Length of image part to download
uint32_t length = 0;
// Path where downloaded FPGA image will be stored
std::string path;
// Name of file containing downloaded FPGA image
std::string fileName = "fpgaimage.bin";
};
FpgaDownload fpgaDownload;
class FpgaUpload {
public:
static const uint32_t MAX_DATA = 1024;
// Full name of file to upload
std::string uploadFile;
};
FpgaUpload fpgaUpload;
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 IMAGE_DATA_SIZE = 1024;
static const size_t MAX_FLASH_DATA = 1024;
static const size_t CONFIG_MAX_DOWNLOAD_RETRIES = 3;
enum class InternalState {
IDLE,
UPLOAD_IMAGE,
DOWNLOAD_IMAGE,
FLASH_WRITE,
FLASH_READ,
DOWNLOAD_FPGA_IMAGE,
UPLOAD_FPGA_IMAGE,
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;
// Section where to write to
uint8_t section = 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 region = 0;
// Will be set with the flash read command and specifies the start address of the flash section
// to read
uint32_t address = 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;
uint32_t nextProgressPrint = 0;
/**
* 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 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
*
* @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 Performs the download of the FPGA image which requires to be slip over multiple
* action requests.
*/
ReturnValue_t performFpgaDownload();
/**
* @brief Performs upload of new FPGA image. Upload sequence split over multiple commands
* because one command can only transport 1024 bytes of image data.
*/
ReturnValue_t performFpgaUpload();
/**
* @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
*
* @return RETURN_OK if successful, otherwise RETURN_FAILED
*/
ReturnValue_t sendAndRead(size_t size, uint32_t parameter);
/**
* @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);
/**
* @brief Checks the region, address and length value of a flash write or read reply.
*
* @return RETURN_OK if values match expected values, otherwise appropriate error return
* value.
*/
ReturnValue_t checkFlashActionReply(uint8_t region_, uint32_t address_, uint16_t length_);
/**
* @brief Checks the reply to the fpga download and upload request
*
* @param expectedPosition The expected position value in the reply
* @param expectedLength The expected length field in the reply
*/
ReturnValue_t checkFpgaActionReply(uint32_t expectedPosition, uint32_t expectedLength);
#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 Prints progress of transfer which can be useful for large data transfers
*
* @param itemsTransferred Number of items transferred
* @param fullNumItems Full number of items to transfer
*/
void printProgress(uint32_t itemsTransferred, uint32_t fullNumItems);
/**
* @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 unlockRegions(uint32_t from, uint32_t to);
};
#endif /* BSP_Q7S_DEVICES_STRHELPER_H_ */

View File

@ -73,6 +73,7 @@ static constexpr size_t FSFW_MAX_TM_PACKET_SIZE = 2048;
}
#define FSFW_HAL_SPI_WIRETAPPING 0
#define FSFW_HAL_I2C_WIRETAPPING 0
#define FSFW_DEV_HYPERION_GPS_CREATE_NMEA_CSV 0
#define FSFW_HAL_L3GD20_GYRO_DEBUG 0

View File

@ -9,6 +9,7 @@
#cmakedefine RASPBERRY_PI
#cmakedefine XIPHOS_Q7S
#cmakedefine BEAGLEBONEBLACK
#cmakedefine EGSE
#ifdef RASPBERRY_PI
#include "rpiConfig.h"
@ -41,6 +42,7 @@ debugging. */
#define OBSW_ENABLE_TIMERS 1
#define OBSW_ADD_MGT 1
#define OBSW_ADD_BPX_BATTERY_HANDLER 1
#define OBSW_ADD_STAR_TRACKER 0
#define OBSW_ADD_PLOC_SUPERVISOR 0
#define OBSW_ADD_PLOC_MPSOC 0
@ -55,9 +57,14 @@ debugging. */
#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
#if defined EGSE
#define OBSW_ADD_STAR_TRACKER 1
#endif
/*******************************************************************/
/** All of the following flags should be disabled for mission code */
/*******************************************************************/
@ -66,15 +73,19 @@ debugging. */
#define OBSW_SWITCH_TO_NORMAL_MODE_AFTER_STARTUP 1
#define OBSW_PRINT_MISSED_DEADLINES 1
// If this is enabled, all other SPI code should be disabled
#define OBSW_SYRLINKS_SIMULATED 1
#define OBSW_ADD_TEST_CODE 0
// If this is enabled, all other SPI code should be disabled
#define OBSW_ADD_SPI_TEST_CODE 0
// If this is enabled, all other I2C code should be disabled
#define OBSW_ADD_I2C_TEST_CODE 0
#define OBSW_ADD_TEST_PST 0
#define OBSW_ADD_TEST_TASK 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
#define OBSW_TEST_CCSDS_PTME 0
#define OBSW_TEST_TE7020_HEATER 0
@ -82,6 +93,7 @@ debugging. */
#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
#define OBSW_DEBUG_PDU2 0
#define OBSW_DEBUG_GPS 0
@ -92,11 +104,16 @@ debugging. */
#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
#if defined EGSE
#define OBSW_DEBUG_STARTRACKER 1
#else
#define OBSW_DEBUG_STARTRACKER 0
#endif
#ifdef RASPBERRY_PI
#define OBSW_ENABLE_TIMERS 1

View File

@ -29,6 +29,7 @@ enum gpioId_t {
GNSS_1_NRESET,
GNSS_0_ENABLE,
GNSS_1_ENABLE,
GNSS_SELECT,
GYRO_0_ENABLE,
GYRO_2_ENABLE,

View File

@ -1,7 +1,7 @@
/**
* @brief Auto-generated event translation file. Contains 140 translations.
* @details
* Generated on: 2022-01-17 15:35:58
* Generated on: 2022-02-03 17:30:40
*/
#include "translateEvents.h"
@ -34,6 +34,7 @@ const char *DEVICE_UNREQUESTED_REPLY_STRING = "DEVICE_UNREQUESTED_REPLY";
const char *INVALID_DEVICE_COMMAND_STRING = "INVALID_DEVICE_COMMAND";
const char *MONITORING_LIMIT_EXCEEDED_STRING = "MONITORING_LIMIT_EXCEEDED";
const char *MONITORING_AMBIGUOUS_STRING = "MONITORING_AMBIGUOUS";
const char *DEVICE_WANTS_HARD_REBOOT_STRING = "DEVICE_WANTS_HARD_REBOOT";
const char *FUSE_CURRENT_HIGH_STRING = "FUSE_CURRENT_HIGH";
const char *FUSE_WENT_OFF_STRING = "FUSE_WENT_OFF";
const char *POWER_ABOVE_HIGH_LIMIT_STRING = "POWER_ABOVE_HIGH_LIMIT";
@ -59,7 +60,6 @@ const char *MONITOR_CHANGED_STATE_STRING = "MONITOR_CHANGED_STATE";
const char *VALUE_BELOW_LOW_LIMIT_STRING = "VALUE_BELOW_LOW_LIMIT";
const char *VALUE_ABOVE_HIGH_LIMIT_STRING = "VALUE_ABOVE_HIGH_LIMIT";
const char *VALUE_OUT_OF_RANGE_STRING = "VALUE_OUT_OF_RANGE";
const char *SWITCHING_TM_FAILED_STRING = "SWITCHING_TM_FAILED";
const char *CHANGING_MODE_STRING = "CHANGING_MODE";
const char *MODE_INFO_STRING = "MODE_INFO";
const char *FALLBACK_FAILED_STRING = "FALLBACK_FAILED";
@ -206,6 +206,8 @@ const char *translateEvents(Event event) {
return MONITORING_LIMIT_EXCEEDED_STRING;
case (2810):
return MONITORING_AMBIGUOUS_STRING;
case (2811):
return DEVICE_WANTS_HARD_REBOOT_STRING;
case (4201):
return FUSE_CURRENT_HIGH_STRING;
case (4202):
@ -256,8 +258,6 @@ const char *translateEvents(Event event) {
return VALUE_ABOVE_HIGH_LIMIT_STRING;
case (7204):
return VALUE_OUT_OF_RANGE_STRING;
case (7301):
return SWITCHING_TM_FAILED_STRING;
case (7400):
return CHANGING_MODE_STRING;
case (7401):

View File

@ -62,6 +62,7 @@ enum sourceObjects : uint32_t {
LIBGPIOD_TEST = 0x54123456,
SPI_TEST = 0x54000010,
UART_TEST = 0x54000020,
I2C_TEST = 0x54000030,
DUMMY_INTERFACE = 0x5400CAFE,
DUMMY_HANDLER = 0x5400AFFE,
P60DOCK_TEST_TASK = 0x00005060,

View File

@ -1,8 +1,8 @@
/**
* @brief Auto-generated object translation file.
* @details
* Contains 113 translations.
* Generated on: 2022-01-17 15:36:10
* Contains 110 translations.
* Generated on: 2022-02-03 12:01:36
*/
#include "translateObjects.h"
@ -36,14 +36,14 @@ const char *MGM_3_RM3100_HANDLER_STRING = "MGM_3_RM3100_HANDLER";
const char *GYRO_3_L3G_HANDLER_STRING = "GYRO_3_L3G_HANDLER";
const char *RW4_STRING = "RW4";
const char *STAR_TRACKER_STRING = "STAR_TRACKER";
const char *GPS0_HANDLER_STRING = "GPS0_HANDLER";
const char *GPS1_HANDLER_STRING = "GPS1_HANDLER";
const char *GPS_CONTROLLER_STRING = "GPS_CONTROLLER";
const char *IMTQ_HANDLER_STRING = "IMTQ_HANDLER";
const char *PCDU_HANDLER_STRING = "PCDU_HANDLER";
const char *P60DOCK_HANDLER_STRING = "P60DOCK_HANDLER";
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 *RAD_SENSOR_STRING = "RAD_SENSOR";
const char *PLOC_UPDATER_STRING = "PLOC_UPDATER";
const char *PLOC_MEMORY_DUMPER_STRING = "PLOC_MEMORY_DUMPER";
@ -83,10 +83,6 @@ 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 *PTME_STRING = "PTME";
const char *PAPB_VC0_STRING = "PAPB_VC0";
const char *PAPB_VC1_STRING = "PAPB_VC1";
const char *PAPB_VC2_STRING = "PAPB_VC2";
const char *PAPB_VC3_STRING = "PAPB_VC3";
const char *PDEC_HANDLER_STRING = "PDEC_HANDLER";
const char *CCSDS_HANDLER_STRING = "CCSDS_HANDLER";
const char *PUS_SERVICE_6_STRING = "PUS_SERVICE_6";
@ -101,6 +97,7 @@ const char *PUS_SERVICE_17_TEST_STRING = "PUS_SERVICE_17_TEST";
const char *PUS_SERVICE_20_PARAMETERS_STRING = "PUS_SERVICE_20_PARAMETERS";
const char *PUS_SERVICE_200_MODE_MGMT_STRING = "PUS_SERVICE_200_MODE_MGMT";
const char *PUS_SERVICE_201_HEALTH_STRING = "PUS_SERVICE_201_HEALTH";
const char *CFDP_PACKET_DISTRIBUTOR_STRING = "CFDP_PACKET_DISTRIBUTOR";
const char *HEALTH_TABLE_STRING = "HEALTH_TABLE";
const char *MODE_STORE_STRING = "MODE_STORE";
const char *EVENT_MANAGER_STRING = "EVENT_MANAGER";
@ -183,9 +180,7 @@ const char *translateObject(object_id_t object) {
case 0x44130001:
return STAR_TRACKER_STRING;
case 0x44130045:
return GPS0_HANDLER_STRING;
case 0x44130146:
return GPS1_HANDLER_STRING;
return GPS_CONTROLLER_STRING;
case 0x44140014:
return IMTQ_HANDLER_STRING;
case 0x442000A1:
@ -198,6 +193,8 @@ const char *translateObject(object_id_t object) {
return PDU2_HANDLER_STRING;
case 0x44250003:
return ACU_HANDLER_STRING;
case 0x44260000:
return BPX_BATT_HANDLER_STRING;
case 0x443200A5:
return RAD_SENSOR_STRING;
case 0x44330000:
@ -277,14 +274,6 @@ const char *translateObject(object_id_t object) {
case 0x50000600:
return PTME_STRING;
case 0x50000700:
return PAPB_VC0_STRING;
case 0x50000701:
return PAPB_VC1_STRING;
case 0x50000702:
return PAPB_VC2_STRING;
case 0x50000703:
return PAPB_VC3_STRING;
case 0x50000704:
return PDEC_HANDLER_STRING;
case 0x50000800:
return CCSDS_HANDLER_STRING;
@ -312,6 +301,8 @@ const char *translateObject(object_id_t object) {
return PUS_SERVICE_200_MODE_MGMT_STRING;
case 0x53000201:
return PUS_SERVICE_201_HEALTH_STRING;
case 0x53001000:
return CFDP_PACKET_DISTRIBUTOR_STRING;
case 0x53010000:
return HEALTH_TABLE_STRING;
case 0x53010100:

View File

@ -526,6 +526,14 @@ ReturnValue_t pst::pstI2c(FixedTimeslotTaskIF *thisSequence) {
thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0.6, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0.8, DeviceHandlerIF::GET_READ);
#endif
#if OBSW_ADD_BPX_BATTERY_HANDLER == 1
thisSequence->addSlot(objects::BPX_BATT_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::BPX_BATT_HANDLER, length * 0.2, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::BPX_BATT_HANDLER, length * 0.4, DeviceHandlerIF::GET_WRITE);
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;
@ -548,9 +556,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);
@ -579,7 +589,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;
}