Merge branch 'develop' into acs-flp-safe
All checks were successful
EIVE/eive-obsw/pipeline/pr-develop This commit looks good
All checks were successful
EIVE/eive-obsw/pipeline/pr-develop This commit looks good
This commit is contained in:
18
mission/acs/CMakeLists.txt
Normal file
18
mission/acs/CMakeLists.txt
Normal file
@ -0,0 +1,18 @@
|
||||
target_sources(
|
||||
${LIB_EIVE_MISSION}
|
||||
PRIVATE GyrAdis1650XHandler.cpp
|
||||
GyrL3gCustomHandler.cpp
|
||||
ImtqHandler.cpp
|
||||
MgmLis3CustomHandler.cpp
|
||||
MgmRm3100CustomHandler.cpp
|
||||
RwHandler.cpp
|
||||
SusHandler.cpp
|
||||
gyroAdisHelpers.cpp
|
||||
imtqHelpers.cpp
|
||||
rwHelpers.cpp
|
||||
defs.cpp)
|
||||
|
||||
# Dependency on proprietary library
|
||||
if(TGT_BSP MATCHES "arm/q7s")
|
||||
add_subdirectory(str)
|
||||
endif()
|
216
mission/acs/GyrAdis1650XHandler.cpp
Normal file
216
mission/acs/GyrAdis1650XHandler.cpp
Normal file
@ -0,0 +1,216 @@
|
||||
#include "GyrAdis1650XHandler.h"
|
||||
|
||||
#include "fsfw/action/HasActionsIF.h"
|
||||
#include "fsfw/datapool/PoolReadGuard.h"
|
||||
#include "mission/acs/acsBoardPolling.h"
|
||||
|
||||
GyrAdis1650XHandler::GyrAdis1650XHandler(object_id_t objectId, object_id_t deviceCommunication,
|
||||
CookieIF *comCookie, adis1650x::Type type)
|
||||
: DeviceHandlerBase(objectId, deviceCommunication, comCookie),
|
||||
adisType(type),
|
||||
primaryDataset(this),
|
||||
configDataset(this),
|
||||
breakCountdown() {
|
||||
adisRequest.type = adisType;
|
||||
}
|
||||
|
||||
void GyrAdis1650XHandler::doStartUp() {
|
||||
if (internalState != InternalState::STARTUP) {
|
||||
internalState = InternalState::STARTUP;
|
||||
commandExecuted = false;
|
||||
}
|
||||
// Initial 310 ms start up time after power-up
|
||||
if (internalState == InternalState::STARTUP) {
|
||||
if (not commandExecuted) {
|
||||
warningSwitch = true;
|
||||
breakCountdown.setTimeout(adis1650x::START_UP_TIME);
|
||||
commandExecuted = true;
|
||||
}
|
||||
if (breakCountdown.hasTimedOut()) {
|
||||
updatePeriodicReply(true, adis1650x::REPLY);
|
||||
setMode(MODE_ON);
|
||||
internalState = InternalState::NONE;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void GyrAdis1650XHandler::doShutDown() {
|
||||
if (internalState != InternalState::SHUTDOWN) {
|
||||
commandExecuted = false;
|
||||
primaryDataset.setValidity(false, true);
|
||||
internalState = InternalState::SHUTDOWN;
|
||||
}
|
||||
if (internalState == InternalState::SHUTDOWN and commandExecuted) {
|
||||
updatePeriodicReply(false, adis1650x::REPLY);
|
||||
internalState = InternalState::NONE;
|
||||
commandExecuted = false;
|
||||
setMode(MODE_OFF);
|
||||
}
|
||||
}
|
||||
|
||||
ReturnValue_t GyrAdis1650XHandler::buildNormalDeviceCommand(DeviceCommandId_t *id) {
|
||||
*id = adis1650x::REQUEST;
|
||||
return preparePeriodicRequest(acs::SimpleSensorMode::NORMAL);
|
||||
}
|
||||
|
||||
ReturnValue_t GyrAdis1650XHandler::buildTransitionDeviceCommand(DeviceCommandId_t *id) {
|
||||
switch (internalState) {
|
||||
case (InternalState::STARTUP): {
|
||||
*id = adis1650x::REQUEST;
|
||||
return preparePeriodicRequest(acs::SimpleSensorMode::NORMAL);
|
||||
}
|
||||
case (InternalState::SHUTDOWN): {
|
||||
*id = adis1650x::REQUEST;
|
||||
return preparePeriodicRequest(acs::SimpleSensorMode::OFF);
|
||||
}
|
||||
default: {
|
||||
return NOTHING_TO_SEND;
|
||||
}
|
||||
}
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t GyrAdis1650XHandler::buildCommandFromCommand(DeviceCommandId_t deviceCommand,
|
||||
const uint8_t *commandData,
|
||||
size_t commandDataLen) {
|
||||
return NOTHING_TO_SEND;
|
||||
}
|
||||
|
||||
void GyrAdis1650XHandler::fillCommandAndReplyMap() {
|
||||
insertInCommandMap(adis1650x::REQUEST);
|
||||
insertInReplyMap(adis1650x::REPLY, 5, nullptr, 0, true);
|
||||
}
|
||||
|
||||
ReturnValue_t GyrAdis1650XHandler::scanForReply(const uint8_t *start, size_t remainingSize,
|
||||
DeviceCommandId_t *foundId, size_t *foundLen) {
|
||||
if (breakCountdown.isBusy() or getMode() == _MODE_WAIT_OFF or getMode() == _MODE_WAIT_ON or
|
||||
getMode() == _MODE_POWER_DOWN) {
|
||||
return IGNORE_FULL_PACKET;
|
||||
}
|
||||
*foundLen = remainingSize;
|
||||
if (remainingSize != sizeof(acs::Adis1650XReply)) {
|
||||
return returnvalue::FAILED;
|
||||
}
|
||||
*foundId = adis1650x::REPLY;
|
||||
if (internalState == InternalState::SHUTDOWN) {
|
||||
commandExecuted = true;
|
||||
}
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t GyrAdis1650XHandler::interpretDeviceReply(DeviceCommandId_t id,
|
||||
const uint8_t *packet) {
|
||||
using namespace adis1650x;
|
||||
const acs::Adis1650XReply *reply = reinterpret_cast<const acs::Adis1650XReply *>(packet);
|
||||
if (internalState == InternalState::STARTUP and reply->cfgWasSet) {
|
||||
switch (adisType) {
|
||||
case (adis1650x::Type::ADIS16507): {
|
||||
if (reply->cfg.prodId != adis1650x::PROD_ID_16507) {
|
||||
sif::error << "GyroADIS1650XHandler::interpretDeviceReply: Invalid product ID "
|
||||
<< reply->cfg.prodId << "for ADIS type 16507" << std::endl;
|
||||
return returnvalue::FAILED;
|
||||
}
|
||||
break;
|
||||
}
|
||||
case (adis1650x::Type::ADIS16505): {
|
||||
if (reply->cfg.prodId != adis1650x::PROD_ID_16505) {
|
||||
sif::error << "GyroADIS1650XHandler::interpretDeviceReply: Invalid product ID "
|
||||
<< reply->cfg.prodId << "for ADIS type 16505" << std::endl;
|
||||
return returnvalue::FAILED;
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
PoolReadGuard rg(&configDataset);
|
||||
configDataset.setValidity(true, true);
|
||||
configDataset.mscCtrlReg = reply->cfg.mscCtrlReg;
|
||||
configDataset.rangMdl = reply->cfg.rangMdl;
|
||||
configDataset.diagStatReg = reply->cfg.diagStat;
|
||||
configDataset.filterSetting = reply->cfg.filterSetting;
|
||||
configDataset.decRateReg = reply->cfg.decRateReg;
|
||||
commandExecuted = true;
|
||||
}
|
||||
if (reply->dataWasSet) {
|
||||
{
|
||||
PoolReadGuard rg(&configDataset);
|
||||
configDataset.diagStatReg = reply->cfg.diagStat;
|
||||
}
|
||||
auto sensitivity = reply->data.sensitivity;
|
||||
auto accelSensitivity = reply->data.accelScaling;
|
||||
PoolReadGuard pg(&primaryDataset);
|
||||
primaryDataset.setValidity(true, true);
|
||||
primaryDataset.angVelocX = static_cast<double>(reply->data.angVelocities[0]) * sensitivity;
|
||||
primaryDataset.angVelocY = static_cast<double>(reply->data.angVelocities[1]) * sensitivity;
|
||||
primaryDataset.angVelocZ = static_cast<double>(reply->data.angVelocities[2]) * sensitivity;
|
||||
// TODO: Check whether we need to divide by INT16_MAX
|
||||
primaryDataset.accelX = static_cast<double>(reply->data.accelerations[0]) * accelSensitivity;
|
||||
primaryDataset.accelY = static_cast<double>(reply->data.accelerations[1]) * accelSensitivity;
|
||||
primaryDataset.accelZ = static_cast<double>(reply->data.accelerations[2]) * accelSensitivity;
|
||||
primaryDataset.temperature.value = static_cast<float>(reply->data.temperatureRaw) * 0.1;
|
||||
}
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
LocalPoolDataSetBase *GyrAdis1650XHandler::getDataSetHandle(sid_t sid) {
|
||||
if (sid.ownerSetId == adis1650x::ADIS_DATASET_ID) {
|
||||
return &primaryDataset;
|
||||
} else if (sid.ownerSetId == adis1650x::ADIS_CFG_DATASET_ID) {
|
||||
return &configDataset;
|
||||
}
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
uint32_t GyrAdis1650XHandler::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { return 6000; }
|
||||
|
||||
void GyrAdis1650XHandler::prepareWriteCommand(uint8_t startReg, uint8_t valueOne,
|
||||
uint8_t valueTwo) {
|
||||
uint8_t secondReg = startReg + 1;
|
||||
startReg |= adis1650x::WRITE_MASK;
|
||||
secondReg |= adis1650x::WRITE_MASK;
|
||||
cmdBuf[0] = startReg;
|
||||
cmdBuf[1] = valueOne;
|
||||
cmdBuf[2] = secondReg;
|
||||
cmdBuf[3] = valueTwo;
|
||||
this->rawPacketLen = 4;
|
||||
this->rawPacket = cmdBuf.data();
|
||||
}
|
||||
|
||||
ReturnValue_t GyrAdis1650XHandler::initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
|
||||
LocalDataPoolManager &poolManager) {
|
||||
localDataPoolMap.emplace(adis1650x::ANG_VELOC_X, new PoolEntry<double>({0.0}));
|
||||
localDataPoolMap.emplace(adis1650x::ANG_VELOC_Y, new PoolEntry<double>({0.0}));
|
||||
localDataPoolMap.emplace(adis1650x::ANG_VELOC_Z, new PoolEntry<double>({0.0}));
|
||||
localDataPoolMap.emplace(adis1650x::ACCELERATION_X, new PoolEntry<double>({0.0}));
|
||||
localDataPoolMap.emplace(adis1650x::ACCELERATION_Y, new PoolEntry<double>({0.0}));
|
||||
localDataPoolMap.emplace(adis1650x::ACCELERATION_Z, new PoolEntry<double>({0.0}));
|
||||
localDataPoolMap.emplace(adis1650x::TEMPERATURE, new PoolEntry<float>({0.0}));
|
||||
|
||||
localDataPoolMap.emplace(adis1650x::DIAG_STAT_REGISTER, new PoolEntry<uint16_t>());
|
||||
localDataPoolMap.emplace(adis1650x::FILTER_SETTINGS, new PoolEntry<uint8_t>());
|
||||
localDataPoolMap.emplace(adis1650x::RANG_MDL, &rangMdl);
|
||||
localDataPoolMap.emplace(adis1650x::MSC_CTRL_REGISTER, new PoolEntry<uint16_t>());
|
||||
localDataPoolMap.emplace(adis1650x::DEC_RATE_REGISTER, new PoolEntry<uint16_t>());
|
||||
poolManager.subscribeForRegularPeriodicPacket(
|
||||
subdp::RegularHkPeriodicParams(primaryDataset.getSid(), false, 5.0));
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
adis1650x::BurstModes GyrAdis1650XHandler::getBurstMode() {
|
||||
using namespace adis1650x;
|
||||
configDataset.mscCtrlReg.read();
|
||||
uint16_t currentCtrlReg = configDataset.mscCtrlReg.value;
|
||||
configDataset.mscCtrlReg.commit();
|
||||
return adis1650x::burstModeFromMscCtrl(currentCtrlReg);
|
||||
}
|
||||
|
||||
void GyrAdis1650XHandler::enablePeriodicPrintouts(bool enable, uint8_t divider) {
|
||||
periodicPrintout = enable;
|
||||
debugDivider.setDivider(divider);
|
||||
}
|
||||
|
||||
ReturnValue_t GyrAdis1650XHandler::preparePeriodicRequest(acs::SimpleSensorMode mode) {
|
||||
adisRequest.mode = mode;
|
||||
rawPacket = reinterpret_cast<uint8_t *>(&adisRequest);
|
||||
rawPacketLen = sizeof(acs::Adis1650XRequest);
|
||||
return returnvalue::OK;
|
||||
}
|
70
mission/acs/GyrAdis1650XHandler.h
Normal file
70
mission/acs/GyrAdis1650XHandler.h
Normal file
@ -0,0 +1,70 @@
|
||||
#ifndef MISSION_DEVICES_GYROADIS16507HANDLER_H_
|
||||
#define MISSION_DEVICES_GYROADIS16507HANDLER_H_
|
||||
|
||||
#include <mission/acs/acsBoardPolling.h>
|
||||
#include <mission/acs/gyroAdisHelpers.h>
|
||||
|
||||
#include "FSFWConfig.h"
|
||||
#include "OBSWConfig.h"
|
||||
#include "fsfw/devicehandlers/DeviceHandlerBase.h"
|
||||
#include "fsfw/globalfunctions/PeriodicOperationDivider.h"
|
||||
|
||||
/**
|
||||
* @brief Device handle for the ADIS16507 Gyroscope by Analog Devices
|
||||
* @details
|
||||
* Flight manual:
|
||||
* https://egit.irs.uni-stuttgart.de/redmine/projects/eive-flight-manual/wiki/ADIS16507_Gyro
|
||||
*/
|
||||
class GyrAdis1650XHandler : public DeviceHandlerBase {
|
||||
public:
|
||||
GyrAdis1650XHandler(object_id_t objectId, object_id_t deviceCommunication, CookieIF *comCookie,
|
||||
adis1650x::Type type);
|
||||
|
||||
void enablePeriodicPrintouts(bool enable, uint8_t divider);
|
||||
|
||||
// DeviceHandlerBase abstract function implementation
|
||||
void doStartUp() override;
|
||||
void doShutDown() override;
|
||||
ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t *id) override;
|
||||
ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t *id) override;
|
||||
ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, const uint8_t *commandData,
|
||||
size_t commandDataLen) override;
|
||||
void fillCommandAndReplyMap() override;
|
||||
ReturnValue_t scanForReply(const uint8_t *start, size_t remainingSize, DeviceCommandId_t *foundId,
|
||||
size_t *foundLen) override;
|
||||
ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) override;
|
||||
uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override;
|
||||
ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
|
||||
LocalDataPoolManager &poolManager) override;
|
||||
LocalPoolDataSetBase *getDataSetHandle(sid_t sid) override;
|
||||
|
||||
private:
|
||||
std::array<uint8_t, 32> cmdBuf;
|
||||
acs::Adis1650XRequest adisRequest;
|
||||
adis1650x::Type adisType;
|
||||
AdisGyroPrimaryDataset primaryDataset;
|
||||
AdisGyroConfigDataset configDataset;
|
||||
double sensitivity = adis1650x::SENSITIVITY_UNSET;
|
||||
|
||||
bool warningSwitch = true;
|
||||
|
||||
enum class InternalState { NONE, STARTUP, SHUTDOWN };
|
||||
|
||||
InternalState internalState = InternalState::STARTUP;
|
||||
bool commandExecuted = false;
|
||||
|
||||
PoolEntry<uint16_t> rangMdl = PoolEntry<uint16_t>();
|
||||
|
||||
adis1650x::BurstModes getBurstMode();
|
||||
|
||||
Countdown breakCountdown;
|
||||
void prepareWriteCommand(uint8_t startReg, uint8_t valueOne, uint8_t valueTwo);
|
||||
ReturnValue_t preparePeriodicRequest(acs::SimpleSensorMode mode);
|
||||
|
||||
ReturnValue_t handleSensorData(const uint8_t *packet);
|
||||
|
||||
bool periodicPrintout = false;
|
||||
PeriodicOperationDivider debugDivider = PeriodicOperationDivider(3);
|
||||
};
|
||||
|
||||
#endif /* MISSION_DEVICES_GYROADIS16507HANDLER_H_ */
|
184
mission/acs/GyrL3gCustomHandler.cpp
Normal file
184
mission/acs/GyrL3gCustomHandler.cpp
Normal file
@ -0,0 +1,184 @@
|
||||
|
||||
#include <mission/acs/GyrL3gCustomHandler.h>
|
||||
#include <mission/acs/acsBoardPolling.h>
|
||||
|
||||
#include <cmath>
|
||||
|
||||
#include "fsfw/datapool/PoolReadGuard.h"
|
||||
|
||||
GyrL3gCustomHandler::GyrL3gCustomHandler(object_id_t objectId, object_id_t deviceCommunication,
|
||||
CookieIF *comCookie, uint32_t transitionDelayMs)
|
||||
: DeviceHandlerBase(objectId, deviceCommunication, comCookie),
|
||||
transitionDelayMs(transitionDelayMs),
|
||||
dataset(this) {}
|
||||
|
||||
GyrL3gCustomHandler::~GyrL3gCustomHandler() = default;
|
||||
|
||||
void GyrL3gCustomHandler::doStartUp() {
|
||||
if (internalState != InternalState::STARTUP) {
|
||||
internalState = InternalState::STARTUP;
|
||||
updatePeriodicReply(true, l3gd20h::REPLY);
|
||||
commandExecuted = false;
|
||||
}
|
||||
|
||||
if (internalState == InternalState::STARTUP) {
|
||||
if (commandExecuted) {
|
||||
setMode(MODE_ON);
|
||||
internalState = InternalState::NONE;
|
||||
commandExecuted = false;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void GyrL3gCustomHandler::doShutDown() {
|
||||
if (internalState != InternalState::SHUTDOWN) {
|
||||
internalState = InternalState::SHUTDOWN;
|
||||
dataset.setValidity(false, true);
|
||||
commandExecuted = false;
|
||||
}
|
||||
if (internalState == InternalState::SHUTDOWN and commandExecuted) {
|
||||
internalState = InternalState::NONE;
|
||||
updatePeriodicReply(false, l3gd20h::REPLY);
|
||||
commandExecuted = false;
|
||||
setMode(MODE_OFF);
|
||||
}
|
||||
}
|
||||
|
||||
ReturnValue_t GyrL3gCustomHandler::buildTransitionDeviceCommand(DeviceCommandId_t *id) {
|
||||
switch (internalState) {
|
||||
case (InternalState::NONE):
|
||||
case (InternalState::NORMAL): {
|
||||
return NOTHING_TO_SEND;
|
||||
}
|
||||
case (InternalState::STARTUP): {
|
||||
*id = l3gd20h::REQUEST;
|
||||
gyrRequest.ctrlRegs[0] = l3gd20h::CTRL_REG_1_VAL;
|
||||
gyrRequest.ctrlRegs[1] = l3gd20h::CTRL_REG_2_VAL;
|
||||
gyrRequest.ctrlRegs[2] = l3gd20h::CTRL_REG_3_VAL;
|
||||
gyrRequest.ctrlRegs[3] = l3gd20h::CTRL_REG_4_VAL;
|
||||
gyrRequest.ctrlRegs[4] = l3gd20h::CTRL_REG_5_VAL;
|
||||
return doPeriodicRequest(acs::SimpleSensorMode::NORMAL);
|
||||
}
|
||||
case (InternalState::SHUTDOWN): {
|
||||
*id = l3gd20h::REQUEST;
|
||||
return doPeriodicRequest(acs::SimpleSensorMode::OFF);
|
||||
}
|
||||
default:
|
||||
#if FSFW_CPP_OSTREAM_ENABLED == 1
|
||||
/* Might be a configuration error. */
|
||||
sif::warning << "GyroL3GD20Handler::buildTransitionDeviceCommand: "
|
||||
"Unknown internal state!"
|
||||
<< std::endl;
|
||||
#else
|
||||
sif::printDebug(
|
||||
"GyroL3GD20Handler::buildTransitionDeviceCommand: "
|
||||
"Unknown internal state!\n");
|
||||
#endif
|
||||
return returnvalue::OK;
|
||||
}
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t GyrL3gCustomHandler::buildNormalDeviceCommand(DeviceCommandId_t *id) {
|
||||
*id = l3gd20h::REQUEST;
|
||||
return doPeriodicRequest(acs::SimpleSensorMode::NORMAL);
|
||||
}
|
||||
|
||||
ReturnValue_t GyrL3gCustomHandler::buildCommandFromCommand(DeviceCommandId_t deviceCommand,
|
||||
const uint8_t *commandData,
|
||||
size_t commandDataLen) {
|
||||
switch (deviceCommand) {
|
||||
default:
|
||||
return DeviceHandlerIF::COMMAND_NOT_IMPLEMENTED;
|
||||
}
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t GyrL3gCustomHandler::scanForReply(const uint8_t *start, size_t len,
|
||||
DeviceCommandId_t *foundId, size_t *foundLen) {
|
||||
if (getMode() == _MODE_WAIT_OFF or getMode() == _MODE_WAIT_ON or getMode() == _MODE_POWER_DOWN) {
|
||||
return IGNORE_FULL_PACKET;
|
||||
}
|
||||
*foundLen = len;
|
||||
if (len != sizeof(acs::GyroL3gReply)) {
|
||||
return returnvalue::FAILED;
|
||||
}
|
||||
*foundId = adis1650x::REPLY;
|
||||
if (internalState == InternalState::SHUTDOWN) {
|
||||
commandExecuted = true;
|
||||
}
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t GyrL3gCustomHandler::interpretDeviceReply(DeviceCommandId_t id,
|
||||
const uint8_t *packet) {
|
||||
const acs::GyroL3gReply *reply = reinterpret_cast<const acs::GyroL3gReply *>(packet);
|
||||
if (reply->cfgWasSet) {
|
||||
if (internalState == InternalState::STARTUP) {
|
||||
commandExecuted = true;
|
||||
}
|
||||
PoolReadGuard pg(&dataset);
|
||||
dataset.setValidity(true, true);
|
||||
dataset.angVelocX = static_cast<float>(reply->angVelocities[0]) * reply->sensitivity;
|
||||
dataset.angVelocY = static_cast<float>(reply->angVelocities[1]) * reply->sensitivity;
|
||||
dataset.angVelocZ = static_cast<float>(reply->angVelocities[2]) * reply->sensitivity;
|
||||
if (std::abs(dataset.angVelocX.value) > absLimitX) {
|
||||
dataset.angVelocX.setValid(false);
|
||||
}
|
||||
if (std::abs(dataset.angVelocY.value) > absLimitY) {
|
||||
dataset.angVelocY.setValid(false);
|
||||
}
|
||||
if (std::abs(dataset.angVelocZ.value) > absLimitZ) {
|
||||
dataset.angVelocZ.setValid(false);
|
||||
}
|
||||
dataset.temperature = 25.0 - reply->tempOffsetRaw;
|
||||
}
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
uint32_t GyrL3gCustomHandler::getTransitionDelayMs(Mode_t from, Mode_t to) {
|
||||
return this->transitionDelayMs;
|
||||
}
|
||||
|
||||
ReturnValue_t GyrL3gCustomHandler::initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
|
||||
LocalDataPoolManager &poolManager) {
|
||||
localDataPoolMap.emplace(l3gd20h::ANG_VELOC_X, new PoolEntry<float>({0.0}));
|
||||
localDataPoolMap.emplace(l3gd20h::ANG_VELOC_Y, new PoolEntry<float>({0.0}));
|
||||
localDataPoolMap.emplace(l3gd20h::ANG_VELOC_Z, new PoolEntry<float>({0.0}));
|
||||
localDataPoolMap.emplace(l3gd20h::TEMPERATURE, new PoolEntry<float>({0.0}));
|
||||
poolManager.subscribeForRegularPeriodicPacket(
|
||||
subdp::RegularHkPeriodicParams(dataset.getSid(), false, 10.0));
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
void GyrL3gCustomHandler::fillCommandAndReplyMap() {
|
||||
insertInCommandMap(l3gd20h::REQUEST);
|
||||
insertInReplyMap(l3gd20h::REPLY, 5, nullptr, 0, true);
|
||||
}
|
||||
|
||||
void GyrL3gCustomHandler::modeChanged() { internalState = InternalState::NONE; }
|
||||
|
||||
void GyrL3gCustomHandler::setAbsoluteLimits(float limitX, float limitY, float limitZ) {
|
||||
this->absLimitX = limitX;
|
||||
this->absLimitY = limitY;
|
||||
this->absLimitZ = limitZ;
|
||||
}
|
||||
|
||||
void GyrL3gCustomHandler::enablePeriodicPrintouts(bool enable, uint8_t divider) {
|
||||
periodicPrintout = enable;
|
||||
debugDivider.setDivider(divider);
|
||||
}
|
||||
|
||||
LocalPoolDataSetBase *GyrL3gCustomHandler::getDataSetHandle(sid_t sid) {
|
||||
if (sid == dataset.getSid()) {
|
||||
return &dataset;
|
||||
}
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
ReturnValue_t GyrL3gCustomHandler::doPeriodicRequest(acs::SimpleSensorMode mode) {
|
||||
gyrRequest.mode = mode;
|
||||
rawPacket = reinterpret_cast<uint8_t *>(&gyrRequest);
|
||||
rawPacketLen = sizeof(acs::GyroL3gRequest);
|
||||
return returnvalue::OK;
|
||||
}
|
85
mission/acs/GyrL3gCustomHandler.h
Normal file
85
mission/acs/GyrL3gCustomHandler.h
Normal file
@ -0,0 +1,85 @@
|
||||
#ifndef MISSION_DEVICES_GYROL3GD20HANDLER_H_
|
||||
#define MISSION_DEVICES_GYROL3GD20HANDLER_H_
|
||||
|
||||
#include <fsfw/devicehandlers/DeviceHandlerBase.h>
|
||||
#include <fsfw/globalfunctions/PeriodicOperationDivider.h>
|
||||
#include <fsfw_hal/devicehandlers/devicedefinitions/gyroL3gHelpers.h>
|
||||
#include <mission/acs/acsBoardPolling.h>
|
||||
|
||||
/**
|
||||
* @brief Device Handler for the L3GD20H gyroscope sensor
|
||||
* (https://www.st.com/en/mems-and-sensors/l3gd20h.html)
|
||||
* @details
|
||||
* Advanced documentation:
|
||||
* https://egit.irs.uni-stuttgart.de/redmine/projects/eive-flight-manual/wiki/L3GD20H_Gyro
|
||||
*
|
||||
* Data is read big endian with the smallest possible range of 245 degrees per second.
|
||||
*/
|
||||
class GyrL3gCustomHandler : public DeviceHandlerBase {
|
||||
public:
|
||||
GyrL3gCustomHandler(object_id_t objectId, object_id_t deviceCommunication, CookieIF *comCookie,
|
||||
uint32_t transitionDelayMs);
|
||||
virtual ~GyrL3gCustomHandler();
|
||||
|
||||
void enablePeriodicPrintouts(bool enable, uint8_t divider);
|
||||
|
||||
/**
|
||||
* Set the absolute limit for the values on the axis in degrees per second.
|
||||
* The dataset values will be marked as invalid if that limit is exceeded
|
||||
* @param xLimit
|
||||
* @param yLimit
|
||||
* @param zLimit
|
||||
*/
|
||||
void setAbsoluteLimits(float limitX, float limitY, float limitZ);
|
||||
|
||||
protected:
|
||||
/* DeviceHandlerBase overrides */
|
||||
ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t *id) override;
|
||||
void doStartUp() override;
|
||||
void doShutDown() override;
|
||||
ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t *id) override;
|
||||
ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, const uint8_t *commandData,
|
||||
size_t commandDataLen) override;
|
||||
ReturnValue_t scanForReply(const uint8_t *start, size_t len, DeviceCommandId_t *foundId,
|
||||
size_t *foundLen) override;
|
||||
virtual ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) override;
|
||||
|
||||
void fillCommandAndReplyMap() override;
|
||||
void modeChanged() override;
|
||||
virtual uint32_t getTransitionDelayMs(Mode_t from, Mode_t to) override;
|
||||
ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
|
||||
LocalDataPoolManager &poolManager) override;
|
||||
LocalPoolDataSetBase *getDataSetHandle(sid_t sid) override;
|
||||
|
||||
private:
|
||||
uint32_t transitionDelayMs = 0;
|
||||
GyroPrimaryDataset dataset;
|
||||
|
||||
float absLimitX = l3gd20h::RANGE_DPS_00;
|
||||
float absLimitY = l3gd20h::RANGE_DPS_00;
|
||||
float absLimitZ = l3gd20h::RANGE_DPS_00;
|
||||
|
||||
enum class InternalState { NONE, STARTUP, SHUTDOWN, NORMAL };
|
||||
InternalState internalState = InternalState::NONE;
|
||||
bool commandExecuted = false;
|
||||
|
||||
uint8_t statusReg = 0;
|
||||
|
||||
uint8_t ctrlReg1Value = l3gd20h::CTRL_REG_1_VAL;
|
||||
uint8_t ctrlReg2Value = l3gd20h::CTRL_REG_2_VAL;
|
||||
uint8_t ctrlReg3Value = l3gd20h::CTRL_REG_3_VAL;
|
||||
uint8_t ctrlReg4Value = l3gd20h::CTRL_REG_4_VAL;
|
||||
uint8_t ctrlReg5Value = l3gd20h::CTRL_REG_5_VAL;
|
||||
|
||||
acs::GyroL3gRequest gyrRequest{};
|
||||
|
||||
// Set default value
|
||||
float sensitivity = l3gd20h::SENSITIVITY_00;
|
||||
|
||||
bool periodicPrintout = false;
|
||||
PeriodicOperationDivider debugDivider = PeriodicOperationDivider(3);
|
||||
|
||||
ReturnValue_t doPeriodicRequest(acs::SimpleSensorMode mode);
|
||||
};
|
||||
|
||||
#endif /* MISSION_DEVICES_GYROL3GD20HANDLER_H_ */
|
2425
mission/acs/ImtqHandler.cpp
Normal file
2425
mission/acs/ImtqHandler.cpp
Normal file
File diff suppressed because it is too large
Load Diff
209
mission/acs/ImtqHandler.h
Normal file
209
mission/acs/ImtqHandler.h
Normal file
@ -0,0 +1,209 @@
|
||||
#ifndef MISSION_DEVICES_IMTQHANDLER_H_
|
||||
#define MISSION_DEVICES_IMTQHANDLER_H_
|
||||
|
||||
#include <fsfw/devicehandlers/DeviceHandlerBase.h>
|
||||
#include <mission/acs/imtqHelpers.h>
|
||||
#include <string.h>
|
||||
|
||||
#include "events/subsystemIdRanges.h"
|
||||
#include "returnvalues/classIds.h"
|
||||
|
||||
/**
|
||||
* @brief This is the device handler for the ISIS Magnetorquer iMTQ.
|
||||
*
|
||||
* @author J. Meier
|
||||
*/
|
||||
class ImtqHandler : public DeviceHandlerBase {
|
||||
public:
|
||||
enum NormalPollingMode { UNCALIBRATED = 0, CALIBRATED = 1, BOTH = 2 };
|
||||
|
||||
ImtqHandler(object_id_t objectId, object_id_t comIF, CookieIF* comCookie,
|
||||
power::Switch_t pwrSwitcher, bool enableHkSets);
|
||||
virtual ~ImtqHandler();
|
||||
|
||||
void setPollingMode(NormalPollingMode pollMode);
|
||||
|
||||
/**
|
||||
* @brief Sets mode to MODE_NORMAL. Can be used for debugging.
|
||||
*/
|
||||
void setToGoToNormal(bool enable);
|
||||
|
||||
void setDebugMode(bool enable);
|
||||
|
||||
protected:
|
||||
ReturnValue_t performOperation(uint8_t opCode);
|
||||
void doStartUp() override;
|
||||
void doShutDown() override;
|
||||
ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t* id) override;
|
||||
ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t* id) override;
|
||||
void fillCommandAndReplyMap() override;
|
||||
ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, const uint8_t* commandData,
|
||||
size_t commandDataLen) override;
|
||||
ReturnValue_t scanForReply(const uint8_t* start, size_t remainingSize, DeviceCommandId_t* foundId,
|
||||
size_t* foundLen) override;
|
||||
ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t* packet) override;
|
||||
virtual LocalPoolDataSetBase* getDataSetHandle(sid_t sid) override;
|
||||
uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override;
|
||||
ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap,
|
||||
LocalDataPoolManager& poolManager) override;
|
||||
ReturnValue_t getSwitches(const uint8_t** switches, uint8_t* numberOfSwitches) override;
|
||||
|
||||
private:
|
||||
static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::IMTQ_HANDLER;
|
||||
|
||||
//! [EXPORT] : [COMMENT] Get self test result returns I2C failure
|
||||
//! P1: Indicates on which axis the failure occurred. 0 -> INIT, 1 -> +X, 2 -> -X, 3 -> +Y, 4 ->
|
||||
//! -Y, 5 -> +Z, 6 -> -Z, 7 -> FINA
|
||||
static const Event SELF_TEST_I2C_FAILURE = MAKE_EVENT(1, severity::LOW);
|
||||
//! [EXPORT] : [COMMENT] Get self test result returns SPI failure. This concerns the MTM
|
||||
//! connectivity. P1: Indicates on which axis the failure occurred. 0 -> INIT, 1 -> +X, 2 -> -X, 3
|
||||
//! -> +Y, 4 -> -Y, 5 -> +Z, 6 -> -Z, 7 -> FINA
|
||||
static const Event SELF_TEST_SPI_FAILURE = MAKE_EVENT(2, severity::LOW);
|
||||
//! [EXPORT] : [COMMENT] Get self test result returns failure in measurement of current and
|
||||
//! temperature. P1: Indicates on which axis the failure occurred. 0 -> INIT, 1 -> +X, 2 -> -X, 3
|
||||
//! -> +Y, 4 -> -Y, 5 -> +Z, 6 -> -Z, 7 -> FINA
|
||||
static const Event SELF_TEST_ADC_FAILURE = MAKE_EVENT(3, severity::LOW);
|
||||
//! [EXPORT] : [COMMENT] Get self test result returns PWM failure which concerns the coil
|
||||
//! actuation. P1: Indicates on which axis the failure occurred. 0 -> INIT, 1 -> +X, 2 -> -X, 3 ->
|
||||
//! +Y, 4 -> -Y, 5 -> +Z, 6 -> -Z, 7 -> FINA
|
||||
static const Event SELF_TEST_PWM_FAILURE = MAKE_EVENT(4, severity::LOW);
|
||||
//! [EXPORT] : [COMMENT] Get self test result returns TC failure (system failure)
|
||||
//! P1: Indicates on which axis the failure occurred. 0 -> INIT, 1 -> +X, 2 -> -X, 3 -> +Y, 4 ->
|
||||
//! -Y, 5 -> +Z, 6 -> -Z, 7 -> FINA
|
||||
static const Event SELF_TEST_TC_FAILURE = MAKE_EVENT(5, severity::LOW);
|
||||
//! [EXPORT] : [COMMENT] Get self test result returns failure that MTM values were outside of the
|
||||
//! expected range. P1: Indicates on which axis the failure occurred. 0 -> INIT, 1 -> +X, 2 -> -X,
|
||||
//! 3 -> +Y, 4 -> -Y, 5 -> +Z, 6 -> -Z, 7 -> FINA
|
||||
static const Event SELF_TEST_MTM_RANGE_FAILURE = MAKE_EVENT(6, severity::LOW);
|
||||
//! [EXPORT] : [COMMENT] Get self test result returns failure indicating that the coil current was
|
||||
//! outside of the expected range P1: Indicates on which axis the failure occurred. 0 -> INIT, 1
|
||||
//! -> +X, 2 -> -X, 3 -> +Y, 4 -> -Y, 5 -> +Z, 6 -> -Z, 7 -> FINA
|
||||
static const Event SELF_TEST_COIL_CURRENT_FAILURE = MAKE_EVENT(7, severity::LOW);
|
||||
//! [EXPORT] : [COMMENT] Received invalid error byte. This indicates an error of the communication
|
||||
//! link between IMTQ and OBC.
|
||||
static const Event INVALID_ERROR_BYTE = MAKE_EVENT(8, severity::LOW);
|
||||
|
||||
enum class InternalState { NONE, STARTUP, SHUTDOWN } internalState = InternalState::NONE;
|
||||
bool commandExecuted = false;
|
||||
bool enableHkSets = false;
|
||||
|
||||
imtq::Request request{};
|
||||
|
||||
imtq::StatusDataset statusSet;
|
||||
imtq::DipoleActuationSet dipoleSet;
|
||||
imtq::RawMtmMeasurementNoTorque rawMtmNoTorque;
|
||||
imtq::HkDatasetNoTorque hkDatasetNoTorque;
|
||||
|
||||
imtq::RawMtmMeasurementWithTorque rawMtmWithTorque;
|
||||
imtq::HkDatasetWithTorque hkDatasetWithTorque;
|
||||
|
||||
imtq::CalibratedMtmMeasurementSet calMtmMeasurementSet;
|
||||
imtq::PosXSelfTestSet posXselfTestDataset;
|
||||
imtq::NegXSelfTestSet negXselfTestDataset;
|
||||
imtq::PosYSelfTestSet posYselfTestDataset;
|
||||
imtq::NegYSelfTestSet negYselfTestDataset;
|
||||
imtq::PosZSelfTestSet posZselfTestDataset;
|
||||
imtq::NegZSelfTestSet negZselfTestDataset;
|
||||
bool manualTorqueCmdActive = false;
|
||||
bool ignoreActForRestOfComSteps = false;
|
||||
Countdown manuallyCommandedTorqueDuration = Countdown();
|
||||
|
||||
NormalPollingMode pollingMode = NormalPollingMode::UNCALIBRATED;
|
||||
|
||||
PoolEntry<uint8_t> statusMode = PoolEntry<uint8_t>({0});
|
||||
PoolEntry<uint8_t> statusError = PoolEntry<uint8_t>({0});
|
||||
PoolEntry<uint8_t> statusConfig = PoolEntry<uint8_t>({0});
|
||||
PoolEntry<uint32_t> statusUptime = PoolEntry<uint32_t>({0});
|
||||
|
||||
PoolEntry<int32_t> mgmCalEntry = PoolEntry<int32_t>(3);
|
||||
PoolEntry<int16_t> dipolesPoolEntry = PoolEntry<int16_t>({0, 0, 0}, false);
|
||||
PoolEntry<uint16_t> torqueDurationEntry = PoolEntry<uint16_t>({0}, false);
|
||||
PoolEntry<float> coilCurrentsMilliampsNoTorque = PoolEntry<float>(3);
|
||||
PoolEntry<float> coilCurrentsMilliampsWithTorque = PoolEntry<float>(3);
|
||||
PoolEntry<int16_t> coilTempsNoTorque = PoolEntry<int16_t>(3);
|
||||
PoolEntry<int16_t> coilTempsWithTorque = PoolEntry<int16_t>(3);
|
||||
PoolEntry<float> mtmRawNoTorque = PoolEntry<float>(3);
|
||||
PoolEntry<uint8_t> actStatusNoTorque = PoolEntry<uint8_t>(1);
|
||||
PoolEntry<float> mtmRawWithTorque = PoolEntry<float>(3);
|
||||
PoolEntry<uint8_t> actStatusWithTorque = PoolEntry<uint8_t>(1);
|
||||
|
||||
power::Switch_t switcher = power::NO_SWITCH;
|
||||
|
||||
DeviceCommandId_t expectedReply = DeviceHandlerIF::NO_COMMAND_ID;
|
||||
bool goToNormalMode = false;
|
||||
bool debugMode = false;
|
||||
bool specialRequestActive = false;
|
||||
bool firstReplyCycle = true;
|
||||
|
||||
imtq::RequestType requestStep = imtq::RequestType::MEASURE_NO_ACTUATION;
|
||||
|
||||
/**
|
||||
* @brief In case of a status reply to a single axis self test command, this function
|
||||
* searches for the actual pending command.
|
||||
*/
|
||||
ReturnValue_t getSelfTestCommandId(DeviceCommandId_t* id);
|
||||
|
||||
/**
|
||||
* @brief Each reply contains a status byte giving information about a request. This function
|
||||
* parses this byte and returns the associated failure message.
|
||||
*
|
||||
* @param packet Pointer to the received message containing the status byte.
|
||||
*
|
||||
* @return The return code derived from the received status byte.
|
||||
*/
|
||||
ReturnValue_t parseStatusByte(imtq::CC::CC command, const uint8_t* packet);
|
||||
|
||||
/**
|
||||
* @brief This function fills the engineering housekeeping dataset with the received data.
|
||||
|
||||
* @param packet Pointer to the received data.
|
||||
*
|
||||
*/
|
||||
void fillEngHkDataset(imtq::HkDataset& hkDataset, const uint8_t* packet);
|
||||
|
||||
void fillSystemStateIntoDataset(const uint8_t* packet);
|
||||
|
||||
/**
|
||||
* @brief This function parses the reply containing the calibrated MTM measurement and writes
|
||||
* the values to the appropriate dataset.
|
||||
* @param packet Pointer to the reply data.
|
||||
*/
|
||||
void fillCalibratedMtmDataset(const uint8_t* packet);
|
||||
|
||||
/**
|
||||
* @brief This function copies the raw MTM measurements to the MTM raw dataset.
|
||||
* @param packet Pointer to the reply data requested with the GET_RAW_MTM_MEASUREMENTS
|
||||
* command.
|
||||
*/
|
||||
void fillRawMtmDataset(imtq::RawMtmMeasurementSet& set, const uint8_t* packet);
|
||||
|
||||
/**
|
||||
* @brief This function handles all self test results. This comprises parsing the error byte
|
||||
* and step byte and calling the function to fill the respective dataset.
|
||||
*/
|
||||
void handleSelfTestReply(const uint8_t* packet);
|
||||
|
||||
/**
|
||||
* @brief The following functions fill the respective dataset of the single axis self tests.
|
||||
* @param packet Pointer to the reply data holding the self test result.
|
||||
*/
|
||||
void handlePositiveXSelfTestReply(const uint8_t* packet);
|
||||
void handleNegativeXSelfTestReply(const uint8_t* packet);
|
||||
void handlePositiveYSelfTestReply(const uint8_t* packet);
|
||||
void handleNegativeYSelfTestReply(const uint8_t* packet);
|
||||
void handlePositiveZSelfTestReply(const uint8_t* packet);
|
||||
void handleNegativeZSelfTestReply(const uint8_t* packet);
|
||||
|
||||
// ReturnValue_t buildDipoleActuationCommand();
|
||||
/**
|
||||
* @brief This function checks the error byte of a self test measurement.
|
||||
*
|
||||
* @param errorByte The received error byte to check
|
||||
* @param step The step of the error byte.
|
||||
*/
|
||||
void checkErrorByte(const uint8_t errorByte, const uint8_t step);
|
||||
|
||||
std::string makeStepString(const uint8_t step);
|
||||
};
|
||||
|
||||
#endif /* MISSION_DEVICES_IMTQHANDLER_H_ */
|
150
mission/acs/MgmLis3CustomHandler.cpp
Normal file
150
mission/acs/MgmLis3CustomHandler.cpp
Normal file
@ -0,0 +1,150 @@
|
||||
#include "MgmLis3CustomHandler.h"
|
||||
|
||||
#include <cmath>
|
||||
|
||||
#include "fsfw/datapool/PoolReadGuard.h"
|
||||
|
||||
MgmLis3CustomHandler::MgmLis3CustomHandler(object_id_t objectId, object_id_t deviceCommunication,
|
||||
CookieIF *comCookie, uint32_t transitionDelay)
|
||||
: DeviceHandlerBase(objectId, deviceCommunication, comCookie),
|
||||
dataset(this),
|
||||
transitionDelay(transitionDelay) {}
|
||||
|
||||
MgmLis3CustomHandler::~MgmLis3CustomHandler() = default;
|
||||
|
||||
void MgmLis3CustomHandler::doStartUp() {
|
||||
if (internalState != InternalState::STARTUP) {
|
||||
commandExecuted = false;
|
||||
updatePeriodicReply(true, REPLY);
|
||||
internalState = InternalState::STARTUP;
|
||||
}
|
||||
if (internalState == InternalState::STARTUP) {
|
||||
if (commandExecuted) {
|
||||
setMode(MODE_ON);
|
||||
internalState = InternalState::NONE;
|
||||
commandExecuted = false;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void MgmLis3CustomHandler::doShutDown() {
|
||||
if (internalState != InternalState::SHUTDOWN) {
|
||||
dataset.setValidity(false, true);
|
||||
internalState = InternalState::SHUTDOWN;
|
||||
commandExecuted = false;
|
||||
}
|
||||
if (internalState == InternalState::SHUTDOWN and commandExecuted) {
|
||||
updatePeriodicReply(false, REPLY);
|
||||
commandExecuted = false;
|
||||
internalState = InternalState::NONE;
|
||||
setMode(MODE_OFF);
|
||||
}
|
||||
}
|
||||
|
||||
ReturnValue_t MgmLis3CustomHandler::buildTransitionDeviceCommand(DeviceCommandId_t *id) {
|
||||
if (internalState == InternalState::STARTUP) {
|
||||
*id = REQUEST;
|
||||
return prepareRequest(acs::SimpleSensorMode::NORMAL);
|
||||
} else if (internalState == InternalState::SHUTDOWN) {
|
||||
*id = REQUEST;
|
||||
return prepareRequest(acs::SimpleSensorMode::OFF);
|
||||
}
|
||||
return NOTHING_TO_SEND;
|
||||
}
|
||||
|
||||
ReturnValue_t MgmLis3CustomHandler::buildNormalDeviceCommand(DeviceCommandId_t *id) {
|
||||
*id = REQUEST;
|
||||
return prepareRequest(acs::SimpleSensorMode::NORMAL);
|
||||
}
|
||||
|
||||
ReturnValue_t MgmLis3CustomHandler::buildCommandFromCommand(DeviceCommandId_t deviceCommand,
|
||||
const uint8_t *commandData,
|
||||
size_t commandDataLen) {
|
||||
return NOTHING_TO_SEND;
|
||||
}
|
||||
|
||||
ReturnValue_t MgmLis3CustomHandler::scanForReply(const uint8_t *start, size_t len,
|
||||
DeviceCommandId_t *foundId, size_t *foundLen) {
|
||||
if (getMode() == _MODE_WAIT_OFF or getMode() == _MODE_WAIT_ON) {
|
||||
return IGNORE_FULL_PACKET;
|
||||
}
|
||||
if (len != sizeof(acs::MgmLis3Reply)) {
|
||||
*foundLen = len;
|
||||
return returnvalue::FAILED;
|
||||
}
|
||||
*foundId = REPLY;
|
||||
*foundLen = len;
|
||||
if (internalState == InternalState::SHUTDOWN) {
|
||||
commandExecuted = true;
|
||||
}
|
||||
return returnvalue::OK;
|
||||
}
|
||||
ReturnValue_t MgmLis3CustomHandler::interpretDeviceReply(DeviceCommandId_t id,
|
||||
const uint8_t *packet) {
|
||||
const auto *reply = reinterpret_cast<const acs::MgmLis3Reply *>(packet);
|
||||
if (reply->dataWasSet) {
|
||||
if (internalState == InternalState::STARTUP) {
|
||||
commandExecuted = true;
|
||||
}
|
||||
PoolReadGuard pg(&dataset);
|
||||
for (uint8_t idx = 0; idx < 3; idx++) {
|
||||
dataset.fieldStrengths[idx] =
|
||||
reply->mgmValuesRaw[idx] * reply->sensitivity * mgmLis3::GAUSS_TO_MICROTESLA_FACTOR;
|
||||
}
|
||||
|
||||
dataset.setValidity(true, true);
|
||||
if (std::abs(dataset.fieldStrengths[0]) > absLimitX or
|
||||
std::abs(dataset.fieldStrengths[1]) > absLimitY or
|
||||
std::abs(dataset.fieldStrengths[2]) > absLimitZ) {
|
||||
dataset.fieldStrengths.setValid(false);
|
||||
}
|
||||
dataset.temperature = 25.0 + ((static_cast<float>(reply->temperatureRaw)) / 8.0);
|
||||
}
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
void MgmLis3CustomHandler::fillCommandAndReplyMap() {
|
||||
insertInCommandMap(REQUEST);
|
||||
insertInReplyMap(REPLY, 5, nullptr, 0, true);
|
||||
}
|
||||
|
||||
void MgmLis3CustomHandler::setToGoToNormalMode(bool enable) { this->goToNormalMode = enable; }
|
||||
|
||||
uint32_t MgmLis3CustomHandler::getTransitionDelayMs(Mode_t from, Mode_t to) {
|
||||
return transitionDelay;
|
||||
}
|
||||
|
||||
void MgmLis3CustomHandler::modeChanged(void) { internalState = InternalState::NONE; }
|
||||
|
||||
ReturnValue_t MgmLis3CustomHandler::initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
|
||||
LocalDataPoolManager &poolManager) {
|
||||
localDataPoolMap.emplace(mgmLis3::FIELD_STRENGTHS, &mgmXYZ);
|
||||
localDataPoolMap.emplace(mgmLis3::TEMPERATURE_CELCIUS, &temperature);
|
||||
poolManager.subscribeForRegularPeriodicPacket({dataset.getSid(), false, 10.0});
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
void MgmLis3CustomHandler::setAbsoluteLimits(float xLimit, float yLimit, float zLimit) {
|
||||
this->absLimitX = xLimit;
|
||||
this->absLimitY = yLimit;
|
||||
this->absLimitZ = zLimit;
|
||||
}
|
||||
|
||||
void MgmLis3CustomHandler::enablePeriodicPrintouts(bool enable, uint8_t divider) {
|
||||
periodicPrintout = enable;
|
||||
debugDivider.setDivider(divider);
|
||||
}
|
||||
|
||||
ReturnValue_t MgmLis3CustomHandler::prepareRequest(acs::SimpleSensorMode mode) {
|
||||
request.mode = mode;
|
||||
rawPacket = reinterpret_cast<uint8_t *>(&request);
|
||||
rawPacketLen = sizeof(acs::MgmLis3Request);
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
LocalPoolDataSetBase *MgmLis3CustomHandler::getDataSetHandle(sid_t sid) {
|
||||
if (sid == dataset.getSid()) {
|
||||
return &dataset;
|
||||
}
|
||||
return nullptr;
|
||||
}
|
103
mission/acs/MgmLis3CustomHandler.h
Normal file
103
mission/acs/MgmLis3CustomHandler.h
Normal file
@ -0,0 +1,103 @@
|
||||
#ifndef MISSION_DEVICES_MGMLIS3CUSTOMHANDLER_H_
|
||||
#define MISSION_DEVICES_MGMLIS3CUSTOMHANDLER_H_
|
||||
|
||||
#include <fsfw_hal/devicehandlers/devicedefinitions/mgmLis3Helpers.h>
|
||||
|
||||
#include "fsfw/devicehandlers/DeviceHandlerBase.h"
|
||||
#include "fsfw/globalfunctions/PeriodicOperationDivider.h"
|
||||
#include "mission/acs/acsBoardPolling.h"
|
||||
|
||||
class PeriodicOperationDivider;
|
||||
|
||||
/**
|
||||
* @brief Device handler object for the LIS3MDL 3-axis magnetometer
|
||||
* by STMicroeletronics
|
||||
* @details
|
||||
* Datasheet can be found online by googling LIS3MDL.
|
||||
* Flight manual:
|
||||
* https://egit.irs.uni-stuttgart.de/redmine/projects/eive-flight-manual/wiki/LIS3MDL_MGM
|
||||
* @author L. Loidold, R. Mueller
|
||||
*/
|
||||
class MgmLis3CustomHandler : public DeviceHandlerBase {
|
||||
public:
|
||||
static constexpr DeviceCommandId_t REQUEST = 0x70;
|
||||
static constexpr DeviceCommandId_t REPLY = 0x77;
|
||||
|
||||
static const uint8_t INTERFACE_ID = CLASS_ID::MGM_LIS3MDL;
|
||||
static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::MGM_LIS3MDL;
|
||||
|
||||
MgmLis3CustomHandler(uint32_t objectId, object_id_t deviceCommunication, CookieIF *comCookie,
|
||||
uint32_t transitionDelay);
|
||||
virtual ~MgmLis3CustomHandler();
|
||||
|
||||
void enablePeriodicPrintouts(bool enable, uint8_t divider);
|
||||
/**
|
||||
* Set the absolute limit for the values on the axis in microtesla. The dataset values will
|
||||
* be marked as invalid if that limit is exceeded
|
||||
* @param xLimit
|
||||
* @param yLimit
|
||||
* @param zLimit
|
||||
*/
|
||||
void setAbsoluteLimits(float xLimit, float yLimit, float zLimit);
|
||||
void setToGoToNormalMode(bool enable);
|
||||
|
||||
protected:
|
||||
/** DeviceHandlerBase overrides */
|
||||
void doShutDown() override;
|
||||
void doStartUp() override;
|
||||
virtual uint32_t getTransitionDelayMs(Mode_t from, Mode_t to) override;
|
||||
ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, const uint8_t *commandData,
|
||||
size_t commandDataLen) override;
|
||||
ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t *id) override;
|
||||
ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t *id) override;
|
||||
ReturnValue_t scanForReply(const uint8_t *start, size_t len, DeviceCommandId_t *foundId,
|
||||
size_t *foundLen) override;
|
||||
/**
|
||||
* This implementation is tailored towards space applications and will flag values larger
|
||||
* than 100 microtesla on X,Y and 150 microtesla on Z as invalid
|
||||
* @param id
|
||||
* @param packet
|
||||
* @return
|
||||
*/
|
||||
virtual ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) override;
|
||||
void fillCommandAndReplyMap() override;
|
||||
void modeChanged(void) override;
|
||||
ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
|
||||
LocalDataPoolManager &poolManager) override;
|
||||
LocalPoolDataSetBase *getDataSetHandle(sid_t sid) override;
|
||||
|
||||
private:
|
||||
mgmLis3::MgmPrimaryDataset dataset;
|
||||
acs::MgmLis3Request request{};
|
||||
|
||||
uint32_t transitionDelay;
|
||||
|
||||
float absLimitX = 100;
|
||||
float absLimitY = 100;
|
||||
float absLimitZ = 150;
|
||||
|
||||
uint8_t statusRegister = 0;
|
||||
bool goToNormalMode = false;
|
||||
|
||||
enum class InternalState {
|
||||
NONE,
|
||||
STARTUP,
|
||||
SHUTDOWN,
|
||||
};
|
||||
|
||||
InternalState internalState = InternalState::NONE;
|
||||
bool commandExecuted = false;
|
||||
|
||||
PoolEntry<float> mgmXYZ = PoolEntry<float>(3);
|
||||
PoolEntry<float> temperature = PoolEntry<float>();
|
||||
/*------------------------------------------------------------------------*/
|
||||
/* Device specific commands and variables */
|
||||
/*------------------------------------------------------------------------*/
|
||||
|
||||
bool periodicPrintout = false;
|
||||
PeriodicOperationDivider debugDivider = PeriodicOperationDivider(3);
|
||||
|
||||
ReturnValue_t prepareRequest(acs::SimpleSensorMode mode);
|
||||
};
|
||||
|
||||
#endif /* MISSION_DEVICES_MGMLIS3CUSTOMHANDLER_H_ */
|
139
mission/acs/MgmRm3100CustomHandler.cpp
Normal file
139
mission/acs/MgmRm3100CustomHandler.cpp
Normal file
@ -0,0 +1,139 @@
|
||||
#include "MgmRm3100CustomHandler.h"
|
||||
|
||||
#include "fsfw/datapool/PoolReadGuard.h"
|
||||
#include "fsfw/devicehandlers/DeviceHandlerMessage.h"
|
||||
#include "fsfw/globalfunctions/bitutility.h"
|
||||
#include "fsfw/objectmanager/SystemObjectIF.h"
|
||||
#include "fsfw/returnvalues/returnvalue.h"
|
||||
|
||||
MgmRm3100CustomHandler::MgmRm3100CustomHandler(object_id_t objectId,
|
||||
object_id_t deviceCommunication, CookieIF *comCookie,
|
||||
uint32_t transitionDelay)
|
||||
: DeviceHandlerBase(objectId, deviceCommunication, comCookie),
|
||||
primaryDataset(this),
|
||||
transitionDelay(transitionDelay) {}
|
||||
|
||||
MgmRm3100CustomHandler::~MgmRm3100CustomHandler() = default;
|
||||
|
||||
void MgmRm3100CustomHandler::doStartUp() {
|
||||
if (internalState != InternalState::STARTUP) {
|
||||
commandExecuted = false;
|
||||
updatePeriodicReply(true, REPLY);
|
||||
internalState = InternalState::STARTUP;
|
||||
}
|
||||
if (internalState == InternalState::STARTUP) {
|
||||
if (commandExecuted) {
|
||||
commandExecuted = false;
|
||||
internalState = InternalState::NONE;
|
||||
setMode(MODE_ON);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void MgmRm3100CustomHandler::doShutDown() {
|
||||
if (internalState != InternalState::SHUTDOWN) {
|
||||
commandExecuted = false;
|
||||
primaryDataset.setValidity(false, true);
|
||||
internalState = InternalState::SHUTDOWN;
|
||||
}
|
||||
if (internalState == InternalState::SHUTDOWN and commandExecuted) {
|
||||
updatePeriodicReply(false, REPLY);
|
||||
setMode(MODE_OFF);
|
||||
commandExecuted = false;
|
||||
}
|
||||
}
|
||||
|
||||
ReturnValue_t MgmRm3100CustomHandler::buildTransitionDeviceCommand(DeviceCommandId_t *id) {
|
||||
if (internalState == InternalState::STARTUP) {
|
||||
*id = REQUEST;
|
||||
return prepareRequest(acs::SimpleSensorMode::NORMAL);
|
||||
} else if (internalState == InternalState::SHUTDOWN) {
|
||||
*id = REQUEST;
|
||||
return prepareRequest(acs::SimpleSensorMode::OFF);
|
||||
}
|
||||
return NOTHING_TO_SEND;
|
||||
}
|
||||
|
||||
ReturnValue_t MgmRm3100CustomHandler::buildCommandFromCommand(DeviceCommandId_t deviceCommand,
|
||||
const uint8_t *commandData,
|
||||
size_t commandDataLen) {
|
||||
return NOTHING_TO_SEND;
|
||||
}
|
||||
|
||||
ReturnValue_t MgmRm3100CustomHandler::buildNormalDeviceCommand(DeviceCommandId_t *id) {
|
||||
*id = REQUEST;
|
||||
return prepareRequest(acs::SimpleSensorMode::NORMAL);
|
||||
}
|
||||
|
||||
ReturnValue_t MgmRm3100CustomHandler::scanForReply(const uint8_t *start, size_t len,
|
||||
DeviceCommandId_t *foundId, size_t *foundLen) {
|
||||
if (getMode() == _MODE_WAIT_OFF or getMode() == _MODE_WAIT_ON) {
|
||||
return IGNORE_FULL_PACKET;
|
||||
}
|
||||
if (len != sizeof(acs::MgmRm3100Reply)) {
|
||||
*foundLen = len;
|
||||
return returnvalue::FAILED;
|
||||
}
|
||||
*foundId = REPLY;
|
||||
*foundLen = len;
|
||||
if (internalState == InternalState::SHUTDOWN) {
|
||||
commandExecuted = true;
|
||||
}
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t MgmRm3100CustomHandler::interpretDeviceReply(DeviceCommandId_t id,
|
||||
const uint8_t *packet) {
|
||||
const auto *reply = reinterpret_cast<const acs::MgmRm3100Reply *>(packet);
|
||||
if (reply->dataWasRead) {
|
||||
if (internalState == InternalState::STARTUP) {
|
||||
commandExecuted = true;
|
||||
}
|
||||
|
||||
PoolReadGuard pg(&primaryDataset);
|
||||
primaryDataset.setValidity(true, true);
|
||||
for (uint8_t idx = 0; idx < 3; idx++) {
|
||||
primaryDataset.fieldStrengths[idx] = reply->mgmValuesRaw[idx] * reply->scaleFactors[idx];
|
||||
}
|
||||
}
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
void MgmRm3100CustomHandler::fillCommandAndReplyMap() {
|
||||
insertInCommandMap(REQUEST);
|
||||
insertInReplyMap(REPLY, 5, nullptr, 0, true);
|
||||
}
|
||||
|
||||
void MgmRm3100CustomHandler::modeChanged() { internalState = InternalState::NONE; }
|
||||
|
||||
ReturnValue_t MgmRm3100CustomHandler::initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
|
||||
LocalDataPoolManager &poolManager) {
|
||||
localDataPoolMap.emplace(mgmRm3100::FIELD_STRENGTHS, &mgmXYZ);
|
||||
poolManager.subscribeForRegularPeriodicPacket({primaryDataset.getSid(), false, 10.0});
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
uint32_t MgmRm3100CustomHandler::getTransitionDelayMs(Mode_t from, Mode_t to) {
|
||||
return this->transitionDelay;
|
||||
}
|
||||
|
||||
void MgmRm3100CustomHandler::setToGoToNormalMode(bool enable) { goToNormalModeAtStartup = enable; }
|
||||
|
||||
void MgmRm3100CustomHandler::enablePeriodicPrintouts(bool enable, uint8_t divider) {
|
||||
periodicPrintout = enable;
|
||||
debugDivider.setDivider(divider);
|
||||
}
|
||||
|
||||
ReturnValue_t MgmRm3100CustomHandler::prepareRequest(acs::SimpleSensorMode mode) {
|
||||
request.mode = mode;
|
||||
rawPacket = reinterpret_cast<uint8_t *>(&request);
|
||||
rawPacketLen = sizeof(acs::MgmRm3100Request);
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
LocalPoolDataSetBase *MgmRm3100CustomHandler::getDataSetHandle(sid_t sid) {
|
||||
if (sid == primaryDataset.getSid()) {
|
||||
return &primaryDataset;
|
||||
}
|
||||
return nullptr;
|
||||
}
|
97
mission/acs/MgmRm3100CustomHandler.h
Normal file
97
mission/acs/MgmRm3100CustomHandler.h
Normal file
@ -0,0 +1,97 @@
|
||||
#ifndef MISSION_DEVICES_MGMRM3100CUSTOMHANDLER_H_
|
||||
#define MISSION_DEVICES_MGMRM3100CUSTOMHANDLER_H_
|
||||
|
||||
#include <fsfw_hal/devicehandlers/devicedefinitions/mgmRm3100Helpers.h>
|
||||
|
||||
#include "fsfw/devicehandlers/DeviceHandlerBase.h"
|
||||
#include "fsfw/globalfunctions/PeriodicOperationDivider.h"
|
||||
#include "mission/acs/acsBoardPolling.h"
|
||||
|
||||
/**
|
||||
* @brief Device Handler for the RM3100 geomagnetic magnetometer sensor
|
||||
* (https://www.pnicorp.com/rm3100/)
|
||||
* @details
|
||||
* Flight manual:
|
||||
* https://egit.irs.uni-stuttgart.de/redmine/projects/eive-flight-manual/wiki/RM3100_MGM
|
||||
*/
|
||||
class MgmRm3100CustomHandler : public DeviceHandlerBase {
|
||||
public:
|
||||
static constexpr DeviceCommandId_t REQUEST = 0x70;
|
||||
static constexpr DeviceCommandId_t REPLY = 0x77;
|
||||
|
||||
static const uint8_t INTERFACE_ID = CLASS_ID::MGM_RM3100;
|
||||
|
||||
//! [EXPORT] : [COMMENT] P1: TMRC value which was set, P2: 0
|
||||
static constexpr Event TMRC_SET =
|
||||
event::makeEvent(SUBSYSTEM_ID::MGM_RM3100, 0x00, severity::INFO);
|
||||
|
||||
//! [EXPORT] : [COMMENT] Cycle counter set. P1: First two bytes new Cycle Count X
|
||||
//! P1: Second two bytes new Cycle Count Y
|
||||
//! P2: New cycle count Z
|
||||
static constexpr Event cycleCountersSet =
|
||||
event::makeEvent(SUBSYSTEM_ID::MGM_RM3100, 0x01, severity::INFO);
|
||||
|
||||
MgmRm3100CustomHandler(object_id_t objectId, object_id_t deviceCommunication, CookieIF *comCookie,
|
||||
uint32_t transitionDelay);
|
||||
virtual ~MgmRm3100CustomHandler();
|
||||
|
||||
void enablePeriodicPrintouts(bool enable, uint8_t divider);
|
||||
/**
|
||||
* Configure device handler to go to normal mode after startup immediately
|
||||
* @param enable
|
||||
*/
|
||||
void setToGoToNormalMode(bool enable);
|
||||
|
||||
protected:
|
||||
/* DeviceHandlerBase overrides */
|
||||
ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t *id) override;
|
||||
void doStartUp() override;
|
||||
void doShutDown() override;
|
||||
ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t *id) override;
|
||||
ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, const uint8_t *commandData,
|
||||
size_t commandDataLen) override;
|
||||
ReturnValue_t scanForReply(const uint8_t *start, size_t len, DeviceCommandId_t *foundId,
|
||||
size_t *foundLen) override;
|
||||
ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) override;
|
||||
|
||||
void fillCommandAndReplyMap() override;
|
||||
void modeChanged(void) override;
|
||||
virtual uint32_t getTransitionDelayMs(Mode_t from, Mode_t to) override;
|
||||
ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
|
||||
LocalDataPoolManager &poolManager) override;
|
||||
LocalPoolDataSetBase *getDataSetHandle(sid_t sid) override;
|
||||
|
||||
private:
|
||||
enum class InternalState { NONE, STARTUP, SHUTDOWN };
|
||||
InternalState internalState = InternalState::NONE;
|
||||
bool commandExecuted = false;
|
||||
mgmRm3100::Rm3100PrimaryDataset primaryDataset;
|
||||
acs::MgmRm3100Request request{};
|
||||
|
||||
// uint8_t cmmRegValue = mgmRm3100::CMM_VALUE;
|
||||
// uint8_t tmrcRegValue = mgmRm3100::TMRC_DEFAULT_VALUE;
|
||||
// uint16_t cycleCountRegValueX = mgmRm3100::CYCLE_COUNT_VALUE;
|
||||
// uint16_t cycleCountRegValueY = mgmRm3100::CYCLE_COUNT_VALUE;
|
||||
// uint16_t cycleCountRegValueZ = mgmRm3100::CYCLE_COUNT_VALUE;
|
||||
float scaleFactorX = 1.0 / mgmRm3100::DEFAULT_GAIN;
|
||||
float scaleFactorY = 1.0 / mgmRm3100::DEFAULT_GAIN;
|
||||
float scaleFactorZ = 1.0 / mgmRm3100::DEFAULT_GAIN;
|
||||
|
||||
bool goToNormalModeAtStartup = false;
|
||||
uint32_t transitionDelay;
|
||||
PoolEntry<float> mgmXYZ = PoolEntry<float>(3);
|
||||
bool periodicPrintout = false;
|
||||
|
||||
ReturnValue_t handleCycleCountConfigCommand(DeviceCommandId_t deviceCommand,
|
||||
const uint8_t *commandData, size_t commandDataLen);
|
||||
ReturnValue_t handleCycleCommand(bool oneCycleValue, const uint8_t *commandData,
|
||||
size_t commandDataLen);
|
||||
|
||||
ReturnValue_t handleTmrcConfigCommand(DeviceCommandId_t deviceCommand, const uint8_t *commandData,
|
||||
size_t commandDataLen);
|
||||
|
||||
ReturnValue_t prepareRequest(acs::SimpleSensorMode mode);
|
||||
PeriodicOperationDivider debugDivider = PeriodicOperationDivider(3);
|
||||
};
|
||||
|
||||
#endif /* MISSION_DEVICEHANDLING_MgmRm3100CustomHandler_H_ */
|
558
mission/acs/RwHandler.cpp
Normal file
558
mission/acs/RwHandler.cpp
Normal file
@ -0,0 +1,558 @@
|
||||
#include "RwHandler.h"
|
||||
|
||||
#include <fsfw/datapool/PoolReadGuard.h>
|
||||
#include <fsfw/globalfunctions/CRC.h>
|
||||
#include <fsfw/globalfunctions/arrayprinter.h>
|
||||
#include <fsfw_hal/common/gpio/GpioIF.h>
|
||||
|
||||
#include "OBSWConfig.h"
|
||||
|
||||
RwHandler::RwHandler(object_id_t objectId, object_id_t comIF, CookieIF* comCookie,
|
||||
GpioIF* gpioComIF, gpioId_t enableGpio, uint8_t rwIdx)
|
||||
: DeviceHandlerBase(objectId, comIF, comCookie),
|
||||
gpioComIF(gpioComIF),
|
||||
enableGpio(enableGpio),
|
||||
statusSet(this),
|
||||
lastResetStatusSet(this),
|
||||
tmDataset(this),
|
||||
rwSpeedActuationSet(*this),
|
||||
rwIdx(rwIdx) {
|
||||
if (comCookie == nullptr) {
|
||||
sif::error << "RwHandler: Invalid com cookie" << std::endl;
|
||||
}
|
||||
if (gpioComIF == nullptr) {
|
||||
sif::error << "RwHandler: Invalid gpio communication interface" << std::endl;
|
||||
}
|
||||
}
|
||||
RwHandler::~RwHandler() {}
|
||||
|
||||
void RwHandler::doStartUp() {
|
||||
internalState = InternalState::DEFAULT;
|
||||
|
||||
if (gpioComIF->pullHigh(enableGpio) != returnvalue::OK) {
|
||||
sif::debug << "RwHandler::doStartUp: Failed to pull enable gpio to high";
|
||||
}
|
||||
updatePeriodicReply(true, rws::REPLY_ID);
|
||||
statusSet.setReportingEnabled(true);
|
||||
setMode(_MODE_TO_ON);
|
||||
}
|
||||
|
||||
void RwHandler::doShutDown() {
|
||||
if (gpioComIF->pullLow(enableGpio) != returnvalue::OK) {
|
||||
sif::debug << "RwHandler::doStartUp: Failed to pull enable gpio to low";
|
||||
}
|
||||
internalState = InternalState::DEFAULT;
|
||||
updatePeriodicReply(false, rws::REPLY_ID);
|
||||
{
|
||||
PoolReadGuard pg(&statusSet);
|
||||
statusSet.currSpeed = 0.0;
|
||||
statusSet.referenceSpeed = 0.0;
|
||||
statusSet.state = 0;
|
||||
statusSet.setValidity(false, true);
|
||||
statusSet.setReportingEnabled(false);
|
||||
}
|
||||
{
|
||||
PoolReadGuard pg(&tmDataset);
|
||||
tmDataset.setValidity(false, true);
|
||||
}
|
||||
// The power switch is handled by the assembly, so we can go off here directly.
|
||||
setMode(MODE_OFF);
|
||||
}
|
||||
|
||||
ReturnValue_t RwHandler::buildNormalDeviceCommand(DeviceCommandId_t* id) {
|
||||
switch (internalState) {
|
||||
case InternalState::DEFAULT: {
|
||||
*id = rws::REQUEST_ID;
|
||||
break;
|
||||
}
|
||||
default:
|
||||
sif::debug << "RwHandler::buildNormalDeviceCommand: Invalid internal step" << std::endl;
|
||||
break;
|
||||
}
|
||||
return buildCommandFromCommand(*id, NULL, 0);
|
||||
}
|
||||
|
||||
ReturnValue_t RwHandler::buildTransitionDeviceCommand(DeviceCommandId_t* id) {
|
||||
return NOTHING_TO_SEND;
|
||||
}
|
||||
|
||||
ReturnValue_t RwHandler::buildCommandFromCommand(DeviceCommandId_t deviceCommand,
|
||||
const uint8_t* commandData,
|
||||
size_t commandDataLen) {
|
||||
ReturnValue_t result = returnvalue::OK;
|
||||
|
||||
switch (deviceCommand) {
|
||||
case (rws::SET_SPEED):
|
||||
case (rws::REQUEST_ID): {
|
||||
if (commandData != nullptr && commandDataLen != 6) {
|
||||
sif::error << "RwHandler::buildCommandFromCommand: Received set speed command with"
|
||||
<< " invalid length" << std::endl;
|
||||
return SET_SPEED_COMMAND_INVALID_LENGTH;
|
||||
}
|
||||
|
||||
{
|
||||
PoolReadGuard pg(&rwSpeedActuationSet);
|
||||
// Commands override anything which was set in the software
|
||||
if (commandData != nullptr) {
|
||||
rwSpeedActuationSet.setValidityBufferGeneration(false);
|
||||
result = rwSpeedActuationSet.deSerialize(&commandData, &commandDataLen,
|
||||
SerializeIF::Endianness::NETWORK);
|
||||
rwSpeedActuationSet.setValidityBufferGeneration(true);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
}
|
||||
}
|
||||
if (ACTUATION_WIRETAPPING) {
|
||||
int32_t speed = 0;
|
||||
uint16_t rampTime = 0;
|
||||
rwSpeedActuationSet.getRwSpeed(speed, rampTime);
|
||||
sif::debug << "Actuating RW " << static_cast<int>(rwIdx) << " with speed = " << speed
|
||||
<< " and rampTime = " << rampTime << std::endl;
|
||||
}
|
||||
result = checkSpeedAndRampTime();
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
// set speed flag.
|
||||
commandBuffer[0] = true;
|
||||
rawPacketLen = 1;
|
||||
uint8_t* currentCmdBuf = commandBuffer + 1;
|
||||
rwSpeedActuationSet.serialize(¤tCmdBuf, &rawPacketLen, sizeof(commandBuffer),
|
||||
SerializeIF::Endianness::MACHINE);
|
||||
commandBuffer[rawPacketLen++] = static_cast<uint8_t>(rws::SpecialRwRequest::REQUEST_NONE);
|
||||
rawPacket = commandBuffer;
|
||||
return returnvalue::OK;
|
||||
}
|
||||
case (rws::RESET_MCU): {
|
||||
commandBuffer[0] = false;
|
||||
commandBuffer[7] = static_cast<uint8_t>(rws::SpecialRwRequest::RESET_MCU);
|
||||
internalState = InternalState::RESET_MCU;
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
case (rws::INIT_RW_CONTROLLER): {
|
||||
commandBuffer[0] = false;
|
||||
commandBuffer[7] = static_cast<uint8_t>(rws::SpecialRwRequest::INIT_RW_CONTROLLER);
|
||||
internalState = InternalState::INIT_RW_CONTROLLER;
|
||||
return returnvalue::OK;
|
||||
}
|
||||
case (rws::GET_TM): {
|
||||
commandBuffer[0] = false;
|
||||
commandBuffer[7] = static_cast<uint8_t>(rws::SpecialRwRequest::GET_TM);
|
||||
internalState = InternalState::GET_TM;
|
||||
return returnvalue::OK;
|
||||
}
|
||||
default:
|
||||
return DeviceHandlerIF::COMMAND_NOT_IMPLEMENTED;
|
||||
}
|
||||
return returnvalue::FAILED;
|
||||
}
|
||||
|
||||
void RwHandler::fillCommandAndReplyMap() {
|
||||
insertInCommandMap(rws::REQUEST_ID);
|
||||
insertInReplyMap(rws::REPLY_ID, 5, nullptr, 0, true);
|
||||
|
||||
insertInCommandMap(rws::RESET_MCU);
|
||||
insertInCommandMap(rws::SET_SPEED);
|
||||
insertInCommandAndReplyMap(rws::INIT_RW_CONTROLLER, 5, nullptr, 0, false, true, rws::REPLY_ID);
|
||||
insertInCommandAndReplyMap(rws::GET_TM, 5, nullptr, 0, false, true, rws::REPLY_ID);
|
||||
}
|
||||
|
||||
ReturnValue_t RwHandler::scanForReply(const uint8_t* start, size_t remainingSize,
|
||||
DeviceCommandId_t* foundId, size_t* foundLen) {
|
||||
if (getMode() == _MODE_WAIT_OFF or getMode() == _MODE_WAIT_ON) {
|
||||
return IGNORE_FULL_PACKET;
|
||||
}
|
||||
if (remainingSize > 0) {
|
||||
*foundLen = remainingSize;
|
||||
*foundId = rws::REPLY_ID;
|
||||
}
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t RwHandler::interpretDeviceReply(DeviceCommandId_t id, const uint8_t* packet) {
|
||||
RwReplies replies(packet);
|
||||
ReturnValue_t result = returnvalue::OK;
|
||||
ReturnValue_t status;
|
||||
auto checkPacket = [&](DeviceCommandId_t currentId, const uint8_t* packetPtr) {
|
||||
// This is just the packet length of the frame from the RW. The actual
|
||||
// data is one more flag byte to show whether the value was read at least once.
|
||||
auto packetLen = rws::idToPacketLen(currentId);
|
||||
// arrayprinter::print(packetPtr, packetLen);
|
||||
uint16_t replyCrc = 0;
|
||||
size_t dummy = 0;
|
||||
SerializeAdapter::deSerialize(&replyCrc, packetPtr + packetLen - 2, &dummy,
|
||||
SerializeIF::Endianness::LITTLE);
|
||||
if (CRC::crc16ccitt(packetPtr, packetLen - 2) != replyCrc) {
|
||||
sif::error << "RwHandler::interpretDeviceReply: CRC error for ID " << id << std::endl;
|
||||
return CRC_ERROR;
|
||||
}
|
||||
if (packetPtr[1] == rws::STATE_ERROR) {
|
||||
sif::error << "RwHandler::interpretDeviceReply: Command execution failed. Command id: " << id
|
||||
<< std::endl;
|
||||
result = EXECUTION_FAILED;
|
||||
}
|
||||
return returnvalue::OK;
|
||||
};
|
||||
if (replies.wasSetSpeedReplyRead()) {
|
||||
status = checkPacket(rws::DeviceCommandId::SET_SPEED, replies.getSetSpeedReply());
|
||||
if (status != returnvalue::OK) {
|
||||
result = status;
|
||||
}
|
||||
}
|
||||
|
||||
if (replies.wasRwStatusRead()) {
|
||||
status = checkPacket(rws::DeviceCommandId::GET_RW_STATUS, replies.getRwStatusReply());
|
||||
if (status == returnvalue::OK) {
|
||||
handleGetRwStatusReply(replies.getRwStatusReply());
|
||||
} else {
|
||||
result = status;
|
||||
}
|
||||
}
|
||||
|
||||
if (replies.wasGetLastStatusReplyRead()) {
|
||||
status = checkPacket(rws::DeviceCommandId::GET_LAST_RESET_STATUS,
|
||||
replies.getGetLastResetStatusReply());
|
||||
if (status == returnvalue::OK) {
|
||||
handleResetStatusReply(replies.getGetLastResetStatusReply());
|
||||
} else {
|
||||
result = status;
|
||||
}
|
||||
}
|
||||
|
||||
if (replies.wasClearLastRsetStatusReplyRead()) {
|
||||
status = checkPacket(rws::DeviceCommandId::CLEAR_LAST_RESET_STATUS,
|
||||
replies.getClearLastResetStatusReply());
|
||||
if (status != returnvalue::OK) {
|
||||
result = status;
|
||||
}
|
||||
}
|
||||
|
||||
if (replies.wasReadTemperatureReplySet()) {
|
||||
status = checkPacket(rws::DeviceCommandId::GET_TEMPERATURE, replies.getReadTemperatureReply());
|
||||
if (status == returnvalue::OK) {
|
||||
handleTemperatureReply(replies.getReadTemperatureReply());
|
||||
} else {
|
||||
result = status;
|
||||
}
|
||||
}
|
||||
if (internalState == InternalState::GET_TM) {
|
||||
if (replies.wasHkDataReplyRead()) {
|
||||
status = checkPacket(rws::DeviceCommandId::GET_TM, replies.getHkDataReply());
|
||||
if (status == returnvalue::OK) {
|
||||
handleGetTelemetryReply(replies.getHkDataReply());
|
||||
} else {
|
||||
result = status;
|
||||
}
|
||||
internalState = InternalState::DEFAULT;
|
||||
}
|
||||
}
|
||||
if (internalState == InternalState::INIT_RW_CONTROLLER) {
|
||||
if (replies.wasInitRwControllerReplyRead()) {
|
||||
status =
|
||||
checkPacket(rws::DeviceCommandId::INIT_RW_CONTROLLER, replies.getInitRwControllerReply());
|
||||
if (status != returnvalue::OK) {
|
||||
result = status;
|
||||
}
|
||||
internalState = InternalState::DEFAULT;
|
||||
}
|
||||
}
|
||||
if (internalState == InternalState::RESET_MCU) {
|
||||
internalState = InternalState::DEFAULT;
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
uint32_t RwHandler::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { return 5000; }
|
||||
|
||||
ReturnValue_t RwHandler::initializeLocalDataPool(localpool::DataPool& localDataPoolMap,
|
||||
LocalDataPoolManager& poolManager) {
|
||||
localDataPoolMap.emplace(rws::RW_SPEED, &rwSpeed);
|
||||
localDataPoolMap.emplace(rws::RAMP_TIME, &rampTime);
|
||||
|
||||
localDataPoolMap.emplace(rws::TEMPERATURE_C, new PoolEntry<int32_t>({0}));
|
||||
|
||||
localDataPoolMap.emplace(rws::CURR_SPEED, new PoolEntry<int32_t>({0}));
|
||||
localDataPoolMap.emplace(rws::REFERENCE_SPEED, new PoolEntry<int32_t>({0}));
|
||||
localDataPoolMap.emplace(rws::STATE, new PoolEntry<uint8_t>({0}));
|
||||
localDataPoolMap.emplace(rws::CLC_MODE, new PoolEntry<uint8_t>({0}));
|
||||
|
||||
localDataPoolMap.emplace(rws::LAST_RESET_STATUS, new PoolEntry<uint8_t>({0}));
|
||||
localDataPoolMap.emplace(rws::CURRRENT_RESET_STATUS, new PoolEntry<uint8_t>({0}));
|
||||
|
||||
localDataPoolMap.emplace(rws::TM_LAST_RESET_STATUS, new PoolEntry<uint8_t>({0}));
|
||||
localDataPoolMap.emplace(rws::TM_MCU_TEMPERATURE, new PoolEntry<int32_t>({0}));
|
||||
localDataPoolMap.emplace(rws::PRESSURE_SENSOR_TEMPERATURE, new PoolEntry<float>({0}));
|
||||
localDataPoolMap.emplace(rws::PRESSURE, new PoolEntry<float>({0}));
|
||||
localDataPoolMap.emplace(rws::TM_RW_STATE, new PoolEntry<uint8_t>({0}));
|
||||
localDataPoolMap.emplace(rws::TM_CLC_MODE, new PoolEntry<uint8_t>({0}));
|
||||
localDataPoolMap.emplace(rws::TM_RW_CURR_SPEED, new PoolEntry<int32_t>({0}));
|
||||
localDataPoolMap.emplace(rws::TM_RW_REF_SPEED, new PoolEntry<int32_t>({0}));
|
||||
localDataPoolMap.emplace(rws::INVALID_CRC_PACKETS, new PoolEntry<uint32_t>({0}));
|
||||
localDataPoolMap.emplace(rws::INVALID_LEN_PACKETS, new PoolEntry<uint32_t>({0}));
|
||||
localDataPoolMap.emplace(rws::INVALID_CMD_PACKETS, new PoolEntry<uint32_t>({0}));
|
||||
localDataPoolMap.emplace(rws::EXECUTED_REPLIES, new PoolEntry<uint32_t>({0}));
|
||||
localDataPoolMap.emplace(rws::COMMAND_REPLIES, new PoolEntry<uint32_t>({0}));
|
||||
localDataPoolMap.emplace(rws::UART_BYTES_WRITTEN, new PoolEntry<uint32_t>({0}));
|
||||
localDataPoolMap.emplace(rws::UART_BYTES_READ, new PoolEntry<uint32_t>({0}));
|
||||
localDataPoolMap.emplace(rws::UART_PARITY_ERRORS, new PoolEntry<uint32_t>({0}));
|
||||
localDataPoolMap.emplace(rws::UART_NOISE_ERRORS, new PoolEntry<uint32_t>({0}));
|
||||
localDataPoolMap.emplace(rws::UART_FRAME_ERRORS, new PoolEntry<uint32_t>({0}));
|
||||
localDataPoolMap.emplace(rws::UART_REG_OVERRUN_ERRORS, new PoolEntry<uint32_t>({0}));
|
||||
localDataPoolMap.emplace(rws::UART_TOTAL_ERRORS, new PoolEntry<uint32_t>({0}));
|
||||
localDataPoolMap.emplace(rws::SPI_BYTES_WRITTEN, new PoolEntry<uint32_t>({0}));
|
||||
localDataPoolMap.emplace(rws::SPI_BYTES_READ, new PoolEntry<uint32_t>({0}));
|
||||
localDataPoolMap.emplace(rws::SPI_REG_OVERRUN_ERRORS, new PoolEntry<uint32_t>({0}));
|
||||
localDataPoolMap.emplace(rws::SPI_TOTAL_ERRORS, new PoolEntry<uint32_t>({0}));
|
||||
poolManager.subscribeForDiagPeriodicPacket(
|
||||
subdp::DiagnosticsHkPeriodicParams(statusSet.getSid(), false, 12.0));
|
||||
poolManager.subscribeForRegularPeriodicPacket(
|
||||
subdp::RegularHkPeriodicParams(tmDataset.getSid(), false, 30.0));
|
||||
poolManager.subscribeForRegularPeriodicPacket(
|
||||
subdp::RegularHkPeriodicParams(lastResetStatusSet.getSid(), false, 30.0));
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t RwHandler::checkSpeedAndRampTime() {
|
||||
int32_t speed = 0;
|
||||
uint16_t rampTime = 0;
|
||||
rwSpeedActuationSet.getRwSpeed(speed, rampTime);
|
||||
if ((speed < -65000 || speed > 65000 || (speed > -1000 && speed < 1000)) && (speed != 0)) {
|
||||
sif::error << "RwHandler::checkSpeedAndRampTime: Command has invalid speed" << std::endl;
|
||||
return INVALID_SPEED;
|
||||
}
|
||||
|
||||
if (rampTime < 10 || rampTime > 20000) {
|
||||
sif::error << "RwHandler::checkSpeedAndRampTime: Command has invalid ramp time" << std::endl;
|
||||
return INVALID_RAMP_TIME;
|
||||
}
|
||||
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
void RwHandler::handleResetStatusReply(const uint8_t* packet) {
|
||||
PoolReadGuard rg(&lastResetStatusSet);
|
||||
uint8_t offset = 2;
|
||||
uint8_t resetStatus = packet[offset];
|
||||
if (resetStatus != 0) {
|
||||
// internalState = InternalState::CLEAR_RESET_STATUS;
|
||||
lastResetStatusSet.lastNonClearedResetStatus = resetStatus;
|
||||
triggerEvent(rws::RESET_OCCURED, resetStatus, 0);
|
||||
}
|
||||
lastResetStatusSet.currentResetStatus = resetStatus;
|
||||
if (debugMode) {
|
||||
#if OBSW_VERBOSE_LEVEL >= 1
|
||||
sif::info << "RwHandler::handleResetStatusReply: Last reset status: "
|
||||
<< static_cast<unsigned int>(lastResetStatusSet.lastNonClearedResetStatus.value)
|
||||
<< std::endl;
|
||||
sif::info << "RwHandler::handleResetStatusReply: Current reset status: "
|
||||
<< static_cast<unsigned int>(lastResetStatusSet.currentResetStatus.value)
|
||||
<< std::endl;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
void RwHandler::handleGetRwStatusReply(const uint8_t* packet) {
|
||||
PoolReadGuard rg0(&statusSet);
|
||||
PoolReadGuard rg1(&tmDataset);
|
||||
uint8_t offset = 2;
|
||||
statusSet.currSpeed = *(packet + offset + 3) << 24 | *(packet + offset + 2) << 16 |
|
||||
*(packet + offset + 1) << 8 | *(packet + offset);
|
||||
tmDataset.rwCurrSpeed = statusSet.currSpeed;
|
||||
tmDataset.rwCurrSpeed.setValid(true);
|
||||
offset += 4;
|
||||
statusSet.referenceSpeed = *(packet + offset + 3) << 24 | *(packet + offset + 2) << 16 |
|
||||
*(packet + offset + 1) << 8 | *(packet + offset);
|
||||
tmDataset.rwRefSpeed = statusSet.referenceSpeed;
|
||||
tmDataset.rwRefSpeed.setValid(true);
|
||||
offset += 4;
|
||||
statusSet.state = *(packet + offset);
|
||||
tmDataset.rwState = statusSet.state;
|
||||
tmDataset.rwState.setValid(true);
|
||||
offset += 1;
|
||||
statusSet.clcMode = *(packet + offset);
|
||||
tmDataset.rwClcMode = statusSet.clcMode;
|
||||
tmDataset.rwClcMode.setValid(true);
|
||||
|
||||
statusSet.setValidity(true, true);
|
||||
|
||||
if (statusSet.state == rws::STATE_ERROR) {
|
||||
// Trigger FDIR reaction, first recovery, then faulty if it doesnt fix the issue.
|
||||
triggerEvent(DeviceHandlerIF::DEVICE_WANTS_HARD_REBOOT, statusSet.state.value, 0);
|
||||
sif::error << "RwHandler::handleGetRwStatusReply: Reaction wheel in error state" << std::endl;
|
||||
}
|
||||
|
||||
if (debugMode) {
|
||||
#if OBSW_VERBOSE_LEVEL >= 1
|
||||
sif::info << "RwHandler::handleGetRwStatusReply: Current speed is: " << statusSet.currSpeed
|
||||
<< " * 0.1 RPM" << std::endl;
|
||||
sif::info << "RwHandler::handleGetRwStatusReply: Reference speed is: "
|
||||
<< statusSet.referenceSpeed << " * 0.1 RPM" << std::endl;
|
||||
sif::info << "RwHandler::handleGetRwStatusReply: State is: "
|
||||
<< (unsigned int)statusSet.state.value << std::endl;
|
||||
sif::info << "RwHandler::handleGetRwStatusReply: clc mode is: "
|
||||
<< (unsigned int)statusSet.clcMode.value << std::endl;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
void RwHandler::handleTemperatureReply(const uint8_t* packet) {
|
||||
PoolReadGuard rg(&statusSet);
|
||||
uint8_t offset = 2;
|
||||
statusSet.temperatureCelcius = *(packet + offset + 3) << 24 | *(packet + offset + 2) << 16 |
|
||||
*(packet + offset + 1) << 8 | *(packet + offset);
|
||||
if (debugMode) {
|
||||
#if OBSW_VERBOSE_LEVEL >= 1
|
||||
sif::info << "RwHandler::handleTemperatureReply: Temperature: " << statusSet.temperatureCelcius
|
||||
<< " °C" << std::endl;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
LocalPoolDataSetBase* RwHandler::getDataSetHandle(sid_t sid) {
|
||||
switch (sid.ownerSetId) {
|
||||
case (rws::SetIds::STATUS_SET_ID): {
|
||||
return &statusSet;
|
||||
}
|
||||
case (rws::SetIds::LAST_RESET_ID): {
|
||||
return &lastResetStatusSet;
|
||||
}
|
||||
case (rws::SetIds::SPEED_CMD_SET): {
|
||||
return &rwSpeedActuationSet;
|
||||
}
|
||||
case (rws::SetIds::TM_SET_ID): {
|
||||
return &tmDataset;
|
||||
}
|
||||
}
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
void RwHandler::handleGetTelemetryReply(const uint8_t* packet) {
|
||||
PoolReadGuard rg(&tmDataset);
|
||||
uint8_t offset = 2;
|
||||
tmDataset.lastResetStatus = *(packet + offset);
|
||||
offset += 1;
|
||||
tmDataset.mcuTemperature = *(packet + offset + 3) << 24 | *(packet + offset + 2) << 16 |
|
||||
*(packet + offset + 1) << 8 | *(packet + offset);
|
||||
offset += 4;
|
||||
tmDataset.pressureSensorTemperature = *(packet + offset + 3) << 24 |
|
||||
*(packet + offset + 2) << 16 | *(packet + offset + 1) << 8 |
|
||||
*(packet + offset);
|
||||
offset += 4;
|
||||
tmDataset.pressure = *(packet + offset + 3) << 24 | *(packet + offset + 2) << 16 |
|
||||
*(packet + offset + 1) << 8 | *(packet + offset);
|
||||
offset += 4;
|
||||
tmDataset.rwState = *(packet + offset);
|
||||
offset += 1;
|
||||
tmDataset.rwClcMode = *(packet + offset);
|
||||
offset += 1;
|
||||
tmDataset.rwCurrSpeed = *(packet + offset + 3) << 24 | *(packet + offset + 2) << 16 |
|
||||
*(packet + offset + 1) << 8 | *(packet + offset);
|
||||
offset += 4;
|
||||
tmDataset.rwRefSpeed = *(packet + offset + 3) << 24 | *(packet + offset + 2) << 16 |
|
||||
*(packet + offset + 1) << 8 | *(packet + offset);
|
||||
offset += 4;
|
||||
tmDataset.numOfInvalidCrcPackets = *(packet + offset + 3) << 24 | *(packet + offset + 2) << 16 |
|
||||
*(packet + offset + 1) << 8 | *(packet + offset);
|
||||
offset += 4;
|
||||
tmDataset.numOfInvalidLenPackets = *(packet + offset + 3) << 24 | *(packet + offset + 2) << 16 |
|
||||
*(packet + offset + 1) << 8 | *(packet + offset);
|
||||
offset += 4;
|
||||
tmDataset.numOfInvalidCmdPackets = *(packet + offset + 3) << 24 | *(packet + offset + 2) << 16 |
|
||||
*(packet + offset + 1) << 8 | *(packet + offset);
|
||||
offset += 4;
|
||||
tmDataset.numOfCmdExecutedReplies = *(packet + offset + 3) << 24 | *(packet + offset + 2) << 16 |
|
||||
*(packet + offset + 1) << 8 | *(packet + offset);
|
||||
offset += 4;
|
||||
tmDataset.numOfCmdReplies = *(packet + offset + 3) << 24 | *(packet + offset + 2) << 16 |
|
||||
*(packet + offset + 1) << 8 | *(packet + offset);
|
||||
offset += 4;
|
||||
tmDataset.uartNumOfBytesWritten = *(packet + offset + 3) << 24 | *(packet + offset + 2) << 16 |
|
||||
*(packet + offset + 1) << 8 | *(packet + offset);
|
||||
offset += 4;
|
||||
tmDataset.uartNumOfBytesRead = *(packet + offset + 3) << 24 | *(packet + offset + 2) << 16 |
|
||||
*(packet + offset + 1) << 8 | *(packet + offset);
|
||||
offset += 4;
|
||||
tmDataset.uartNumOfParityErrors = *(packet + offset + 3) << 24 | *(packet + offset + 2) << 16 |
|
||||
*(packet + offset + 1) << 8 | *(packet + offset);
|
||||
offset += 4;
|
||||
tmDataset.uartNumOfNoiseErrors = *(packet + offset + 3) << 24 | *(packet + offset + 2) << 16 |
|
||||
*(packet + offset + 1) << 8 | *(packet + offset);
|
||||
offset += 4;
|
||||
tmDataset.uartNumOfFrameErrors = *(packet + offset + 3) << 24 | *(packet + offset + 2) << 16 |
|
||||
*(packet + offset + 1) << 8 | *(packet + offset);
|
||||
offset += 4;
|
||||
tmDataset.uartNumOfRegisterOverrunErrors = *(packet + offset + 3) << 24 |
|
||||
*(packet + offset + 2) << 16 |
|
||||
*(packet + offset + 1) << 8 | *(packet + offset);
|
||||
offset += 4;
|
||||
tmDataset.uartTotalNumOfErrors = *(packet + offset + 3) << 24 | *(packet + offset + 2) << 16 |
|
||||
*(packet + offset + 1) << 8 | *(packet + offset);
|
||||
offset += 4;
|
||||
tmDataset.spiNumOfBytesWritten = *(packet + offset + 3) << 24 | *(packet + offset + 2) << 16 |
|
||||
*(packet + offset + 1) << 8 | *(packet + offset);
|
||||
offset += 4;
|
||||
tmDataset.spiNumOfBytesRead = *(packet + offset + 3) << 24 | *(packet + offset + 2) << 16 |
|
||||
*(packet + offset + 1) << 8 | *(packet + offset);
|
||||
offset += 4;
|
||||
tmDataset.spiNumOfRegisterOverrunErrors = *(packet + offset + 3) << 24 |
|
||||
*(packet + offset + 2) << 16 |
|
||||
*(packet + offset + 1) << 8 | *(packet + offset);
|
||||
offset += 4;
|
||||
tmDataset.spiTotalNumOfErrors = *(packet + offset + 3) << 24 | *(packet + offset + 2) << 16 |
|
||||
*(packet + offset + 1) << 8 | *(packet + offset);
|
||||
if (debugMode) {
|
||||
#if OBSW_VERBOSE_LEVEL >= 1
|
||||
sif::info << "RwHandler::handleGetTelemetryReply: Last reset status: "
|
||||
<< static_cast<unsigned int>(tmDataset.lastResetStatus.value) << std::endl;
|
||||
sif::info << "RwHandler::handleGetTelemetryReply: MCU temperature: " << tmDataset.mcuTemperature
|
||||
<< std::endl;
|
||||
sif::info << "RwHandler::handleGetTelemetryReply: Pressure sensor temperature: "
|
||||
<< tmDataset.pressureSensorTemperature << std::endl;
|
||||
sif::info << "RwHandler::handleGetTelemetryReply: Pressure " << tmDataset.pressure << std::endl;
|
||||
sif::info << "RwHandler::handleGetTelemetryReply: State: "
|
||||
<< static_cast<unsigned int>(tmDataset.rwState.value) << std::endl;
|
||||
sif::info << "RwHandler::handleGetTelemetryReply: CLC mode: "
|
||||
<< static_cast<unsigned int>(tmDataset.rwClcMode.value) << std::endl;
|
||||
sif::info << "RwHandler::handleGetTelemetryReply: Current speed: " << tmDataset.rwCurrSpeed
|
||||
<< std::endl;
|
||||
sif::info << "RwHandler::handleGetTelemetryReply: Reference speed: " << tmDataset.rwRefSpeed
|
||||
<< std::endl;
|
||||
sif::info << "RwHandler::handleGetTelemetryReply: Number of invalid CRC packets: "
|
||||
<< tmDataset.numOfInvalidCrcPackets << std::endl;
|
||||
sif::info << "RwHandler::handleGetTelemetryReply: Number of invalid length packets: "
|
||||
<< tmDataset.numOfInvalidLenPackets << std::endl;
|
||||
sif::info << "RwHandler::handleGetTelemetryReply: Number of invalid command packets: "
|
||||
<< tmDataset.numOfInvalidCmdPackets << std::endl;
|
||||
sif::info << "RwHandler::handleGetTelemetryReply: Number of command executed replies: "
|
||||
<< tmDataset.numOfCmdExecutedReplies << std::endl;
|
||||
sif::info << "RwHandler::handleGetTelemetryReply: Number of command replies: "
|
||||
<< tmDataset.numOfCmdReplies << std::endl;
|
||||
sif::info << "RwHandler::handleGetTelemetryReply: UART number of bytes written: "
|
||||
<< tmDataset.uartNumOfBytesWritten << std::endl;
|
||||
sif::info << "RwHandler::handleGetTelemetryReply: UART number of bytes read: "
|
||||
<< tmDataset.uartNumOfBytesRead << std::endl;
|
||||
sif::info << "RwHandler::handleGetTelemetryReply: UART number of parity errors: "
|
||||
<< tmDataset.uartNumOfParityErrors << std::endl;
|
||||
sif::info << "RwHandler::handleGetTelemetryReply: UART number of noise errors: "
|
||||
<< tmDataset.uartNumOfNoiseErrors << std::endl;
|
||||
sif::info << "RwHandler::handleGetTelemetryReply: UART number of frame errors: "
|
||||
<< tmDataset.uartNumOfFrameErrors << std::endl;
|
||||
sif::info << "RwHandler::handleGetTelemetryReply: UART number of register overrun errors: "
|
||||
<< tmDataset.uartNumOfRegisterOverrunErrors << std::endl;
|
||||
sif::info << "RwHandler::handleGetTelemetryReply: UART number of total errors: "
|
||||
<< tmDataset.uartTotalNumOfErrors << std::endl;
|
||||
sif::info << "RwHandler::handleGetTelemetryReply: SPI number of bytes written: "
|
||||
<< tmDataset.spiNumOfBytesWritten << std::endl;
|
||||
sif::info << "RwHandler::handleGetTelemetryReply: SPI number of bytes read: "
|
||||
<< tmDataset.spiNumOfBytesRead << std::endl;
|
||||
sif::info << "RwHandler::handleGetTelemetryReply: SPI number of register overrun errors: "
|
||||
<< tmDataset.spiNumOfRegisterOverrunErrors << std::endl;
|
||||
sif::info << "RwHandler::handleGetTelemetryReply: SPI number of register total errors: "
|
||||
<< tmDataset.spiTotalNumOfErrors << std::endl;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
void RwHandler::setDebugMode(bool enable) { this->debugMode = enable; }
|
152
mission/acs/RwHandler.h
Normal file
152
mission/acs/RwHandler.h
Normal file
@ -0,0 +1,152 @@
|
||||
#ifndef MISSION_DEVICES_RWHANDLER_H_
|
||||
#define MISSION_DEVICES_RWHANDLER_H_
|
||||
|
||||
#include <fsfw/devicehandlers/DeviceHandlerBase.h>
|
||||
#include <fsfw_hal/common/gpio/gpioDefinitions.h>
|
||||
#include <mission/acs/rwHelpers.h>
|
||||
#include <string.h>
|
||||
|
||||
#include "events/subsystemIdRanges.h"
|
||||
#include "returnvalues/classIds.h"
|
||||
|
||||
static constexpr bool ACTUATION_WIRETAPPING = false;
|
||||
|
||||
class GpioIF;
|
||||
|
||||
/**
|
||||
* @brief This is the device handler for the reaction wheel from nano avionics.
|
||||
*
|
||||
* @details Datasheet: https://eive-cloud.irs.uni-stuttgart.de/index.php/apps/files/?dir=/EIVE_IRS/
|
||||
* Arbeitsdaten/08_Used%20Components/Nanoavionics_Reactionwheels&fileid=181622
|
||||
*
|
||||
* @note Values are transferred in little endian format.
|
||||
*
|
||||
* @author J. Meier
|
||||
*/
|
||||
class RwHandler : 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.
|
||||
*/
|
||||
RwHandler(object_id_t objectId, object_id_t comIF, CookieIF* comCookie, GpioIF* gpioComIF,
|
||||
gpioId_t enableGpio, uint8_t rwIdx);
|
||||
|
||||
void setDebugMode(bool enable);
|
||||
|
||||
virtual ~RwHandler();
|
||||
|
||||
protected:
|
||||
void doStartUp() override;
|
||||
void doShutDown() override;
|
||||
ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t* id) override;
|
||||
ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t* id) override;
|
||||
void fillCommandAndReplyMap() override;
|
||||
ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, const uint8_t* commandData,
|
||||
size_t commandDataLen) override;
|
||||
ReturnValue_t scanForReply(const uint8_t* start, size_t remainingSize, DeviceCommandId_t* foundId,
|
||||
size_t* foundLen) override;
|
||||
ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t* packet) override;
|
||||
uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override;
|
||||
ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap,
|
||||
LocalDataPoolManager& poolManager) override;
|
||||
LocalPoolDataSetBase* getDataSetHandle(sid_t sid) override;
|
||||
|
||||
private:
|
||||
//! [EXPORT] : [COMMENT] Action Message with invalid speed was received. Valid speeds must be in
|
||||
//! the range of [-65000; 1000] or [1000; 65000]
|
||||
static const ReturnValue_t INVALID_SPEED = MAKE_RETURN_CODE(0xA0);
|
||||
//! [EXPORT] : [COMMENT] Action Message with invalid ramp time was received.
|
||||
static const ReturnValue_t INVALID_RAMP_TIME = MAKE_RETURN_CODE(0xA1);
|
||||
//! [EXPORT] : [COMMENT] Received set speed command has invalid length. Should be 6.
|
||||
static const ReturnValue_t SET_SPEED_COMMAND_INVALID_LENGTH = MAKE_RETURN_CODE(0xA2);
|
||||
//! [EXPORT] : [COMMENT] Command execution failed
|
||||
static const ReturnValue_t EXECUTION_FAILED = MAKE_RETURN_CODE(0xA3);
|
||||
//! [EXPORT] : [COMMENT] Reaction wheel reply has invalid crc
|
||||
static const ReturnValue_t CRC_ERROR = MAKE_RETURN_CODE(0xA4);
|
||||
static const ReturnValue_t VALUE_NOT_READ = MAKE_RETURN_CODE(0xA5);
|
||||
|
||||
GpioIF* gpioComIF = nullptr;
|
||||
gpioId_t enableGpio = gpio::NO_GPIO;
|
||||
bool debugMode = false;
|
||||
|
||||
rws::StatusSet statusSet;
|
||||
rws::LastResetSatus lastResetStatusSet;
|
||||
rws::TmDataset tmDataset;
|
||||
rws::RwSpeedActuationSet rwSpeedActuationSet;
|
||||
|
||||
uint8_t commandBuffer[32];
|
||||
uint8_t rwIdx;
|
||||
|
||||
PoolEntry<int32_t> rwSpeed = PoolEntry<int32_t>({0});
|
||||
PoolEntry<uint16_t> rampTime = PoolEntry<uint16_t>({10});
|
||||
|
||||
enum class InternalState {
|
||||
DEFAULT,
|
||||
GET_TM,
|
||||
INIT_RW_CONTROLLER,
|
||||
RESET_MCU,
|
||||
// GET_RESET_STATUS,
|
||||
// CLEAR_RESET_STATUS,
|
||||
// READ_TEMPERATURE,
|
||||
// SET_SPEED,
|
||||
// GET_RW_SATUS
|
||||
};
|
||||
|
||||
InternalState internalState = InternalState::DEFAULT;
|
||||
|
||||
/**
|
||||
* @brief This function can be used to build commands which do not contain any data apart
|
||||
* from the command id and the CRC.
|
||||
* @param commandId The command id of the command to build.
|
||||
*/
|
||||
// void prepareSimpleCommand(DeviceCommandId_t id);
|
||||
|
||||
/**
|
||||
* @brief This function checks if the receiced speed and ramp time to set are in a valid
|
||||
* range.
|
||||
* @return returnvalue::OK if successful, otherwise error code.
|
||||
*/
|
||||
ReturnValue_t checkSpeedAndRampTime();
|
||||
|
||||
/**
|
||||
* @brief This function prepares the set speed command from the dataSet received with
|
||||
* an action message or set in the software.
|
||||
* @return returnvalue::OK if successful, otherwise error code.
|
||||
*/
|
||||
// ReturnValue_t prepareSetSpeedCmd();
|
||||
|
||||
/**
|
||||
* @brief This function writes the last reset status retrieved with the get last reset status
|
||||
* command into the reset status dataset.
|
||||
*
|
||||
* @param packet Pointer to the buffer holding the reply data.
|
||||
*/
|
||||
void handleResetStatusReply(const uint8_t* packet);
|
||||
|
||||
/**
|
||||
* @brief This function handles the reply of the get temperature command.
|
||||
*
|
||||
* @param packet Pointer to the reply data
|
||||
*/
|
||||
void handleTemperatureReply(const uint8_t* packet);
|
||||
|
||||
/**
|
||||
* @brief This function fills the status set with the data from the get-status-reply.
|
||||
*/
|
||||
void handleGetRwStatusReply(const uint8_t* packet);
|
||||
|
||||
/**
|
||||
* @brief This function fills the tmDataset with the reply data requested with get telemetry
|
||||
* command.
|
||||
*/
|
||||
void handleGetTelemetryReply(const uint8_t* packet);
|
||||
};
|
||||
|
||||
#endif /* MISSION_DEVICES_RWHANDLER_H_ */
|
128
mission/acs/SusHandler.cpp
Normal file
128
mission/acs/SusHandler.cpp
Normal file
@ -0,0 +1,128 @@
|
||||
#include "SusHandler.h"
|
||||
|
||||
#include <mission/tcs/max1227.h>
|
||||
|
||||
#include <cmath>
|
||||
|
||||
#include "fsfw/datapool/PoolReadGuard.h"
|
||||
|
||||
SusHandler::SusHandler(object_id_t objectId, uint8_t susIdx, object_id_t deviceCommunication,
|
||||
CookieIF *comCookie)
|
||||
: DeviceHandlerBase(objectId, deviceCommunication, comCookie), dataset(this), susIdx(susIdx) {}
|
||||
|
||||
SusHandler::~SusHandler() = default;
|
||||
|
||||
void SusHandler::doStartUp() {
|
||||
if (internalState != InternalState::STARTUP) {
|
||||
commandExecuted = false;
|
||||
updatePeriodicReply(true, REPLY);
|
||||
internalState = InternalState::STARTUP;
|
||||
}
|
||||
if (internalState == InternalState::STARTUP) {
|
||||
if (commandExecuted) {
|
||||
setMode(MODE_ON);
|
||||
internalState = InternalState::NONE;
|
||||
commandExecuted = false;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void SusHandler::doShutDown() {
|
||||
if (internalState != InternalState::SHUTDOWN) {
|
||||
dataset.setValidity(false, true);
|
||||
internalState = InternalState::SHUTDOWN;
|
||||
commandExecuted = false;
|
||||
}
|
||||
if (internalState == InternalState::SHUTDOWN and commandExecuted) {
|
||||
updatePeriodicReply(false, REPLY);
|
||||
commandExecuted = false;
|
||||
internalState = InternalState::NONE;
|
||||
setMode(MODE_OFF);
|
||||
}
|
||||
}
|
||||
|
||||
ReturnValue_t SusHandler::buildTransitionDeviceCommand(DeviceCommandId_t *id) {
|
||||
if (internalState == InternalState::STARTUP) {
|
||||
*id = REQUEST;
|
||||
return prepareRequest(acs::SimpleSensorMode::NORMAL);
|
||||
} else if (internalState == InternalState::SHUTDOWN) {
|
||||
*id = REQUEST;
|
||||
return prepareRequest(acs::SimpleSensorMode::OFF);
|
||||
}
|
||||
return NOTHING_TO_SEND;
|
||||
}
|
||||
|
||||
ReturnValue_t SusHandler::buildNormalDeviceCommand(DeviceCommandId_t *id) {
|
||||
*id = REQUEST;
|
||||
return prepareRequest(acs::SimpleSensorMode::NORMAL);
|
||||
}
|
||||
|
||||
ReturnValue_t SusHandler::buildCommandFromCommand(DeviceCommandId_t deviceCommand,
|
||||
const uint8_t *commandData,
|
||||
size_t commandDataLen) {
|
||||
return NOTHING_TO_SEND;
|
||||
}
|
||||
|
||||
ReturnValue_t SusHandler::scanForReply(const uint8_t *start, size_t len, DeviceCommandId_t *foundId,
|
||||
size_t *foundLen) {
|
||||
if (getMode() == _MODE_WAIT_OFF or getMode() == _MODE_WAIT_ON) {
|
||||
return IGNORE_FULL_PACKET;
|
||||
}
|
||||
if (len != sizeof(acs::SusReply)) {
|
||||
*foundLen = len;
|
||||
return returnvalue::FAILED;
|
||||
}
|
||||
*foundId = REPLY;
|
||||
*foundLen = len;
|
||||
if (internalState == InternalState::SHUTDOWN) {
|
||||
commandExecuted = true;
|
||||
}
|
||||
return returnvalue::OK;
|
||||
}
|
||||
ReturnValue_t SusHandler::interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) {
|
||||
const auto *reply = reinterpret_cast<const acs::SusReply *>(packet);
|
||||
if (reply->dataWasSet) {
|
||||
if (internalState == InternalState::STARTUP) {
|
||||
commandExecuted = true;
|
||||
}
|
||||
PoolReadGuard pg(&dataset);
|
||||
dataset.setValidity(true, true);
|
||||
dataset.tempC = max1227::getTemperature(reply->tempRaw);
|
||||
std::memcpy(dataset.channels.value, reply->channelsRaw, sizeof(reply->channelsRaw));
|
||||
}
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
void SusHandler::fillCommandAndReplyMap() {
|
||||
insertInCommandMap(REQUEST);
|
||||
insertInReplyMap(REPLY, 5, nullptr, 0, true);
|
||||
}
|
||||
|
||||
void SusHandler::setToGoToNormalMode(bool enable) { this->goToNormalMode = enable; }
|
||||
|
||||
uint32_t SusHandler::getTransitionDelayMs(Mode_t from, Mode_t to) { return transitionDelay; }
|
||||
|
||||
void SusHandler::modeChanged(void) { internalState = InternalState::NONE; }
|
||||
|
||||
ReturnValue_t SusHandler::initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
|
||||
LocalDataPoolManager &poolManager) {
|
||||
localDataPoolMap.emplace(susMax1227::TEMPERATURE_C, &tempC);
|
||||
localDataPoolMap.emplace(susMax1227::CHANNEL_VEC, &channelVec);
|
||||
poolManager.subscribeForDiagPeriodicPacket(
|
||||
subdp::DiagnosticsHkPeriodicParams(dataset.getSid(), false, 5.0));
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t SusHandler::prepareRequest(acs::SimpleSensorMode mode) {
|
||||
request.mode = mode;
|
||||
rawPacket = reinterpret_cast<uint8_t *>(&request);
|
||||
rawPacketLen = sizeof(acs::SusRequest);
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
LocalPoolDataSetBase *SusHandler::getDataSetHandle(sid_t sid) {
|
||||
if (sid == dataset.getSid()) {
|
||||
return &dataset;
|
||||
}
|
||||
return nullptr;
|
||||
}
|
68
mission/acs/SusHandler.h
Normal file
68
mission/acs/SusHandler.h
Normal file
@ -0,0 +1,68 @@
|
||||
#ifndef MISSION_DEVICES_SusHandler_H_
|
||||
#define MISSION_DEVICES_SusHandler_H_
|
||||
|
||||
#include <eive/eventSubsystemIds.h>
|
||||
#include <eive/resultClassIds.h>
|
||||
#include <mission/acs/susMax1227Helpers.h>
|
||||
|
||||
#include "fsfw/devicehandlers/DeviceHandlerBase.h"
|
||||
#include "fsfw/globalfunctions/PeriodicOperationDivider.h"
|
||||
#include "mission/acs/acsBoardPolling.h"
|
||||
|
||||
class SusHandler : public DeviceHandlerBase {
|
||||
public:
|
||||
static constexpr DeviceCommandId_t REQUEST = 0x70;
|
||||
static constexpr DeviceCommandId_t REPLY = 0x77;
|
||||
|
||||
static const uint8_t INTERFACE_ID = CLASS_ID::SUS_HANDLER;
|
||||
static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::SUS_BOARD_ASS;
|
||||
|
||||
SusHandler(uint32_t objectId, uint8_t susIdx, object_id_t deviceCommunication,
|
||||
CookieIF *comCookie);
|
||||
virtual ~SusHandler();
|
||||
|
||||
void enablePeriodicPrintouts(bool enable, uint8_t divider);
|
||||
void setToGoToNormalMode(bool enable);
|
||||
|
||||
protected:
|
||||
/** DeviceHandlerBase overrides */
|
||||
void doShutDown() override;
|
||||
void doStartUp() override;
|
||||
uint32_t getTransitionDelayMs(Mode_t from, Mode_t to) override;
|
||||
ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, const uint8_t *commandData,
|
||||
size_t commandDataLen) override;
|
||||
ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t *id) override;
|
||||
ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t *id) override;
|
||||
ReturnValue_t scanForReply(const uint8_t *start, size_t len, DeviceCommandId_t *foundId,
|
||||
size_t *foundLen) override;
|
||||
ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) override;
|
||||
void fillCommandAndReplyMap() override;
|
||||
void modeChanged(void) override;
|
||||
ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
|
||||
LocalDataPoolManager &poolManager) override;
|
||||
LocalPoolDataSetBase *getDataSetHandle(sid_t sid) override;
|
||||
|
||||
private:
|
||||
susMax1227::SusDataset dataset;
|
||||
acs::SusRequest request{};
|
||||
uint8_t susIdx;
|
||||
|
||||
uint32_t transitionDelay = 1000;
|
||||
bool goToNormalMode = false;
|
||||
|
||||
PoolEntry<float> tempC = PoolEntry<float>({0.0});
|
||||
PoolEntry<uint16_t> channelVec = PoolEntry<uint16_t>({0, 0, 0, 0, 0, 0});
|
||||
|
||||
enum class InternalState {
|
||||
NONE,
|
||||
STARTUP,
|
||||
SHUTDOWN,
|
||||
};
|
||||
|
||||
InternalState internalState = InternalState::NONE;
|
||||
bool commandExecuted = false;
|
||||
|
||||
ReturnValue_t prepareRequest(acs::SimpleSensorMode mode);
|
||||
};
|
||||
|
||||
#endif /* MISSION_DEVICES_SusHandler_H_ */
|
92
mission/acs/acsBoardPolling.h
Normal file
92
mission/acs/acsBoardPolling.h
Normal file
@ -0,0 +1,92 @@
|
||||
#ifndef MISSION_DEVICES_DEVICEDEFINITIONS_ACSPOLLING_H_
|
||||
#define MISSION_DEVICES_DEVICEDEFINITIONS_ACSPOLLING_H_
|
||||
|
||||
#include <mission/acs/defs.h>
|
||||
|
||||
#include "fsfw/thermal/tcsDefinitions.h"
|
||||
#include "gyroAdisHelpers.h"
|
||||
|
||||
namespace acs {
|
||||
|
||||
struct Adis1650XRequest {
|
||||
SimpleSensorMode mode;
|
||||
adis1650x::Type type;
|
||||
};
|
||||
|
||||
struct Adis1650XConfig {
|
||||
uint16_t diagStat;
|
||||
uint16_t filterSetting;
|
||||
uint16_t rangMdl;
|
||||
uint16_t mscCtrlReg;
|
||||
uint16_t decRateReg;
|
||||
uint16_t prodId;
|
||||
};
|
||||
|
||||
struct Adis1650XData {
|
||||
double sensitivity = 0.0;
|
||||
// Angular velocities in all axes (X, Y and Z)
|
||||
int16_t angVelocities[3]{};
|
||||
double accelScaling = 0.0;
|
||||
// Accelerations in all axes
|
||||
int16_t accelerations[3]{};
|
||||
int16_t temperatureRaw = thermal::INVALID_TEMPERATURE;
|
||||
};
|
||||
|
||||
struct Adis1650XReply {
|
||||
bool cfgWasSet = false;
|
||||
Adis1650XConfig cfg;
|
||||
bool dataWasSet = false;
|
||||
Adis1650XData data;
|
||||
};
|
||||
|
||||
struct GyroL3gRequest {
|
||||
SimpleSensorMode mode = SimpleSensorMode::OFF;
|
||||
uint8_t ctrlRegs[5]{};
|
||||
};
|
||||
|
||||
struct GyroL3gReply {
|
||||
bool cfgWasSet = false;
|
||||
uint8_t statusReg;
|
||||
// Angular velocities in all axes (X, Y and Z)
|
||||
int16_t angVelocities[3]{};
|
||||
int8_t tempOffsetRaw = 0;
|
||||
uint8_t ctrlRegs[5]{};
|
||||
float sensitivity = 0.0;
|
||||
};
|
||||
|
||||
struct MgmRm3100Request {
|
||||
SimpleSensorMode mode = SimpleSensorMode::OFF;
|
||||
};
|
||||
|
||||
struct MgmRm3100Reply {
|
||||
bool dataWasRead = false;
|
||||
float scaleFactors[3]{};
|
||||
int32_t mgmValuesRaw[3]{};
|
||||
};
|
||||
|
||||
struct MgmLis3Request {
|
||||
SimpleSensorMode mode = SimpleSensorMode::OFF;
|
||||
};
|
||||
|
||||
struct MgmLis3Reply {
|
||||
bool dataWasSet = false;
|
||||
float sensitivity = 0.0;
|
||||
int16_t mgmValuesRaw[3]{};
|
||||
bool temperatureWasSet = false;
|
||||
int16_t temperatureRaw = thermal::INVALID_TEMPERATURE;
|
||||
};
|
||||
|
||||
struct SusRequest {
|
||||
SimpleSensorMode mode = SimpleSensorMode::OFF;
|
||||
};
|
||||
|
||||
struct SusReply {
|
||||
bool cfgWasSet = false;
|
||||
bool dataWasSet = false;
|
||||
uint16_t tempRaw = 0;
|
||||
uint16_t channelsRaw[6]{};
|
||||
};
|
||||
|
||||
} // namespace acs
|
||||
|
||||
#endif /* MISSION_DEVICES_DEVICEDEFINITIONS_ACSPOLLING_H_ */
|
75
mission/acs/archive/GPSDefinitions.h
Normal file
75
mission/acs/archive/GPSDefinitions.h
Normal file
@ -0,0 +1,75 @@
|
||||
#ifndef MISSION_ACS_ARCHIVE_GPSDEFINITIONS_H_
|
||||
#define MISSION_ACS_ARCHIVE_GPSDEFINITIONS_H_
|
||||
|
||||
#include "eive/eventSubsystemIds.h"
|
||||
#include "fsfw/datapoollocal/StaticLocalDataSet.h"
|
||||
#include "fsfw/devicehandlers/DeviceHandlerIF.h"
|
||||
|
||||
namespace GpsHyperion {
|
||||
|
||||
enum class FixMode : uint8_t { NOT_SEEN = 0, NO_FIX = 1, FIX_2D = 2, FIX_3D = 3, UNKNOWN = 4 };
|
||||
|
||||
static constexpr uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::GPS_HANDLER;
|
||||
//! [EXPORT] : [COMMENT] Fix has changed. P1: Old fix. P2: New fix
|
||||
//! 0: Not seen, 1: No Fix, 2: 2D-Fix, 3: 3D-Fix
|
||||
static constexpr Event GPS_FIX_CHANGE = event::makeEvent(SUBSYSTEM_ID, 0, severity::INFO);
|
||||
//! [EXPORT] : [COMMENT] Could not get fix in maximum allowed time. P1: Maximum allowed time
|
||||
//! to get a fix after the GPS was switched on.
|
||||
static constexpr Event CANT_GET_FIX = event::makeEvent(SUBSYSTEM_ID, 1, severity::LOW);
|
||||
|
||||
static constexpr DeviceCommandId_t GPS_REPLY = 0;
|
||||
static constexpr DeviceCommandId_t TRIGGER_RESET_PIN_GNSS = 5;
|
||||
|
||||
static constexpr uint32_t DATASET_ID = 0;
|
||||
|
||||
enum GpsPoolIds : lp_id_t {
|
||||
LATITUDE = 0,
|
||||
LONGITUDE = 1,
|
||||
ALTITUDE = 2,
|
||||
SPEED = 3,
|
||||
FIX_MODE = 4,
|
||||
SATS_IN_USE = 5,
|
||||
SATS_IN_VIEW = 6,
|
||||
UNIX_SECONDS = 7,
|
||||
YEAR = 8,
|
||||
MONTH = 9,
|
||||
DAY = 10,
|
||||
HOURS = 11,
|
||||
MINUTES = 12,
|
||||
SECONDS = 13
|
||||
};
|
||||
|
||||
enum GpsFixModes : uint8_t { INVALID = 0, NO_FIX = 1, FIX_2D = 2, FIX_3D = 3 };
|
||||
|
||||
} // namespace GpsHyperion
|
||||
|
||||
class GpsPrimaryDataset : public StaticLocalDataSet<18> {
|
||||
public:
|
||||
GpsPrimaryDataset(object_id_t gpsId) : StaticLocalDataSet(sid_t(gpsId, GpsHyperion::DATASET_ID)) {
|
||||
setAllVariablesReadOnly();
|
||||
}
|
||||
|
||||
lp_var_t<double> latitude = lp_var_t<double>(sid.objectId, GpsHyperion::LATITUDE, this);
|
||||
lp_var_t<double> longitude = lp_var_t<double>(sid.objectId, GpsHyperion::LONGITUDE, this);
|
||||
lp_var_t<double> altitude = lp_var_t<double>(sid.objectId, GpsHyperion::ALTITUDE, this);
|
||||
lp_var_t<double> speed = lp_var_t<double>(sid.objectId, GpsHyperion::SPEED, this);
|
||||
lp_var_t<uint8_t> fixMode = lp_var_t<uint8_t>(sid.objectId, GpsHyperion::FIX_MODE, this);
|
||||
lp_var_t<uint8_t> satInUse = lp_var_t<uint8_t>(sid.objectId, GpsHyperion::SATS_IN_USE, this);
|
||||
lp_var_t<uint8_t> satInView = lp_var_t<uint8_t>(sid.objectId, GpsHyperion::SATS_IN_VIEW, this);
|
||||
lp_var_t<uint16_t> year = lp_var_t<uint16_t>(sid.objectId, GpsHyperion::YEAR, this);
|
||||
lp_var_t<uint8_t> month = lp_var_t<uint8_t>(sid.objectId, GpsHyperion::MONTH, this);
|
||||
lp_var_t<uint8_t> day = lp_var_t<uint8_t>(sid.objectId, GpsHyperion::DAY, this);
|
||||
lp_var_t<uint8_t> hours = lp_var_t<uint8_t>(sid.objectId, GpsHyperion::HOURS, this);
|
||||
lp_var_t<uint8_t> minutes = lp_var_t<uint8_t>(sid.objectId, GpsHyperion::MINUTES, this);
|
||||
lp_var_t<uint8_t> seconds = lp_var_t<uint8_t>(sid.objectId, GpsHyperion::SECONDS, this);
|
||||
lp_var_t<uint32_t> unixSeconds =
|
||||
lp_var_t<uint32_t>(sid.objectId, GpsHyperion::UNIX_SECONDS, this);
|
||||
|
||||
private:
|
||||
friend class GpsHyperionLinuxController;
|
||||
friend class GpsCtrlDummy;
|
||||
GpsPrimaryDataset(HasLocalDataPoolIF* hkOwner)
|
||||
: StaticLocalDataSet(hkOwner, GpsHyperion::DATASET_ID) {}
|
||||
};
|
||||
|
||||
#endif /* MISSION_ACS_ARCHIVE_GPSDEFINITIONS_H_ */
|
204
mission/acs/archive/GPSHyperionHandler.cpp
Normal file
204
mission/acs/archive/GPSHyperionHandler.cpp
Normal file
@ -0,0 +1,204 @@
|
||||
#include "GPSHyperionHandler.h"
|
||||
|
||||
#include <mission/acs/archive/GPSDefinitions.h>
|
||||
|
||||
#include "fsfw/datapool/PoolReadGuard.h"
|
||||
#include "fsfw/timemanager/Clock.h"
|
||||
#include "lwgps/lwgps.h"
|
||||
|
||||
#if FSFW_DEV_HYPERION_GPS_CREATE_NMEA_CSV == 1
|
||||
#include <filesystem>
|
||||
#include <fstream>
|
||||
#endif
|
||||
|
||||
GPSHyperionHandler::GPSHyperionHandler(object_id_t objectId, object_id_t deviceCommunication,
|
||||
CookieIF *comCookie, bool debugHyperionGps)
|
||||
: DeviceHandlerBase(objectId, deviceCommunication, comCookie),
|
||||
gpsSet(this),
|
||||
debugHyperionGps(debugHyperionGps) {
|
||||
lwgps_init(&gpsData);
|
||||
}
|
||||
|
||||
GPSHyperionHandler::~GPSHyperionHandler() {}
|
||||
|
||||
void GPSHyperionHandler::doStartUp() {
|
||||
if (internalState == InternalStates::NONE) {
|
||||
commandExecuted = false;
|
||||
internalState = InternalStates::WAIT_FIRST_MESSAGE;
|
||||
}
|
||||
|
||||
if (internalState == InternalStates::WAIT_FIRST_MESSAGE) {
|
||||
if (commandExecuted) {
|
||||
internalState = InternalStates::IDLE;
|
||||
setMode(MODE_ON);
|
||||
commandExecuted = false;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void GPSHyperionHandler::doShutDown() {
|
||||
internalState = InternalStates::NONE;
|
||||
commandExecuted = false;
|
||||
setMode(_MODE_POWER_DOWN);
|
||||
}
|
||||
|
||||
ReturnValue_t GPSHyperionHandler::buildTransitionDeviceCommand(DeviceCommandId_t *id) {
|
||||
return NOTHING_TO_SEND;
|
||||
}
|
||||
|
||||
ReturnValue_t GPSHyperionHandler::buildNormalDeviceCommand(DeviceCommandId_t *id) {
|
||||
return NOTHING_TO_SEND;
|
||||
}
|
||||
|
||||
ReturnValue_t GPSHyperionHandler::buildCommandFromCommand(DeviceCommandId_t deviceCommand,
|
||||
const uint8_t *commandData,
|
||||
size_t commandDataLen) {
|
||||
// By default, send nothing
|
||||
rawPacketLen = 0;
|
||||
switch (deviceCommand) {
|
||||
case (GpsHyperion::TRIGGER_RESET_PIN): {
|
||||
if (resetCallback != nullptr) {
|
||||
PoolReadGuard pg(&gpsSet);
|
||||
// Set HK entries invalid
|
||||
gpsSet.setValidity(false, true);
|
||||
resetCallback(resetCallbackArgs);
|
||||
return HasActionsIF::EXECUTION_FINISHED;
|
||||
}
|
||||
return DeviceHandlerIF::COMMAND_NOT_IMPLEMENTED;
|
||||
}
|
||||
}
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t GPSHyperionHandler::scanForReply(const uint8_t *start, size_t len,
|
||||
DeviceCommandId_t *foundId, size_t *foundLen) {
|
||||
// Pass data to GPS library
|
||||
if (len > 0) {
|
||||
// sif::debug << "GPSHandler::scanForReply: Received " << len << " bytes" << std::endl;
|
||||
if (internalState == InternalStates::WAIT_FIRST_MESSAGE) {
|
||||
// TODO: Check whether data is valid by checking whether NMEA start string is valid?
|
||||
commandExecuted = true;
|
||||
}
|
||||
int result = lwgps_process(&gpsData, start, len);
|
||||
if (result != 1) {
|
||||
sif::warning << "GPSHandler::scanForReply: Issue processing GPS data with lwgps" << std::endl;
|
||||
} else {
|
||||
// The data from the device will generally be read all at once. Therefore, we
|
||||
// can set all field here
|
||||
PoolReadGuard pg(&gpsSet);
|
||||
if (pg.getReadResult() != returnvalue::OK) {
|
||||
#if FSFW_VERBOSE_LEVEL >= 1
|
||||
sif::warning << "GPSHyperionHandler::scanForReply: Reading dataset failed" << std::endl;
|
||||
#endif
|
||||
}
|
||||
// Print messages
|
||||
if (gpsData.is_valid) {
|
||||
// Set all entries valid now, set invalid on case basis if values are sanitized
|
||||
gpsSet.setValidity(true, true);
|
||||
}
|
||||
// Negative latitude -> South direction
|
||||
gpsSet.latitude.value = gpsData.latitude;
|
||||
// Negative longitude -> West direction
|
||||
gpsSet.longitude.value = gpsData.longitude;
|
||||
if (gpsData.altitude > 600000.0 or gpsData.altitude < 400000.0) {
|
||||
gpsSet.altitude.setValid(false);
|
||||
} else {
|
||||
gpsSet.altitude.setValid(true);
|
||||
gpsSet.altitude.value = gpsData.altitude;
|
||||
}
|
||||
gpsSet.fixMode.value = gpsData.fix_mode;
|
||||
gpsSet.satInUse.value = gpsData.sats_in_use;
|
||||
Clock::TimeOfDay_t timeStruct = {};
|
||||
timeStruct.day = gpsData.date;
|
||||
timeStruct.hour = gpsData.hours;
|
||||
timeStruct.minute = gpsData.minutes;
|
||||
timeStruct.month = gpsData.month;
|
||||
timeStruct.second = gpsData.seconds;
|
||||
// Convert two-digit year to full year (AD)
|
||||
timeStruct.year = gpsData.year + 2000;
|
||||
timeval timeval = {};
|
||||
Clock::convertTimeOfDayToTimeval(&timeStruct, &timeval);
|
||||
gpsSet.year = timeStruct.year;
|
||||
gpsSet.month = gpsData.month;
|
||||
gpsSet.day = gpsData.date;
|
||||
gpsSet.hours = gpsData.hours;
|
||||
gpsSet.minutes = gpsData.minutes;
|
||||
gpsSet.seconds = gpsData.seconds;
|
||||
gpsSet.unixSeconds = timeval.tv_sec;
|
||||
if (debugHyperionGps) {
|
||||
sif::info << "GPS Data" << std::endl;
|
||||
printf("Valid status: %d\n", gpsData.is_valid);
|
||||
printf("Latitude: %f degrees\n", gpsData.latitude);
|
||||
printf("Longitude: %f degrees\n", gpsData.longitude);
|
||||
printf("Altitude: %f meters\n", gpsData.altitude);
|
||||
}
|
||||
#if FSFW_DEV_HYPERION_GPS_CREATE_NMEA_CSV == 1
|
||||
std::string filename = "/mnt/sd0/gps_log.txt";
|
||||
std::ofstream gpsFile;
|
||||
if (not std::filesystem::exists(filename)) {
|
||||
gpsFile.open(filename, std::ofstream::out);
|
||||
}
|
||||
gpsFile.open(filename, std::ofstream::out | std::ofstream::app);
|
||||
gpsFile.write("\n", 1);
|
||||
gpsFile.write(reinterpret_cast<const char *>(start), len);
|
||||
#endif
|
||||
}
|
||||
*foundLen = len;
|
||||
*foundId = GpsHyperion::GPS_REPLY;
|
||||
}
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t GPSHyperionHandler::interpretDeviceReply(DeviceCommandId_t id,
|
||||
const uint8_t *packet) {
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
uint32_t GPSHyperionHandler::getTransitionDelayMs(Mode_t from, Mode_t to) { return 5000; }
|
||||
|
||||
ReturnValue_t GPSHyperionHandler::initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
|
||||
LocalDataPoolManager &poolManager) {
|
||||
localDataPoolMap.emplace(GpsHyperion::ALTITUDE, new PoolEntry<double>({0.0}));
|
||||
localDataPoolMap.emplace(GpsHyperion::LONGITUDE, new PoolEntry<double>({0.0}));
|
||||
localDataPoolMap.emplace(GpsHyperion::LATITUDE, new PoolEntry<double>({0.0}));
|
||||
localDataPoolMap.emplace(GpsHyperion::YEAR, new PoolEntry<uint16_t>());
|
||||
localDataPoolMap.emplace(GpsHyperion::MONTH, new PoolEntry<uint8_t>());
|
||||
localDataPoolMap.emplace(GpsHyperion::DAY, new PoolEntry<uint8_t>());
|
||||
localDataPoolMap.emplace(GpsHyperion::HOURS, new PoolEntry<uint8_t>());
|
||||
localDataPoolMap.emplace(GpsHyperion::MINUTES, new PoolEntry<uint8_t>());
|
||||
localDataPoolMap.emplace(GpsHyperion::SECONDS, new PoolEntry<uint8_t>());
|
||||
localDataPoolMap.emplace(GpsHyperion::UNIX_SECONDS, new PoolEntry<uint32_t>());
|
||||
localDataPoolMap.emplace(GpsHyperion::SATS_IN_USE, new PoolEntry<uint8_t>());
|
||||
localDataPoolMap.emplace(GpsHyperion::FIX_MODE, new PoolEntry<uint8_t>());
|
||||
poolManager.subscribeForPeriodicPacket(gpsSet.getSid(), false, 30.0, false);
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
void GPSHyperionHandler::fillCommandAndReplyMap() {
|
||||
// Reply length does not matter, packets should always arrive periodically
|
||||
insertInReplyMap(GpsHyperion::GPS_REPLY, 4, &gpsSet, 0, true);
|
||||
insertInCommandMap(GpsHyperion::TRIGGER_RESET_PIN);
|
||||
}
|
||||
|
||||
void GPSHyperionHandler::modeChanged() { internalState = InternalStates::NONE; }
|
||||
|
||||
void GPSHyperionHandler::setResetPinTriggerFunction(gpioResetFunction_t resetCallback, void *args) {
|
||||
this->resetCallback = resetCallback;
|
||||
resetCallbackArgs = args;
|
||||
}
|
||||
|
||||
void GPSHyperionHandler::debugInterface(uint8_t positionTracker, object_id_t objectId,
|
||||
uint32_t parameter) {}
|
||||
|
||||
ReturnValue_t GPSHyperionHandler::initialize() {
|
||||
ReturnValue_t result = DeviceHandlerBase::initialize();
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
// Enable reply immediately for now
|
||||
return updatePeriodicReply(true, GpsHyperion::GPS_REPLY);
|
||||
}
|
||||
|
||||
ReturnValue_t GPSHyperionHandler::acceptExternalDeviceCommands() {
|
||||
return DeviceHandlerBase::acceptExternalDeviceCommands();
|
||||
}
|
62
mission/acs/archive/GPSHyperionHandler.h
Normal file
62
mission/acs/archive/GPSHyperionHandler.h
Normal file
@ -0,0 +1,62 @@
|
||||
#ifndef MISSION_DEVICES_GPSHYPERIONHANDLER_H_
|
||||
#define MISSION_DEVICES_GPSHYPERIONHANDLER_H_
|
||||
|
||||
#include <mission/acs/archive/GPSDefinitions.h>
|
||||
|
||||
#include "fsfw/FSFW.h"
|
||||
#include "fsfw/devicehandlers/DeviceHandlerBase.h"
|
||||
#include "lwgps/lwgps.h"
|
||||
|
||||
/**
|
||||
* @brief Device handler for the Hyperion HT-GPS200 device
|
||||
* @details
|
||||
* Flight manual:
|
||||
* https://egit.irs.uni-stuttgart.de/redmine/projects/eive-flight-manual/wiki/Hyperion_HT-GPS200
|
||||
*/
|
||||
class GPSHyperionHandler : public DeviceHandlerBase {
|
||||
public:
|
||||
GPSHyperionHandler(object_id_t objectId, object_id_t deviceCommunication, CookieIF *comCookie,
|
||||
bool debugHyperionGps = false);
|
||||
virtual ~GPSHyperionHandler();
|
||||
|
||||
using gpioResetFunction_t = ReturnValue_t (*)(void *args);
|
||||
|
||||
void setResetPinTriggerFunction(gpioResetFunction_t resetCallback, void *args);
|
||||
ReturnValue_t acceptExternalDeviceCommands() override;
|
||||
|
||||
ReturnValue_t initialize() override;
|
||||
|
||||
protected:
|
||||
gpioResetFunction_t resetCallback = nullptr;
|
||||
void *resetCallbackArgs = nullptr;
|
||||
|
||||
enum class InternalStates { NONE, WAIT_FIRST_MESSAGE, IDLE };
|
||||
InternalStates internalState = InternalStates::NONE;
|
||||
bool commandExecuted = false;
|
||||
|
||||
/* DeviceHandlerBase overrides */
|
||||
ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t *id) override;
|
||||
void doStartUp() override;
|
||||
void doShutDown() override;
|
||||
ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t *id) override;
|
||||
ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, const uint8_t *commandData,
|
||||
size_t commandDataLen) override;
|
||||
ReturnValue_t scanForReply(const uint8_t *start, size_t len, DeviceCommandId_t *foundId,
|
||||
size_t *foundLen) override;
|
||||
ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) override;
|
||||
|
||||
void fillCommandAndReplyMap() override;
|
||||
void modeChanged() override;
|
||||
uint32_t getTransitionDelayMs(Mode_t from, Mode_t to) override;
|
||||
ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
|
||||
LocalDataPoolManager &poolManager) override;
|
||||
virtual void debugInterface(uint8_t positionTracker = 0, object_id_t objectId = 0,
|
||||
uint32_t parameter = 0) override;
|
||||
|
||||
private:
|
||||
lwgps_t gpsData = {};
|
||||
GpsPrimaryDataset gpsSet;
|
||||
bool debugHyperionGps = false;
|
||||
};
|
||||
|
||||
#endif /* MISSION_DEVICES_GPSHYPERIONHANDLER_H_ */
|
233
mission/acs/archive/LegacySusHandler.cpp
Normal file
233
mission/acs/archive/LegacySusHandler.cpp
Normal file
@ -0,0 +1,233 @@
|
||||
#include <fsfw/datapool/PoolReadGuard.h>
|
||||
#include <fsfw/globalfunctions/arrayprinter.h>
|
||||
#include <mission/devices/LegacySusHandler.h>
|
||||
|
||||
#include "OBSWConfig.h"
|
||||
|
||||
LegacySusHandler::LegacySusHandler(object_id_t objectId, uint8_t susIdx, object_id_t comIF,
|
||||
CookieIF *comCookie)
|
||||
: DeviceHandlerBase(objectId, comIF, comCookie), divider(5), dataset(this), susIdx(susIdx) {}
|
||||
|
||||
LegacySusHandler::~LegacySusHandler() {}
|
||||
|
||||
void LegacySusHandler::doStartUp() {
|
||||
if (comState == ComStates::IDLE) {
|
||||
comState = ComStates::WRITE_SETUP;
|
||||
commandExecuted = false;
|
||||
}
|
||||
if (comState == ComStates::WRITE_SETUP) {
|
||||
if (commandExecuted) {
|
||||
if (goToNormalModeImmediately) {
|
||||
setMode(MODE_NORMAL);
|
||||
} else {
|
||||
setMode(_MODE_TO_ON);
|
||||
}
|
||||
commandExecuted = false;
|
||||
if (clkMode == ClkModes::INT_CLOCKED) {
|
||||
comState = ComStates::START_INT_CLOCKED_CONVERSIONS;
|
||||
} else {
|
||||
comState = ComStates::EXT_CLOCKED_CONVERSIONS;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void LegacySusHandler::doShutDown() {
|
||||
setMode(_MODE_POWER_DOWN);
|
||||
comState = ComStates::IDLE;
|
||||
}
|
||||
|
||||
ReturnValue_t LegacySusHandler::buildNormalDeviceCommand(DeviceCommandId_t *id) {
|
||||
switch (comState) {
|
||||
case (ComStates::IDLE): {
|
||||
break;
|
||||
}
|
||||
case (ComStates::WRITE_SETUP): {
|
||||
*id = susMax1227::WRITE_SETUP;
|
||||
return buildCommandFromCommand(*id, nullptr, 0);
|
||||
}
|
||||
case (ComStates::EXT_CLOCKED_CONVERSIONS): {
|
||||
*id = susMax1227::READ_EXT_TIMED_CONVERSIONS;
|
||||
return buildCommandFromCommand(*id, nullptr, 0);
|
||||
}
|
||||
case (ComStates::START_INT_CLOCKED_CONVERSIONS): {
|
||||
*id = susMax1227::START_INT_TIMED_CONVERSIONS;
|
||||
comState = ComStates::READ_INT_CLOCKED_CONVERSIONS;
|
||||
return buildCommandFromCommand(*id, nullptr, 0);
|
||||
}
|
||||
case (ComStates::READ_INT_CLOCKED_CONVERSIONS): {
|
||||
*id = susMax1227::READ_INT_TIMED_CONVERSIONS;
|
||||
comState = ComStates::START_INT_CLOCKED_CONVERSIONS;
|
||||
return buildCommandFromCommand(*id, nullptr, 0);
|
||||
}
|
||||
case (ComStates::EXT_CLOCKED_TEMP): {
|
||||
*id = susMax1227::READ_EXT_TIMED_TEMPS;
|
||||
return buildCommandFromCommand(*id, nullptr, 0);
|
||||
}
|
||||
}
|
||||
return NOTHING_TO_SEND;
|
||||
}
|
||||
|
||||
ReturnValue_t LegacySusHandler::buildTransitionDeviceCommand(DeviceCommandId_t *id) {
|
||||
if (comState == ComStates::WRITE_SETUP) {
|
||||
*id = susMax1227::WRITE_SETUP;
|
||||
return buildCommandFromCommand(*id, nullptr, 0);
|
||||
}
|
||||
return NOTHING_TO_SEND;
|
||||
}
|
||||
|
||||
ReturnValue_t LegacySusHandler::buildCommandFromCommand(DeviceCommandId_t deviceCommand,
|
||||
const uint8_t *commandData,
|
||||
size_t commandDataLen) {
|
||||
using namespace max1227;
|
||||
switch (deviceCommand) {
|
||||
case (susMax1227::WRITE_SETUP): {
|
||||
if (clkMode == ClkModes::INT_CLOCKED) {
|
||||
cmdBuffer[0] = susMax1227::SETUP_INT_CLOKED;
|
||||
} else {
|
||||
cmdBuffer[0] = susMax1227::SETUP_EXT_CLOCKED;
|
||||
}
|
||||
|
||||
rawPacket = cmdBuffer;
|
||||
rawPacketLen = 1;
|
||||
break;
|
||||
}
|
||||
case (susMax1227::START_INT_TIMED_CONVERSIONS): {
|
||||
std::memset(cmdBuffer, 0, sizeof(cmdBuffer));
|
||||
cmdBuffer[0] = max1227::buildResetByte(true);
|
||||
cmdBuffer[1] = susMax1227::CONVERSION;
|
||||
rawPacket = cmdBuffer;
|
||||
rawPacketLen = 2;
|
||||
break;
|
||||
}
|
||||
case (susMax1227::READ_INT_TIMED_CONVERSIONS): {
|
||||
std::memset(cmdBuffer, 0, sizeof(cmdBuffer));
|
||||
rawPacket = cmdBuffer;
|
||||
rawPacketLen = susMax1227::SIZE_READ_INT_CONVERSIONS;
|
||||
break;
|
||||
}
|
||||
case (susMax1227::READ_EXT_TIMED_CONVERSIONS): {
|
||||
std::memset(cmdBuffer, 0, sizeof(cmdBuffer));
|
||||
rawPacket = cmdBuffer;
|
||||
for (uint8_t idx = 0; idx < 6; idx++) {
|
||||
cmdBuffer[idx * 2] = buildConvByte(ScanModes::N_ONCE, idx, false);
|
||||
cmdBuffer[idx * 2 + 1] = 0;
|
||||
}
|
||||
cmdBuffer[12] = 0x00;
|
||||
rawPacketLen = susMax1227::SIZE_READ_EXT_CONVERSIONS;
|
||||
break;
|
||||
}
|
||||
case (susMax1227::READ_EXT_TIMED_TEMPS): {
|
||||
cmdBuffer[0] = buildConvByte(ScanModes::N_ONCE, 0, true);
|
||||
std::memset(cmdBuffer + 1, 0, 24);
|
||||
rawPacket = cmdBuffer;
|
||||
rawPacketLen = 25;
|
||||
break;
|
||||
}
|
||||
default:
|
||||
return DeviceHandlerIF::COMMAND_NOT_IMPLEMENTED;
|
||||
}
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
void LegacySusHandler::fillCommandAndReplyMap() {
|
||||
insertInCommandAndReplyMap(susMax1227::WRITE_SETUP, 1);
|
||||
insertInCommandAndReplyMap(susMax1227::START_INT_TIMED_CONVERSIONS, 1);
|
||||
insertInCommandAndReplyMap(susMax1227::READ_INT_TIMED_CONVERSIONS, 1, &dataset,
|
||||
susMax1227::SIZE_READ_INT_CONVERSIONS);
|
||||
insertInCommandAndReplyMap(susMax1227::READ_EXT_TIMED_CONVERSIONS, 1, &dataset,
|
||||
susMax1227::SIZE_READ_EXT_CONVERSIONS);
|
||||
insertInCommandAndReplyMap(susMax1227::READ_EXT_TIMED_TEMPS, 1);
|
||||
}
|
||||
|
||||
ReturnValue_t LegacySusHandler::scanForReply(const uint8_t *start, size_t remainingSize,
|
||||
DeviceCommandId_t *foundId, size_t *foundLen) {
|
||||
*foundId = this->getPendingCommand();
|
||||
*foundLen = remainingSize;
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t LegacySusHandler::interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) {
|
||||
switch (id) {
|
||||
case susMax1227::WRITE_SETUP: {
|
||||
if (getMode() == _MODE_START_UP) {
|
||||
commandExecuted = true;
|
||||
}
|
||||
return returnvalue::OK;
|
||||
}
|
||||
case susMax1227::START_INT_TIMED_CONVERSIONS: {
|
||||
return returnvalue::OK;
|
||||
}
|
||||
case susMax1227::READ_INT_TIMED_CONVERSIONS: {
|
||||
PoolReadGuard readSet(&dataset);
|
||||
dataset.tempC = max1227::getTemperature(((packet[0] & 0x0f) << 8) | packet[1]);
|
||||
for (uint8_t idx = 0; idx < 6; idx++) {
|
||||
dataset.channels[idx] = packet[idx * 2 + 2] << 8 | packet[idx * 2 + 3];
|
||||
}
|
||||
dataset.setValidity(true, true);
|
||||
printDataset();
|
||||
break;
|
||||
}
|
||||
case (susMax1227::READ_EXT_TIMED_CONVERSIONS): {
|
||||
PoolReadGuard readSet(&dataset);
|
||||
for (uint8_t idx = 0; idx < 6; idx++) {
|
||||
dataset.channels[idx] = packet[idx * 2 + 1] << 8 | packet[idx * 2 + 2];
|
||||
}
|
||||
dataset.channels.setValid(true);
|
||||
// Read temperature in next read cycle
|
||||
if (clkMode == ClkModes::EXT_CLOCKED_WITH_TEMP) {
|
||||
comState = ComStates::EXT_CLOCKED_TEMP;
|
||||
}
|
||||
printDataset();
|
||||
break;
|
||||
}
|
||||
case (susMax1227::READ_EXT_TIMED_TEMPS): {
|
||||
PoolReadGuard readSet(&dataset);
|
||||
dataset.tempC = max1227::getTemperature(((packet[23] & 0x0f) << 8) | packet[24]);
|
||||
dataset.tempC.setValid(true);
|
||||
comState = ComStates::EXT_CLOCKED_CONVERSIONS;
|
||||
break;
|
||||
}
|
||||
default: {
|
||||
sif::debug << "SusHandler::interpretDeviceReply: Unknown reply id" << std::endl;
|
||||
return DeviceHandlerIF::UNKNOWN_DEVICE_REPLY;
|
||||
}
|
||||
}
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
uint32_t LegacySusHandler::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { return 3000; }
|
||||
|
||||
ReturnValue_t LegacySusHandler::initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
|
||||
LocalDataPoolManager &poolManager) {
|
||||
localDataPoolMap.emplace(susMax1227::TEMPERATURE_C, &tempC);
|
||||
localDataPoolMap.emplace(susMax1227::CHANNEL_VEC, &channelVec);
|
||||
poolManager.subscribeForDiagPeriodicPacket(
|
||||
subdp::DiagnosticsHkPeriodicParams(dataset.getSid(), false, 5.0));
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
void LegacySusHandler::setToGoToNormalMode(bool enable) {
|
||||
this->goToNormalModeImmediately = enable;
|
||||
}
|
||||
|
||||
void LegacySusHandler::printDataset() {
|
||||
if (periodicPrintout) {
|
||||
if (divider.checkAndIncrement()) {
|
||||
sif::info << "SUS ADC " << static_cast<int>(susIdx) << " hex [" << std::setfill('0')
|
||||
<< std::hex;
|
||||
for (uint8_t idx = 0; idx < 6; idx++) {
|
||||
sif::info << std::setw(3) << dataset.channels[idx];
|
||||
if (idx < 6 - 1) {
|
||||
sif::info << ",";
|
||||
}
|
||||
}
|
||||
sif::info << "] | T[C] " << std::dec << dataset.tempC.value << std::endl;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void LegacySusHandler::enablePeriodicPrintout(bool enable, uint8_t divider) {
|
||||
this->periodicPrintout = enable;
|
||||
this->divider.setDivider(divider);
|
||||
}
|
92
mission/acs/archive/LegacySusHandler.h
Normal file
92
mission/acs/archive/LegacySusHandler.h
Normal file
@ -0,0 +1,92 @@
|
||||
#ifndef MISSION_DEVICES_LEGACYSUSHANDLER_H_
|
||||
#define MISSION_DEVICES_LEGACYSUSHANDLER_H_
|
||||
|
||||
#include <fsfw/devicehandlers/DeviceHandlerBase.h>
|
||||
#include <mission/acs/susMax1227Helpers.h>
|
||||
#include <mission/tcs/max1227.h>
|
||||
|
||||
#include "events/subsystemIdRanges.h"
|
||||
#include "fsfw/globalfunctions/PeriodicOperationDivider.h"
|
||||
#include "returnvalues/classIds.h"
|
||||
|
||||
/**
|
||||
* @brief This is the device handler class for the SUS sensor based on the MAX1227 ADC.
|
||||
*
|
||||
* @details
|
||||
* Datasheet of MAX1227: https://datasheets.maximintegrated.com/en/ds/MAX1227-MAX1231.pdf
|
||||
* Details about the SUS electronic can be found at
|
||||
* https://egit.irs.uni-stuttgart.de/eive/eive_dokumente/src/branch/master/400_Raumsegment/443_SunSensorDocumentation/release
|
||||
*
|
||||
* @note When adding a SusHandler to the polling sequence table make sure to add a slot with
|
||||
* the executionStep FIRST_WRITE. Otherwise the communication sequence will never be
|
||||
* started.
|
||||
*
|
||||
* @author J. Meier
|
||||
*/
|
||||
class LegacySusHandler : public DeviceHandlerBase {
|
||||
public:
|
||||
enum ClkModes { INT_CLOCKED, EXT_CLOCKED, EXT_CLOCKED_WITH_TEMP };
|
||||
|
||||
static const uint8_t FIRST_WRITE = 7;
|
||||
|
||||
LegacySusHandler(object_id_t objectId, uint8_t susIdx, object_id_t comIF, CookieIF* comCookie);
|
||||
virtual ~LegacySusHandler();
|
||||
|
||||
void enablePeriodicPrintout(bool enable, uint8_t divider);
|
||||
|
||||
void setToGoToNormalMode(bool enable);
|
||||
|
||||
protected:
|
||||
void doStartUp() override;
|
||||
void doShutDown() override;
|
||||
ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t* id) override;
|
||||
ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t* id) override;
|
||||
void fillCommandAndReplyMap() override;
|
||||
ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, const uint8_t* commandData,
|
||||
size_t commandDataLen) override;
|
||||
ReturnValue_t scanForReply(const uint8_t* start, size_t remainingSize, DeviceCommandId_t* foundId,
|
||||
size_t* foundLen) override;
|
||||
ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t* packet) override;
|
||||
uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override;
|
||||
ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap,
|
||||
LocalDataPoolManager& poolManager) override;
|
||||
|
||||
private:
|
||||
static const uint8_t INTERFACE_ID = CLASS_ID::SUS_HANDLER;
|
||||
|
||||
static const ReturnValue_t ERROR_UNLOCK_MUTEX = MAKE_RETURN_CODE(0xA0);
|
||||
static const ReturnValue_t ERROR_LOCK_MUTEX = MAKE_RETURN_CODE(0xA1);
|
||||
|
||||
enum class ComStates {
|
||||
IDLE,
|
||||
WRITE_SETUP,
|
||||
EXT_CLOCKED_CONVERSIONS,
|
||||
EXT_CLOCKED_TEMP,
|
||||
START_INT_CLOCKED_CONVERSIONS,
|
||||
READ_INT_CLOCKED_CONVERSIONS
|
||||
};
|
||||
|
||||
bool periodicPrintout = false;
|
||||
PeriodicOperationDivider divider;
|
||||
bool goToNormalModeImmediately = false;
|
||||
bool commandExecuted = false;
|
||||
|
||||
susMax1227::SusDataset dataset;
|
||||
// Read temperature in each alternating communication step when using
|
||||
// externally clocked mode
|
||||
ClkModes clkMode = ClkModes::INT_CLOCKED;
|
||||
PoolEntry<float> tempC = PoolEntry<float>({0.0});
|
||||
PoolEntry<uint16_t> channelVec = PoolEntry<uint16_t>({0, 0, 0, 0, 0, 0});
|
||||
|
||||
uint8_t susIdx = 0;
|
||||
uint8_t cmdBuffer[susMax1227::MAX_CMD_SIZE];
|
||||
ComStates comState = ComStates::IDLE;
|
||||
|
||||
MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING;
|
||||
uint32_t timeoutMs = 20;
|
||||
void printDataset();
|
||||
|
||||
MutexIF* spiMutex = nullptr;
|
||||
};
|
||||
|
||||
#endif /* MISSION_DEVICES_LEGACYSUSHANDLER_H_ */
|
36
mission/acs/defs.cpp
Normal file
36
mission/acs/defs.cpp
Normal file
@ -0,0 +1,36 @@
|
||||
#include "defs.h"
|
||||
|
||||
const char* acs::getModeStr(AcsMode mode) {
|
||||
static const char* modeStr = "UNKNOWN";
|
||||
switch (mode) {
|
||||
case (acs::AcsMode::OFF): {
|
||||
modeStr = "OFF";
|
||||
break;
|
||||
}
|
||||
case (acs::AcsMode::SAFE): {
|
||||
modeStr = "SAFE";
|
||||
break;
|
||||
}
|
||||
case (acs::AcsMode::PTG_NADIR): {
|
||||
modeStr = "POITNING NADIR";
|
||||
break;
|
||||
}
|
||||
case (acs::AcsMode::PTG_IDLE): {
|
||||
modeStr = "POINTING IDLE";
|
||||
break;
|
||||
}
|
||||
case (acs::AcsMode::PTG_INERTIAL): {
|
||||
modeStr = "POINTING INERTIAL";
|
||||
break;
|
||||
}
|
||||
case (acs::AcsMode::PTG_TARGET): {
|
||||
modeStr = "POINTING TARGET";
|
||||
break;
|
||||
}
|
||||
case (acs::AcsMode::PTG_TARGET_GS): {
|
||||
modeStr = "POINTING TARGET GS";
|
||||
break;
|
||||
}
|
||||
}
|
||||
return modeStr;
|
||||
}
|
51
mission/acs/defs.h
Normal file
51
mission/acs/defs.h
Normal file
@ -0,0 +1,51 @@
|
||||
#ifndef MISSION_ACSDEFS_H_
|
||||
#define MISSION_ACSDEFS_H_
|
||||
|
||||
#include <eive/eventSubsystemIds.h>
|
||||
#include <fsfw/modes/HasModesIF.h>
|
||||
|
||||
namespace acs {
|
||||
|
||||
enum class SimpleSensorMode { NORMAL = 0, OFF = 1 };
|
||||
|
||||
// These modes are the modes of the ACS controller and of the ACS subsystem.
|
||||
enum AcsMode : Mode_t {
|
||||
OFF = HasModesIF::MODE_OFF,
|
||||
SAFE = 10,
|
||||
PTG_IDLE = 11,
|
||||
PTG_NADIR = 12,
|
||||
PTG_TARGET = 13,
|
||||
PTG_TARGET_GS = 14,
|
||||
PTG_INERTIAL = 15,
|
||||
};
|
||||
|
||||
enum SafeSubmode : Submode_t { DEFAULT = 0, DETUMBLE = 1 };
|
||||
|
||||
static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::ACS_SUBSYSTEM;
|
||||
//! [EXPORT] : [COMMENT] The limits for the rotation in safe mode were violated.
|
||||
static constexpr Event SAFE_RATE_VIOLATION = MAKE_EVENT(0, severity::MEDIUM);
|
||||
//! [EXPORT] : [COMMENT] The system has recovered from a safe rate rotation violation.
|
||||
static constexpr Event SAFE_RATE_RECOVERY = MAKE_EVENT(1, severity::MEDIUM);
|
||||
//! [EXPORT] : [COMMENT] Multiple RWs are invalid, uncommandable and therefore higher ACS modes
|
||||
//! cannot be maintained.
|
||||
static constexpr Event MULTIPLE_RW_INVALID = MAKE_EVENT(2, severity::HIGH);
|
||||
//! [EXPORT] : [COMMENT] MEKF was not able to compute a solution.
|
||||
//! P1: MEKF state on exit
|
||||
static constexpr Event MEKF_INVALID_INFO = MAKE_EVENT(3, severity::INFO);
|
||||
//! [EXPORT] : [COMMENT] MEKF is able to compute a solution again.
|
||||
static constexpr Event MEKF_RECOVERY = MAKE_EVENT(4, severity::INFO);
|
||||
//! [EXPORT] : [COMMENT] MEKF performed an automatic reset after detection of nonfinite values.
|
||||
static constexpr Event MEKF_AUTOMATIC_RESET = MAKE_EVENT(5, severity::INFO);
|
||||
//! [EXPORT] : [COMMENT] MEKF was not able to compute a solution during any pointing ACS mode for a
|
||||
//! prolonged time.
|
||||
static constexpr Event MEKF_INVALID_MODE_VIOLATION = MAKE_EVENT(6, severity::HIGH);
|
||||
//! [EXPORT] : [COMMENT] The ACS safe mode controller was not able to compute a solution and has
|
||||
//! failed.
|
||||
//! P1: Missing information about magnetic field, P2: Missing information about rotational rate
|
||||
static constexpr Event SAFE_MODE_CONTROLLER_FAILURE = MAKE_EVENT(7, severity::HIGH);
|
||||
|
||||
extern const char* getModeStr(AcsMode mode);
|
||||
|
||||
} // namespace acs
|
||||
|
||||
#endif /* MISSION_ACSDEFS_H_ */
|
54
mission/acs/gyroAdisHelpers.cpp
Normal file
54
mission/acs/gyroAdisHelpers.cpp
Normal file
@ -0,0 +1,54 @@
|
||||
#include "gyroAdisHelpers.h"
|
||||
|
||||
size_t adis1650x::prepareReadCommand(const uint8_t* regList, size_t len, uint8_t* outBuf,
|
||||
size_t maxLen) {
|
||||
if (len * 2 + 2 > maxLen) {
|
||||
return 0;
|
||||
}
|
||||
for (size_t idx = 0; idx < len; idx++) {
|
||||
outBuf[idx * 2] = regList[idx];
|
||||
outBuf[idx * 2 + 1] = 0x00;
|
||||
}
|
||||
outBuf[len * 2] = 0x00;
|
||||
outBuf[len * 2 + 1] = 0x00;
|
||||
return len * 2 + 2;
|
||||
}
|
||||
|
||||
adis1650x::BurstModes adis1650x::burstModeFromMscCtrl(uint16_t mscCtrl) {
|
||||
if ((mscCtrl & adis1650x::BURST_32_BIT) == adis1650x::BURST_32_BIT) {
|
||||
if ((mscCtrl & adis1650x::BURST_SEL_BIT) == adis1650x::BURST_SEL_BIT) {
|
||||
return BurstModes::BURST_32_BURST_SEL_1;
|
||||
} else {
|
||||
return BurstModes::BURST_32_BURST_SEL_0;
|
||||
}
|
||||
} else {
|
||||
if ((mscCtrl & adis1650x::BURST_SEL_BIT) == adis1650x::BURST_SEL_BIT) {
|
||||
return BurstModes::BURST_16_BURST_SEL_1;
|
||||
} else {
|
||||
return BurstModes::BURST_16_BURST_SEL_0;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
double adis1650x::rangMdlToSensitivity(uint16_t rangMdl) {
|
||||
adis1650x::RangMdlBitfield bitfield =
|
||||
static_cast<adis1650x::RangMdlBitfield>((rangMdl >> 2) & 0b11);
|
||||
switch (bitfield) {
|
||||
case (adis1650x::RangMdlBitfield::RANGE_125_1BMLZ): {
|
||||
return SENSITIVITY_1BMLZ;
|
||||
}
|
||||
case (adis1650x::RangMdlBitfield::RANGE_500_2BMLZ): {
|
||||
return SENSITIVITY_2BMLZ;
|
||||
}
|
||||
case (adis1650x::RangMdlBitfield::RANGE_2000_3BMLZ): {
|
||||
return SENSITIVITY_3BMLZ;
|
||||
}
|
||||
case (RangMdlBitfield::RESERVED):
|
||||
default: {
|
||||
#if FSFW_CPP_OSTREAM_ENABLED == 1
|
||||
sif::error << "ADIS1650X: Unexpected value for RANG_MDL register" << std::endl;
|
||||
#endif
|
||||
return 0.0;
|
||||
}
|
||||
}
|
||||
}
|
181
mission/acs/gyroAdisHelpers.h
Normal file
181
mission/acs/gyroAdisHelpers.h
Normal file
@ -0,0 +1,181 @@
|
||||
#ifndef MISSION_DEVICES_DEVICEDEFINITIONS_GYROADIS16507DEFINITIONS_H_
|
||||
#define MISSION_DEVICES_DEVICEDEFINITIONS_GYROADIS16507DEFINITIONS_H_
|
||||
|
||||
#include <cstddef>
|
||||
|
||||
#include "fsfw/datapoollocal/StaticLocalDataSet.h"
|
||||
#include "fsfw/devicehandlers/DeviceHandlerIF.h"
|
||||
|
||||
namespace adis1650x {
|
||||
|
||||
enum class BurstModes {
|
||||
BURST_16_BURST_SEL_0,
|
||||
BURST_16_BURST_SEL_1,
|
||||
BURST_32_BURST_SEL_0,
|
||||
BURST_32_BURST_SEL_1
|
||||
};
|
||||
|
||||
size_t prepareReadCommand(const uint8_t* regList, size_t len, uint8_t* outBuf, size_t maxLen);
|
||||
BurstModes burstModeFromMscCtrl(uint16_t mscCtrl);
|
||||
double rangMdlToSensitivity(uint16_t rangMdl);
|
||||
|
||||
enum class Type : uint8_t { ADIS16505, ADIS16507 };
|
||||
|
||||
static constexpr size_t MAXIMUM_REPLY_SIZE = 64;
|
||||
static constexpr uint8_t WRITE_MASK = 0b1000'0000;
|
||||
|
||||
// Ranges in deg / s
|
||||
static constexpr double RANGE_UNSET = 0.0;
|
||||
static constexpr double RANGE_1BMLZ = 125.0;
|
||||
static constexpr double RANGE_2BMLZ = 500.0;
|
||||
static constexpr double RANGE_3BMLZ = 2000.0;
|
||||
// Sensitivities in deg/s/LSB
|
||||
static constexpr double SENSITIVITY_UNSET = 0.0;
|
||||
static constexpr double SENSITIVITY_1BMLZ = 0.00625;
|
||||
static constexpr double SENSITIVITY_2BMLZ = 0.025;
|
||||
static constexpr double SENSITIVITY_3BMLZ = 0.1;
|
||||
|
||||
enum RangMdlBitfield {
|
||||
RANGE_125_1BMLZ = 0b00,
|
||||
RANGE_500_2BMLZ = 0b01,
|
||||
RESERVED = 0b10,
|
||||
RANGE_2000_3BMLZ = 0b11
|
||||
};
|
||||
|
||||
static constexpr uint32_t ACCELEROMETER_RANGE_16507 = 392;
|
||||
static constexpr float ACCELEROMETER_RANGE_16505 = 78.4;
|
||||
|
||||
static constexpr uint32_t STALL_TIME_MICROSECONDS = 16;
|
||||
|
||||
static constexpr uint16_t PROD_ID_16507 = 16507;
|
||||
static constexpr uint16_t PROD_ID_16505 = 16505;
|
||||
|
||||
static constexpr std::array<uint8_t, 2> BURST_READ_ENABLE = {0x68, 0x00};
|
||||
|
||||
static constexpr dur_millis_t START_UP_TIME = 310;
|
||||
static constexpr dur_millis_t SW_RESET_BREAK = 255;
|
||||
static constexpr dur_millis_t FACTORY_CALIBRATION_BREAK = 136;
|
||||
static constexpr dur_millis_t FLASH_MEMORY_UPDATE_BREAK = 70;
|
||||
static constexpr dur_millis_t FLASH_MEMORY_TEST_BREAK = 30;
|
||||
static constexpr dur_millis_t SELF_TEST_BREAK = 24;
|
||||
|
||||
static constexpr uint8_t DIAG_STAT_REG = 0x02;
|
||||
static constexpr uint8_t FILTER_CTRL_REG = 0x5c;
|
||||
static constexpr uint8_t RANG_MDL_REG = 0x5e;
|
||||
static constexpr uint8_t MSC_CTRL_REG = 0x60;
|
||||
static constexpr uint8_t DEC_RATE_REG = 0x64;
|
||||
static constexpr uint8_t GLOB_CMD = 0x68;
|
||||
static constexpr uint8_t PROD_ID_REG = 0x72;
|
||||
|
||||
static constexpr DeviceCommandId_t READ_SENSOR_DATA = 0;
|
||||
static constexpr DeviceCommandId_t READ_OUT_CONFIG = 1;
|
||||
static constexpr DeviceCommandId_t SELF_TEST_SENSORS = 2;
|
||||
static constexpr DeviceCommandId_t SELF_TEST_MEMORY = 3;
|
||||
static constexpr DeviceCommandId_t UPDATE_NV_CONFIGURATION = 4;
|
||||
static constexpr DeviceCommandId_t SELECT_BURST_READ_MODE = 5;
|
||||
|
||||
static constexpr DeviceCommandId_t RESET_SENSOR_CONFIGURATION = 30;
|
||||
static constexpr DeviceCommandId_t SW_RESET = 31;
|
||||
static constexpr DeviceCommandId_t PRINT_CURRENT_CONFIGURATION = 32;
|
||||
|
||||
static constexpr DeviceCommandId_t REQUEST = 0x70;
|
||||
static constexpr DeviceCommandId_t REPLY = 0x77;
|
||||
|
||||
static constexpr uint16_t BURST_32_BIT = 1 << 9;
|
||||
static constexpr uint16_t BURST_SEL_BIT = 1 << 8;
|
||||
static constexpr uint16_t LIN_ACCEL_COMPENSATION_BIT = 1 << 7;
|
||||
static constexpr uint16_t POINT_PERCUSSION_COMPENSATION_BIT = 1 << 6;
|
||||
|
||||
static constexpr size_t CONFIG_READOUT_SIZE = 12 + 2;
|
||||
static constexpr size_t SENSOR_READOUT_SIZE = 20 + 2;
|
||||
|
||||
static constexpr uint32_t ADIS_DATASET_ID = READ_SENSOR_DATA;
|
||||
static constexpr uint32_t ADIS_CFG_DATASET_ID = READ_OUT_CONFIG;
|
||||
|
||||
enum GlobCmds : uint8_t {
|
||||
FACTORY_CALIBRATION = 0b0000'0010,
|
||||
SENSOR_SELF_TEST = 0b0000'0100,
|
||||
FLASH_MEMORY_UPDATE = 0b0000'1000,
|
||||
FLASH_MEMORY_TEST = 0b0001'0000,
|
||||
SOFTWARE_RESET = 0b1000'0000
|
||||
};
|
||||
|
||||
enum PrimaryPoolIds : lp_id_t {
|
||||
ANG_VELOC_X,
|
||||
ANG_VELOC_Y,
|
||||
ANG_VELOC_Z,
|
||||
ACCELERATION_X,
|
||||
ACCELERATION_Y,
|
||||
ACCELERATION_Z,
|
||||
TEMPERATURE,
|
||||
DIAG_STAT_REGISTER,
|
||||
FILTER_SETTINGS,
|
||||
RANG_MDL,
|
||||
MSC_CTRL_REGISTER,
|
||||
DEC_RATE_REGISTER,
|
||||
};
|
||||
|
||||
enum FilterSettings : uint8_t {
|
||||
NO_FILTER = 0,
|
||||
TWO_TAPS = 1,
|
||||
FOUR_TAPS = 2,
|
||||
EIGHT_TAPS = 3,
|
||||
SIXTEEN_TAPS = 4,
|
||||
THIRTYTWO_TAPS = 5,
|
||||
SIXTYFOUR_TAPS = 6
|
||||
};
|
||||
|
||||
} // namespace adis1650x
|
||||
|
||||
class AdisGyroPrimaryDataset : public StaticLocalDataSet<8> {
|
||||
public:
|
||||
/** Constructor for data users like controllers */
|
||||
AdisGyroPrimaryDataset(object_id_t adisId)
|
||||
: StaticLocalDataSet(sid_t(adisId, adis1650x::ADIS_DATASET_ID)) {
|
||||
setAllVariablesReadOnly();
|
||||
}
|
||||
|
||||
/* Angular velocities in degrees per second (DPS) */
|
||||
lp_var_t<double> angVelocX = lp_var_t<double>(sid.objectId, adis1650x::ANG_VELOC_X, this);
|
||||
lp_var_t<double> angVelocY = lp_var_t<double>(sid.objectId, adis1650x::ANG_VELOC_Y, this);
|
||||
lp_var_t<double> angVelocZ = lp_var_t<double>(sid.objectId, adis1650x::ANG_VELOC_Z, this);
|
||||
lp_var_t<double> accelX = lp_var_t<double>(sid.objectId, adis1650x::ACCELERATION_X, this);
|
||||
lp_var_t<double> accelY = lp_var_t<double>(sid.objectId, adis1650x::ACCELERATION_Y, this);
|
||||
lp_var_t<double> accelZ = lp_var_t<double>(sid.objectId, adis1650x::ACCELERATION_Z, this);
|
||||
lp_var_t<float> temperature = lp_var_t<float>(sid.objectId, adis1650x::TEMPERATURE, this);
|
||||
|
||||
private:
|
||||
friend class GyrAdis1650XHandler;
|
||||
friend class GyroAdisDummy;
|
||||
|
||||
/** Constructor for the data creator */
|
||||
AdisGyroPrimaryDataset(HasLocalDataPoolIF* hkOwner)
|
||||
: StaticLocalDataSet(hkOwner, adis1650x::ADIS_DATASET_ID) {}
|
||||
};
|
||||
|
||||
class AdisGyroConfigDataset : public StaticLocalDataSet<5> {
|
||||
public:
|
||||
/** Constructor for data users like controllers */
|
||||
AdisGyroConfigDataset(object_id_t adisId)
|
||||
: StaticLocalDataSet(sid_t(adisId, adis1650x::ADIS_CFG_DATASET_ID)) {
|
||||
setAllVariablesReadOnly();
|
||||
}
|
||||
|
||||
lp_var_t<uint16_t> diagStatReg =
|
||||
lp_var_t<uint16_t>(sid.objectId, adis1650x::DIAG_STAT_REGISTER, this);
|
||||
lp_var_t<uint8_t> filterSetting =
|
||||
lp_var_t<uint8_t>(sid.objectId, adis1650x::FILTER_SETTINGS, this);
|
||||
lp_var_t<uint16_t> rangMdl = lp_var_t<uint16_t>(sid.objectId, adis1650x::RANG_MDL, this);
|
||||
lp_var_t<uint16_t> mscCtrlReg =
|
||||
lp_var_t<uint16_t>(sid.objectId, adis1650x::MSC_CTRL_REGISTER, this);
|
||||
lp_var_t<uint16_t> decRateReg =
|
||||
lp_var_t<uint16_t>(sid.objectId, adis1650x::DEC_RATE_REGISTER, this);
|
||||
|
||||
private:
|
||||
friend class GyrAdis1650XHandler;
|
||||
/** Constructor for the data creator */
|
||||
AdisGyroConfigDataset(HasLocalDataPoolIF* hkOwner)
|
||||
: StaticLocalDataSet(hkOwner, adis1650x::ADIS_CFG_DATASET_ID) {}
|
||||
};
|
||||
|
||||
#endif /* MISSION_DEVICES_DEVICEDEFINITIONS_GYROADIS16507DEFINITIONS_H_ */
|
70
mission/acs/imtqHelpers.cpp
Normal file
70
mission/acs/imtqHelpers.cpp
Normal file
@ -0,0 +1,70 @@
|
||||
#include "imtqHelpers.h"
|
||||
|
||||
uint16_t imtq::integrationTimeFromSelectValue(uint8_t value) {
|
||||
switch (value) {
|
||||
case (0):
|
||||
return 2;
|
||||
case (1):
|
||||
return 3;
|
||||
case (2):
|
||||
return 6;
|
||||
case (3):
|
||||
return 10;
|
||||
case (4):
|
||||
return 20;
|
||||
case (5):
|
||||
return 40;
|
||||
case (6):
|
||||
return 80;
|
||||
default:
|
||||
return 10;
|
||||
}
|
||||
}
|
||||
|
||||
size_t imtq::getReplySize(CC::CC cc, size_t* optSecondSize) {
|
||||
switch (cc) {
|
||||
// Software reset is a bit special and can also cause a I2C NAK because
|
||||
// the device might be reset at that moment. Otherwise, 2 bytes should be returned
|
||||
case (CC::CC::SOFTWARE_RESET): {
|
||||
if (optSecondSize != nullptr) {
|
||||
*optSecondSize = 0;
|
||||
}
|
||||
return 2;
|
||||
}
|
||||
case (CC::CC::START_ACTUATION_DIPOLE):
|
||||
case (CC::CC::SELF_TEST_CMD):
|
||||
case (CC::CC::START_MTM_MEASUREMENT): {
|
||||
return 2;
|
||||
}
|
||||
case (CC::CC::GET_SYSTEM_STATE): {
|
||||
return 9;
|
||||
}
|
||||
case (CC::CC::GET_RAW_MTM_MEASUREMENT):
|
||||
case (CC::CC::GET_CAL_MTM_MEASUREMENT): {
|
||||
return 15;
|
||||
}
|
||||
case (CC::CC::GET_COIL_CURRENT):
|
||||
case (CC::CC::GET_COMMANDED_DIPOLE):
|
||||
case (CC::CC::GET_COIL_TEMPERATURES): {
|
||||
return 8;
|
||||
}
|
||||
case (CC::CC::GET_SELF_TEST_RESULT): {
|
||||
// Can also be 360 for the all axes self-test!
|
||||
if (optSecondSize != nullptr) {
|
||||
*optSecondSize = 360;
|
||||
}
|
||||
return 120;
|
||||
}
|
||||
case (CC::CC::GET_RAW_HK_DATA):
|
||||
case (CC::CC::GET_ENG_HK_DATA): {
|
||||
return 24;
|
||||
}
|
||||
case (CC::CC::GET_PARAM): {
|
||||
return imtq::replySize::MAX_SET_GET_PARAM_LEN;
|
||||
}
|
||||
default: {
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
return 0;
|
||||
}
|
1239
mission/acs/imtqHelpers.h
Normal file
1239
mission/acs/imtqHelpers.h
Normal file
File diff suppressed because it is too large
Load Diff
54
mission/acs/rwHelpers.cpp
Normal file
54
mission/acs/rwHelpers.cpp
Normal file
@ -0,0 +1,54 @@
|
||||
#ifndef MISSION_DEVICES_DEVICEDEFINITIONS_RWHELPERS_CPP_
|
||||
#define MISSION_DEVICES_DEVICEDEFINITIONS_RWHELPERS_CPP_
|
||||
|
||||
#include "rwHelpers.h"
|
||||
|
||||
void rws::encodeHdlc(const uint8_t* sourceBuf, size_t sourceLen, uint8_t* encodedBuffer,
|
||||
size_t& encodedLen) {
|
||||
encodedBuffer[0] = rws::FRAME_DELIMITER;
|
||||
encodedLen = 1;
|
||||
for (size_t sourceIdx = 0; sourceIdx < sourceLen; sourceIdx++) {
|
||||
if (sourceBuf[sourceIdx] == 0x7E) {
|
||||
encodedBuffer[encodedLen++] = 0x7D;
|
||||
encodedBuffer[encodedLen++] = 0x5E;
|
||||
} else if (sourceBuf[sourceIdx] == 0x7D) {
|
||||
encodedBuffer[encodedLen++] = 0x7D;
|
||||
encodedBuffer[encodedLen++] = 0x5D;
|
||||
} else {
|
||||
encodedBuffer[encodedLen++] = sourceBuf[sourceIdx];
|
||||
}
|
||||
}
|
||||
encodedBuffer[encodedLen++] = rws::FRAME_DELIMITER;
|
||||
}
|
||||
|
||||
size_t rws::idToPacketLen(DeviceCommandId_t id) {
|
||||
switch (id) {
|
||||
case (rws::GET_RW_STATUS): {
|
||||
return rws::SIZE_GET_RW_STATUS;
|
||||
}
|
||||
case (rws::SET_SPEED): {
|
||||
return rws::SIZE_SET_SPEED_REPLY;
|
||||
}
|
||||
case (rws::CLEAR_LAST_RESET_STATUS): {
|
||||
return rws::SIZE_CLEAR_RESET_STATUS;
|
||||
}
|
||||
case (rws::GET_LAST_RESET_STATUS): {
|
||||
return rws::SIZE_GET_RESET_STATUS;
|
||||
}
|
||||
case (rws::GET_TEMPERATURE): {
|
||||
return rws::SIZE_GET_TEMPERATURE_REPLY;
|
||||
}
|
||||
case (rws::GET_TM): {
|
||||
return rws::SIZE_GET_TELEMETRY_REPLY;
|
||||
}
|
||||
case (rws::INIT_RW_CONTROLLER): {
|
||||
return rws::SIZE_INIT_RW;
|
||||
}
|
||||
default: {
|
||||
sif::error << "no reply buffer for rw command " << id << std::endl;
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#endif /* MISSION_DEVICES_DEVICEDEFINITIONS_RWHELPERS_CPP_ */
|
338
mission/acs/rwHelpers.h
Normal file
338
mission/acs/rwHelpers.h
Normal file
@ -0,0 +1,338 @@
|
||||
#ifndef MISSION_DEVICES_DEVICEDEFINITIONS_RWHELPERS_H_
|
||||
#define MISSION_DEVICES_DEVICEDEFINITIONS_RWHELPERS_H_
|
||||
|
||||
#include <fsfw/datapoollocal/LocalPoolVariable.h>
|
||||
#include <fsfw/datapoollocal/StaticLocalDataSet.h>
|
||||
#include <fsfw/devicehandlers/DeviceHandlerIF.h>
|
||||
|
||||
#include "eive/resultClassIds.h"
|
||||
#include "events/subsystemIdRanges.h"
|
||||
#include "objects/systemObjectList.h"
|
||||
|
||||
namespace rws {
|
||||
|
||||
void encodeHdlc(const uint8_t* sourceBuf, size_t sourceLen, uint8_t* encodedBuffer,
|
||||
size_t& encodedLen);
|
||||
size_t idToPacketLen(DeviceCommandId_t id);
|
||||
|
||||
static const size_t SIZE_GET_RESET_STATUS = 5;
|
||||
static const size_t SIZE_CLEAR_RESET_STATUS = 4;
|
||||
static const size_t SIZE_INIT_RW = 4;
|
||||
static const size_t SIZE_GET_RW_STATUS = 14;
|
||||
static const size_t SIZE_SET_SPEED_REPLY = 4;
|
||||
static const size_t SIZE_GET_TEMPERATURE_REPLY = 8;
|
||||
/** Max size when requesting telemetry */
|
||||
static const size_t SIZE_GET_TELEMETRY_REPLY = 91;
|
||||
|
||||
//! This is the end and start marker of the frame datalinklayer. Also called frame delimiter
|
||||
//! in the NanoAvionics datasheet.
|
||||
static constexpr uint8_t FRAME_DELIMITER = 0x7E;
|
||||
|
||||
enum class SpecialRwRequest : uint8_t {
|
||||
REQUEST_NONE = 0,
|
||||
RESET_MCU = 1,
|
||||
INIT_RW_CONTROLLER = 2,
|
||||
GET_TM = 3,
|
||||
NUM_REQUESTS
|
||||
};
|
||||
|
||||
static const uint8_t INTERFACE_ID = CLASS_ID::RW_HANDLER;
|
||||
|
||||
static const ReturnValue_t SPI_WRITE_FAILURE = MAKE_RETURN_CODE(0xB0);
|
||||
//! [EXPORT] : [COMMENT] Used by the spi send function to tell a failing read call
|
||||
static const ReturnValue_t SPI_READ_FAILURE = MAKE_RETURN_CODE(0xB1);
|
||||
//! [EXPORT] : [COMMENT] Can be used by the HDLC decoding mechanism to inform about a missing
|
||||
//! start sign 0x7E
|
||||
static const ReturnValue_t MISSING_START_SIGN = MAKE_RETURN_CODE(0xB2);
|
||||
//! [EXPORT] : [COMMENT] Can be used by the HDLC decoding mechanism to inform about an invalid
|
||||
//! substitution combination
|
||||
static const ReturnValue_t INVALID_SUBSTITUTE = MAKE_RETURN_CODE(0xB3);
|
||||
//! [EXPORT] : [COMMENT] HDLC decoding mechanism never receives the end sign 0x7E
|
||||
static const ReturnValue_t MISSING_END_SIGN = MAKE_RETURN_CODE(0xB4);
|
||||
//! [EXPORT] : [COMMENT] Reaction wheel only responds with empty frames.
|
||||
static const ReturnValue_t NO_REPLY = MAKE_RETURN_CODE(0xB5);
|
||||
//! [EXPORT] : [COMMENT] Expected a start marker as first byte
|
||||
static const ReturnValue_t NO_START_MARKER = MAKE_RETURN_CODE(0xB6);
|
||||
//! [EXPORT] : [COMMENT] Timeout when reading reply
|
||||
static const ReturnValue_t SPI_READ_TIMEOUT = MAKE_RETURN_CODE(0xB7);
|
||||
|
||||
static constexpr uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::RW_HANDLER;
|
||||
|
||||
//! [EXPORT] : [COMMENT] Reaction wheel signals an error state
|
||||
static constexpr Event ERROR_STATE = MAKE_EVENT(1, severity::HIGH);
|
||||
|
||||
static constexpr Event RESET_OCCURED = event::makeEvent(SUBSYSTEM_ID, 2, severity::LOW);
|
||||
|
||||
//! Minimal delay as specified by the datasheet.
|
||||
static const uint32_t SPI_REPLY_DELAY = 20000; // us
|
||||
|
||||
enum PoolIds : lp_id_t {
|
||||
TEMPERATURE_C,
|
||||
CURR_SPEED,
|
||||
REFERENCE_SPEED,
|
||||
STATE,
|
||||
CLC_MODE,
|
||||
LAST_RESET_STATUS,
|
||||
CURRRENT_RESET_STATUS,
|
||||
TM_LAST_RESET_STATUS,
|
||||
TM_MCU_TEMPERATURE,
|
||||
PRESSURE_SENSOR_TEMPERATURE,
|
||||
PRESSURE,
|
||||
TM_RW_STATE,
|
||||
TM_CLC_MODE,
|
||||
TM_RW_CURR_SPEED,
|
||||
TM_RW_REF_SPEED,
|
||||
INVALID_CRC_PACKETS,
|
||||
INVALID_LEN_PACKETS,
|
||||
INVALID_CMD_PACKETS,
|
||||
EXECUTED_REPLIES,
|
||||
COMMAND_REPLIES,
|
||||
UART_BYTES_WRITTEN,
|
||||
UART_BYTES_READ,
|
||||
UART_PARITY_ERRORS,
|
||||
UART_NOISE_ERRORS,
|
||||
UART_FRAME_ERRORS,
|
||||
UART_REG_OVERRUN_ERRORS,
|
||||
UART_TOTAL_ERRORS,
|
||||
TOTAL_ERRORS,
|
||||
SPI_BYTES_WRITTEN,
|
||||
SPI_BYTES_READ,
|
||||
SPI_REG_OVERRUN_ERRORS,
|
||||
SPI_TOTAL_ERRORS,
|
||||
|
||||
RW_SPEED,
|
||||
RAMP_TIME,
|
||||
};
|
||||
|
||||
enum States : uint8_t { STATE_ERROR, IDLE, COASTING, RUNNING_SPEED_STABLE, RUNNING_SPEED_CHANGING };
|
||||
|
||||
enum LastResetStatusBitPos : uint8_t {
|
||||
PIN_RESET = 0,
|
||||
POR_PDR_BOR_RESET = 1,
|
||||
SOFTWARE_RESET = 2,
|
||||
INDEPENDENT_WATCHDOG_RESET = 3,
|
||||
WINDOW_WATCHDOG_RESET = 4,
|
||||
LOW_POWER_RESET = 5
|
||||
};
|
||||
|
||||
enum DeviceCommandId : DeviceCommandId_t {
|
||||
RESET_MCU = 1,
|
||||
|
||||
GET_LAST_RESET_STATUS = 2,
|
||||
CLEAR_LAST_RESET_STATUS = 3,
|
||||
GET_RW_STATUS = 4,
|
||||
INIT_RW_CONTROLLER = 5,
|
||||
SET_SPEED = 6,
|
||||
GET_TEMPERATURE = 8,
|
||||
GET_TM = 9
|
||||
};
|
||||
|
||||
static constexpr DeviceCommandId_t REQUEST_ID = 0x77;
|
||||
static constexpr DeviceCommandId_t REPLY_ID = 0x78;
|
||||
|
||||
enum SetIds : uint32_t {
|
||||
TEMPERATURE_SET_ID = DeviceCommandId::GET_TEMPERATURE,
|
||||
STATUS_SET_ID = DeviceCommandId::GET_RW_STATUS,
|
||||
LAST_RESET_ID = DeviceCommandId::GET_LAST_RESET_STATUS,
|
||||
TM_SET_ID = DeviceCommandId::GET_TM,
|
||||
SPEED_CMD_SET = 10,
|
||||
};
|
||||
|
||||
/** Set speed command has maximum size */
|
||||
static const size_t MAX_CMD_SIZE = 9;
|
||||
/**
|
||||
* Max reply is reached when each byte is replaced by its substitude which should normally never
|
||||
* happen.
|
||||
*/
|
||||
static const size_t MAX_REPLY_SIZE = 2 * SIZE_GET_TELEMETRY_REPLY;
|
||||
|
||||
static const uint8_t LAST_RESET_ENTRIES = 2;
|
||||
static const uint8_t STATUS_SET_ENTRIES = 5;
|
||||
static const uint8_t TM_SET_ENTRIES = 24;
|
||||
|
||||
/**
|
||||
* @brief This dataset can be used to store the data periodically polled from the RW
|
||||
*/
|
||||
class StatusSet : public StaticLocalDataSet<STATUS_SET_ENTRIES> {
|
||||
public:
|
||||
StatusSet(HasLocalDataPoolIF* owner) : StaticLocalDataSet(owner, rws::SetIds::STATUS_SET_ID) {}
|
||||
|
||||
StatusSet(object_id_t objectId)
|
||||
: StaticLocalDataSet(sid_t(objectId, rws::SetIds::STATUS_SET_ID)) {}
|
||||
|
||||
lp_var_t<int32_t> temperatureCelcius =
|
||||
lp_var_t<int32_t>(sid.objectId, PoolIds::TEMPERATURE_C, this);
|
||||
lp_var_t<int32_t> currSpeed = lp_var_t<int32_t>(sid.objectId, PoolIds::CURR_SPEED, this);
|
||||
lp_var_t<int32_t> referenceSpeed =
|
||||
lp_var_t<int32_t>(sid.objectId, PoolIds::REFERENCE_SPEED, this);
|
||||
lp_var_t<uint8_t> state = lp_var_t<uint8_t>(sid.objectId, PoolIds::STATE, this);
|
||||
lp_var_t<uint8_t> clcMode = lp_var_t<uint8_t>(sid.objectId, PoolIds::CLC_MODE, this);
|
||||
};
|
||||
|
||||
/**
|
||||
* @brief This dataset stores the last reset status.
|
||||
*/
|
||||
class LastResetSatus : public StaticLocalDataSet<LAST_RESET_ENTRIES> {
|
||||
public:
|
||||
LastResetSatus(HasLocalDataPoolIF* owner)
|
||||
: StaticLocalDataSet(owner, rws::SetIds::LAST_RESET_ID) {}
|
||||
|
||||
LastResetSatus(object_id_t objectId)
|
||||
: StaticLocalDataSet(sid_t(objectId, rws::SetIds::LAST_RESET_ID)) {}
|
||||
|
||||
// If a reset occurs, the status code will be cached into this variable
|
||||
lp_var_t<uint8_t> lastNonClearedResetStatus =
|
||||
lp_var_t<uint8_t>(sid.objectId, PoolIds::LAST_RESET_STATUS, this);
|
||||
// This will always contain the last polled reset status
|
||||
lp_var_t<uint8_t> currentResetStatus =
|
||||
lp_var_t<uint8_t>(sid.objectId, PoolIds::CURRRENT_RESET_STATUS, this);
|
||||
};
|
||||
|
||||
/**
|
||||
* @brief This dataset stores telemetry data as specified in the datasheet of the nano avionics
|
||||
* reaction wheels. https://eive-cloud.irs.uni-stuttgart.de/index.php/apps/files/?dir=/
|
||||
* EIVE_IRS/Arbeitsdaten/08_Used%20Components/Nanoavionics_Reactionwheels&fileid=181622
|
||||
*/
|
||||
class TmDataset : public StaticLocalDataSet<TM_SET_ENTRIES> {
|
||||
public:
|
||||
TmDataset(HasLocalDataPoolIF* owner) : StaticLocalDataSet(owner, rws::SetIds::TM_SET_ID) {}
|
||||
|
||||
TmDataset(object_id_t objectId) : StaticLocalDataSet(sid_t(objectId, rws::SetIds::TM_SET_ID)) {}
|
||||
|
||||
lp_var_t<uint8_t> lastResetStatus =
|
||||
lp_var_t<uint8_t>(sid.objectId, PoolIds::TM_LAST_RESET_STATUS, this);
|
||||
lp_var_t<int32_t> mcuTemperature =
|
||||
lp_var_t<int32_t>(sid.objectId, PoolIds::TM_MCU_TEMPERATURE, this);
|
||||
lp_var_t<float> pressureSensorTemperature =
|
||||
lp_var_t<float>(sid.objectId, PoolIds::PRESSURE_SENSOR_TEMPERATURE, this);
|
||||
lp_var_t<float> pressure = lp_var_t<float>(sid.objectId, PoolIds::PRESSURE, this);
|
||||
lp_var_t<uint8_t> rwState = lp_var_t<uint8_t>(sid.objectId, PoolIds::TM_RW_STATE, this);
|
||||
lp_var_t<uint8_t> rwClcMode = lp_var_t<uint8_t>(sid.objectId, PoolIds::TM_CLC_MODE, this);
|
||||
lp_var_t<int32_t> rwCurrSpeed = lp_var_t<int32_t>(sid.objectId, PoolIds::TM_RW_CURR_SPEED, this);
|
||||
lp_var_t<int32_t> rwRefSpeed = lp_var_t<int32_t>(sid.objectId, PoolIds::TM_RW_REF_SPEED, this);
|
||||
lp_var_t<uint32_t> numOfInvalidCrcPackets =
|
||||
lp_var_t<uint32_t>(sid.objectId, PoolIds::INVALID_CRC_PACKETS, this);
|
||||
lp_var_t<uint32_t> numOfInvalidLenPackets =
|
||||
lp_var_t<uint32_t>(sid.objectId, PoolIds::INVALID_LEN_PACKETS, this);
|
||||
lp_var_t<uint32_t> numOfInvalidCmdPackets =
|
||||
lp_var_t<uint32_t>(sid.objectId, PoolIds::INVALID_CMD_PACKETS, this);
|
||||
lp_var_t<uint32_t> numOfCmdExecutedReplies =
|
||||
lp_var_t<uint32_t>(sid.objectId, PoolIds::EXECUTED_REPLIES, this);
|
||||
lp_var_t<uint32_t> numOfCmdReplies =
|
||||
lp_var_t<uint32_t>(sid.objectId, PoolIds::COMMAND_REPLIES, this);
|
||||
lp_var_t<uint32_t> uartNumOfBytesWritten =
|
||||
lp_var_t<uint32_t>(sid.objectId, PoolIds::UART_BYTES_WRITTEN, this);
|
||||
lp_var_t<uint32_t> uartNumOfBytesRead =
|
||||
lp_var_t<uint32_t>(sid.objectId, PoolIds::UART_BYTES_READ, this);
|
||||
lp_var_t<uint32_t> uartNumOfParityErrors =
|
||||
lp_var_t<uint32_t>(sid.objectId, PoolIds::UART_PARITY_ERRORS, this);
|
||||
lp_var_t<uint32_t> uartNumOfNoiseErrors =
|
||||
lp_var_t<uint32_t>(sid.objectId, PoolIds::UART_NOISE_ERRORS, this);
|
||||
lp_var_t<uint32_t> uartNumOfFrameErrors =
|
||||
lp_var_t<uint32_t>(sid.objectId, PoolIds::UART_FRAME_ERRORS, this);
|
||||
lp_var_t<uint32_t> uartNumOfRegisterOverrunErrors =
|
||||
lp_var_t<uint32_t>(sid.objectId, PoolIds::UART_REG_OVERRUN_ERRORS, this);
|
||||
lp_var_t<uint32_t> uartTotalNumOfErrors =
|
||||
lp_var_t<uint32_t>(sid.objectId, PoolIds::UART_TOTAL_ERRORS, this);
|
||||
lp_var_t<uint32_t> spiNumOfBytesWritten =
|
||||
lp_var_t<uint32_t>(sid.objectId, PoolIds::SPI_BYTES_WRITTEN, this);
|
||||
lp_var_t<uint32_t> spiNumOfBytesRead =
|
||||
lp_var_t<uint32_t>(sid.objectId, PoolIds::SPI_BYTES_READ, this);
|
||||
lp_var_t<uint32_t> spiNumOfRegisterOverrunErrors =
|
||||
lp_var_t<uint32_t>(sid.objectId, PoolIds::SPI_REG_OVERRUN_ERRORS, this);
|
||||
lp_var_t<uint32_t> spiTotalNumOfErrors =
|
||||
lp_var_t<uint32_t>(sid.objectId, PoolIds::SPI_TOTAL_ERRORS, this);
|
||||
};
|
||||
|
||||
class RwSpeedActuationSet : public StaticLocalDataSet<2> {
|
||||
friend class RwHandler;
|
||||
|
||||
public:
|
||||
RwSpeedActuationSet(HasLocalDataPoolIF& owner)
|
||||
: StaticLocalDataSet(&owner, rws::SetIds::SPEED_CMD_SET) {}
|
||||
RwSpeedActuationSet(object_id_t objectId)
|
||||
: StaticLocalDataSet(sid_t(objectId, rws::SetIds::SPEED_CMD_SET)) {}
|
||||
|
||||
void setRwSpeed(int32_t rwSpeed_, uint16_t rampTime_) {
|
||||
if (rwSpeed.value != rwSpeed_) {
|
||||
rwSpeed = rwSpeed_;
|
||||
}
|
||||
if (rampTime.value != rampTime_) {
|
||||
rampTime = rampTime_;
|
||||
}
|
||||
}
|
||||
|
||||
void getRwSpeed(int32_t& rwSpeed_, uint16_t& rampTime_) {
|
||||
rwSpeed_ = rwSpeed.value;
|
||||
rampTime_ = rampTime.value;
|
||||
}
|
||||
|
||||
private:
|
||||
lp_var_t<int32_t> rwSpeed = lp_var_t<int32_t>(sid.objectId, rws::PoolIds::RW_SPEED, this);
|
||||
lp_var_t<uint16_t> rampTime = lp_var_t<uint16_t>(sid.objectId, rws::PoolIds::RAMP_TIME, this);
|
||||
};
|
||||
|
||||
} // namespace rws
|
||||
|
||||
/**
|
||||
* Raw pointer overlay to hold the different frames received from the reaction
|
||||
* wheel in a raw buffer and send them to the device handler.
|
||||
*/
|
||||
struct RwReplies {
|
||||
friend class RwPollingTask;
|
||||
|
||||
public:
|
||||
RwReplies(const uint8_t* rawData) : rawData(const_cast<uint8_t*>(rawData)) { initPointers(); }
|
||||
|
||||
const uint8_t* getClearLastResetStatusReply() const { return clearLastResetStatusReply + 1; }
|
||||
bool wasClearLastRsetStatusReplyRead() const { return clearLastResetStatusReply[0]; }
|
||||
|
||||
const uint8_t* getGetLastResetStatusReply() const { return getLastResetStatusReply + 1; }
|
||||
bool wasGetLastStatusReplyRead() const { return getLastResetStatusReply[0]; }
|
||||
|
||||
const uint8_t* getHkDataReply() const { return hkDataReply + 1; }
|
||||
bool wasHkDataReplyRead() const { return hkDataReply[0]; }
|
||||
|
||||
const uint8_t* getInitRwControllerReply() const { return initRwControllerReply + 1; }
|
||||
bool wasInitRwControllerReplyRead() const { return initRwControllerReply[0]; }
|
||||
|
||||
const uint8_t* getRawData() const { return rawData; }
|
||||
|
||||
const uint8_t* getReadTemperatureReply() const { return readTemperatureReply + 1; }
|
||||
bool wasReadTemperatureReplySet() const { return readTemperatureReply[0]; }
|
||||
|
||||
const uint8_t* getRwStatusReply() const { return rwStatusReply + 1; }
|
||||
bool wasRwStatusRead() const { return rwStatusReply[0]; }
|
||||
|
||||
const uint8_t* getSetSpeedReply() const { return setSpeedReply + 1; }
|
||||
bool wasSetSpeedReplyRead() const { return setSpeedReply[0]; }
|
||||
|
||||
private:
|
||||
RwReplies(uint8_t* rwData) : rawData(rwData) { initPointers(); }
|
||||
|
||||
/**
|
||||
* The first byte of the reply buffers contains a flag which shows whether that
|
||||
* frame was read from the reaction wheel at least once.
|
||||
*/
|
||||
void initPointers() {
|
||||
rwStatusReply = rawData;
|
||||
setSpeedReply = rawData + rws::SIZE_GET_RW_STATUS + 1;
|
||||
getLastResetStatusReply = setSpeedReply + rws::SIZE_SET_SPEED_REPLY + 1;
|
||||
clearLastResetStatusReply = getLastResetStatusReply + rws::SIZE_GET_RESET_STATUS + 1;
|
||||
readTemperatureReply = clearLastResetStatusReply + rws::SIZE_CLEAR_RESET_STATUS + 1;
|
||||
hkDataReply = readTemperatureReply + rws::SIZE_GET_TEMPERATURE_REPLY + 1;
|
||||
initRwControllerReply = hkDataReply + rws::SIZE_GET_TELEMETRY_REPLY + 1;
|
||||
dummyPointer = initRwControllerReply + rws::SIZE_INIT_RW + 1;
|
||||
}
|
||||
uint8_t* rawData;
|
||||
uint8_t* rwStatusReply;
|
||||
uint8_t* setSpeedReply;
|
||||
uint8_t* getLastResetStatusReply;
|
||||
uint8_t* clearLastResetStatusReply;
|
||||
uint8_t* readTemperatureReply;
|
||||
uint8_t* hkDataReply;
|
||||
uint8_t* initRwControllerReply;
|
||||
uint8_t* dummyPointer;
|
||||
};
|
||||
|
||||
#endif /* MISSION_DEVICES_DEVICEDEFINITIONS_RWHELPERS_H_ */
|
73
mission/acs/str/ArcsecDatalinkLayer.cpp
Normal file
73
mission/acs/str/ArcsecDatalinkLayer.cpp
Normal file
@ -0,0 +1,73 @@
|
||||
#include <mission/acs/str/ArcsecDatalinkLayer.h>
|
||||
|
||||
ArcsecDatalinkLayer::ArcsecDatalinkLayer() : decodeRingBuf(BUFFER_LENGTHS, true) { slipInit(); }
|
||||
|
||||
ArcsecDatalinkLayer::~ArcsecDatalinkLayer() {}
|
||||
|
||||
ReturnValue_t ArcsecDatalinkLayer::checkRingBufForFrame(const uint8_t** decodedFrame,
|
||||
size_t& frameLen) {
|
||||
size_t currentLen = decodeRingBuf.getAvailableReadData();
|
||||
if (currentLen == 0) {
|
||||
return DEC_IN_PROGRESS;
|
||||
}
|
||||
decodeRingBuf.readData(rxAnalysisBuffer, currentLen);
|
||||
for (size_t idx = 0; idx < currentLen; idx++) {
|
||||
enum arc_dec_result decResult =
|
||||
arc_transport_decode_body(rxAnalysisBuffer[idx], &slipInfo, decodedRxFrame, &rxFrameSize);
|
||||
switch (decResult) {
|
||||
case ARC_DEC_INPROGRESS: {
|
||||
break;
|
||||
}
|
||||
case ARC_DEC_ERROR_FRAME_SHORT: {
|
||||
decodeRingBuf.deleteData(idx);
|
||||
return REPLY_TOO_SHORT;
|
||||
}
|
||||
case ARC_DEC_ERROR_CHECKSUM:
|
||||
decodeRingBuf.deleteData(idx);
|
||||
return CRC_FAILURE;
|
||||
case ARC_DEC_ASYNC:
|
||||
case ARC_DEC_SYNC: {
|
||||
// Reset length of SLIP struct for next frame
|
||||
slipInfo.length = 0;
|
||||
if (decodedFrame != nullptr) {
|
||||
*decodedFrame = decodedRxFrame;
|
||||
}
|
||||
frameLen = rxFrameSize;
|
||||
decodeRingBuf.deleteData(idx);
|
||||
return returnvalue::OK;
|
||||
}
|
||||
default:
|
||||
sif::debug << "ArcsecDatalinkLayer::decodeFrame: Unknown result code" << std::endl;
|
||||
break;
|
||||
return returnvalue::FAILED;
|
||||
}
|
||||
}
|
||||
decodeRingBuf.deleteData(currentLen);
|
||||
return DEC_IN_PROGRESS;
|
||||
}
|
||||
|
||||
ReturnValue_t ArcsecDatalinkLayer::feedData(const uint8_t* rawData, size_t rawDataLen) {
|
||||
if (rawDataLen > 4096) {
|
||||
sif::error << "ArcsecDatalinklayer: Can not write more than 4096 bytes to ring buffer"
|
||||
<< std::endl;
|
||||
return returnvalue::FAILED;
|
||||
}
|
||||
return decodeRingBuf.writeData(rawData, rawDataLen);
|
||||
}
|
||||
|
||||
void ArcsecDatalinkLayer::reset() {
|
||||
slipInit();
|
||||
decodeRingBuf.clear();
|
||||
}
|
||||
|
||||
void ArcsecDatalinkLayer::slipInit() {
|
||||
slip_decode_init(rxBufferArc, sizeof(rxBufferArc), &slipInfo);
|
||||
}
|
||||
|
||||
void ArcsecDatalinkLayer::encodeFrame(const uint8_t* data, size_t length, const uint8_t** txFrame,
|
||||
size_t& size) {
|
||||
arc_transport_encode_body(data, length, txEncoded, &size);
|
||||
if (txFrame != nullptr) {
|
||||
*txFrame = txEncoded;
|
||||
}
|
||||
}
|
90
mission/acs/str/ArcsecDatalinkLayer.h
Normal file
90
mission/acs/str/ArcsecDatalinkLayer.h
Normal file
@ -0,0 +1,90 @@
|
||||
#ifndef BSP_Q7S_DEVICES_ARCSECDATALINKLAYER_H_
|
||||
#define BSP_Q7S_DEVICES_ARCSECDATALINKLAYER_H_
|
||||
|
||||
#include <fsfw/container/SimpleRingBuffer.h>
|
||||
#include <fsfw/devicehandlers/CookieIF.h>
|
||||
#include <mission/acs/str/strHelpers.h>
|
||||
|
||||
#include "arcsec/common/misc.h"
|
||||
#include "eive/resultClassIds.h"
|
||||
#include "fsfw/returnvalues/returnvalue.h"
|
||||
|
||||
/**
|
||||
* @brief Helper class to handle the datalinklayer of replies from the star tracker of arcsec.
|
||||
*/
|
||||
class ArcsecDatalinkLayer {
|
||||
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;
|
||||
|
||||
static constexpr size_t BUFFER_LENGTHS = 4096;
|
||||
|
||||
ArcsecDatalinkLayer();
|
||||
virtual ~ArcsecDatalinkLayer();
|
||||
|
||||
/**
|
||||
* Feed received data to the internal ring buffer.
|
||||
* @param rawData
|
||||
* @param rawDataLen
|
||||
* @return
|
||||
*/
|
||||
ReturnValue_t feedData(const uint8_t* rawData, size_t rawDataLen);
|
||||
|
||||
/**
|
||||
* Runs the arcsec datalink layer decoding algorithm on the data in the ring buffer, decoding
|
||||
* frames in the process.
|
||||
* @param decodedFrame
|
||||
* @param frameLen
|
||||
* @return
|
||||
* - returnvalue::OK if a frame was found
|
||||
* - DEC_IN_PROGRESS if frame decoding is in progress
|
||||
* - Anything else is a decoding error
|
||||
*/
|
||||
ReturnValue_t checkRingBufForFrame(const uint8_t** decodedFrame, size_t& frameLen);
|
||||
|
||||
/**
|
||||
* @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, size_t length, const uint8_t** txFrame, size_t& frameLen);
|
||||
|
||||
void reset();
|
||||
|
||||
private:
|
||||
static const uint8_t ID_OFFSET = 1;
|
||||
static const uint8_t STATUS_OFFSET = 2;
|
||||
|
||||
// User to buffer and analyse data and allow feeding and checking for frames asychronously.
|
||||
SimpleRingBuffer decodeRingBuf;
|
||||
uint8_t rxAnalysisBuffer[BUFFER_LENGTHS];
|
||||
|
||||
// Used by arcsec slip decoding function to process received data. This should only be written
|
||||
// to or read from by arcsec functions!
|
||||
uint8_t rxBufferArc[startracker::MAX_FRAME_SIZE];
|
||||
// Decoded frame will be copied to this buffer
|
||||
uint8_t decodedRxFrame[startracker::MAX_FRAME_SIZE];
|
||||
// Size of decoded frame
|
||||
uint32_t rxFrameSize = 0;
|
||||
|
||||
// Buffer where encoded frames will be stored. First byte of encoded frame represents type of
|
||||
// reply
|
||||
uint8_t txEncoded[startracker::MAX_FRAME_SIZE * 2 + 2];
|
||||
// Size of encoded frame
|
||||
uint32_t txFrameSize = 0;
|
||||
|
||||
slip_decode_state slipInfo;
|
||||
|
||||
void slipInit();
|
||||
};
|
||||
|
||||
#endif /* BSP_Q7S_DEVICES_ARCSECDATALINKLAYER_H_ */
|
102
mission/acs/str/ArcsecJsonParamBase.cpp
Normal file
102
mission/acs/str/ArcsecJsonParamBase.cpp
Normal file
@ -0,0 +1,102 @@
|
||||
#include <mission/acs/str/ArcsecJsonParamBase.h>
|
||||
#include <mission/acs/str/arcsecJsonKeys.h>
|
||||
|
||||
#include "arcsecJsonKeys.h"
|
||||
|
||||
ArcsecJsonParamBase::ArcsecJsonParamBase(std::string setName) : setName(setName) {}
|
||||
|
||||
ReturnValue_t ArcsecJsonParamBase::create(uint8_t* buffer) {
|
||||
ReturnValue_t result = createCommand(buffer);
|
||||
if (result != returnvalue::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 returnvalue::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, ¶m, sizeof(param));
|
||||
}
|
||||
|
||||
void ArcsecJsonParamBase::adduint8(const std::string value, uint8_t* buffer) {
|
||||
uint8_t param = std::stoi(value);
|
||||
std::memcpy(buffer, ¶m, sizeof(param));
|
||||
}
|
||||
|
||||
void ArcsecJsonParamBase::addint16(const std::string value, uint8_t* buffer) {
|
||||
int16_t param = std::stoi(value);
|
||||
std::memcpy(buffer, ¶m, sizeof(param));
|
||||
}
|
||||
|
||||
void ArcsecJsonParamBase::adduint16(const std::string value, uint8_t* buffer) {
|
||||
uint16_t param = std::stoi(value);
|
||||
std::memcpy(buffer, ¶m, sizeof(param));
|
||||
}
|
||||
|
||||
void ArcsecJsonParamBase::adduint32(const std::string value, uint8_t* buffer) {
|
||||
uint32_t param = std::stoi(value);
|
||||
std::memcpy(buffer, ¶m, 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 = returnvalue::OK;
|
||||
if (not std::filesystem::exists(filename)) {
|
||||
sif::warning << "ArcsecJsonParamBase::init: JSON file " << filename << " does not exist"
|
||||
<< std::endl;
|
||||
return JSON_FILE_NOT_EXISTS;
|
||||
}
|
||||
try {
|
||||
createJsonObject(filename);
|
||||
result = initSet();
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
return returnvalue::OK;
|
||||
} catch (json::exception& e) {
|
||||
// TODO: Re-create json file from backup here.
|
||||
return returnvalue::FAILED;
|
||||
}
|
||||
}
|
||||
|
||||
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 returnvalue::OK;
|
||||
}
|
||||
}
|
||||
sif::warning << "ArcsecJsonParamBase::initSet: Set " << setName << "not present in json file"
|
||||
<< std::endl;
|
||||
return SET_NOT_EXISTS;
|
||||
}
|
146
mission/acs/str/ArcsecJsonParamBase.h
Normal file
146
mission/acs/str/ArcsecJsonParamBase.h
Normal file
@ -0,0 +1,146 @@
|
||||
#ifndef BSP_Q7S_DEVICES_STARTRACKER_ARCSECJSONPARAMBASE_H_
|
||||
#define BSP_Q7S_DEVICES_STARTRACKER_ARCSECJSONPARAMBASE_H_
|
||||
|
||||
#include <mission/acs/str/strHelpers.h>
|
||||
|
||||
#include <filesystem>
|
||||
#include <fstream>
|
||||
#include <nlohmann/json.hpp>
|
||||
|
||||
#include "arcsec/common/generated/tmtcstructs.h"
|
||||
#include "arcsec/common/genericstructs.h"
|
||||
#include "eive/resultClassIds.h"
|
||||
#include "fsfw/returnvalues/returnvalue.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:
|
||||
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);
|
||||
|
||||
virtual ~ArcsecJsonParamBase() = default;
|
||||
/**
|
||||
* @brief Constructor
|
||||
*
|
||||
* @param fullname Name with absolute path of json file containing the parameters to set.
|
||||
*/
|
||||
ArcsecJsonParamBase(std::string setName);
|
||||
|
||||
/**
|
||||
* @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
|
||||
* returnvalue::OK
|
||||
*/
|
||||
ReturnValue_t init(const std::string filename);
|
||||
|
||||
/**
|
||||
* @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(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 returnvalue::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;
|
||||
|
||||
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_ */
|
4
mission/acs/str/CMakeLists.txt
Normal file
4
mission/acs/str/CMakeLists.txt
Normal file
@ -0,0 +1,4 @@
|
||||
target_sources(
|
||||
${OBSW_NAME}
|
||||
PRIVATE StarTrackerHandler.cpp strJsonCommands.cpp ArcsecDatalinkLayer.cpp
|
||||
ArcsecJsonParamBase.cpp strHelpers.cpp)
|
2136
mission/acs/str/StarTrackerHandler.cpp
Normal file
2136
mission/acs/str/StarTrackerHandler.cpp
Normal file
File diff suppressed because it is too large
Load Diff
501
mission/acs/str/StarTrackerHandler.h
Normal file
501
mission/acs/str/StarTrackerHandler.h
Normal file
@ -0,0 +1,501 @@
|
||||
#ifndef MISSION_DEVICES_STARTRACKERHANDLER_H_
|
||||
#define MISSION_DEVICES_STARTRACKERHANDLER_H_
|
||||
|
||||
#include <fsfw/datapool/PoolReadGuard.h>
|
||||
#include <linux/acs/StrComHandler.h>
|
||||
#include <mission/acs/str/ArcsecJsonParamBase.h>
|
||||
#include <mission/acs/str/strHelpers.h>
|
||||
#include <mission/acs/str/strJsonCommands.h>
|
||||
|
||||
#include <thread>
|
||||
|
||||
#include "OBSWConfig.h"
|
||||
#include "arcsec/common/SLIP.h"
|
||||
#include "devices/powerSwitcherList.h"
|
||||
#include "fsfw/devicehandlers/DeviceHandlerBase.h"
|
||||
#include "fsfw/src/fsfw/serialize/SerializeAdapter.h"
|
||||
#include "fsfw/timemanager/Countdown.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,
|
||||
const char* jsonFileStr, StrComHandler* strHelper,
|
||||
power::Switch_t powerSwitch);
|
||||
virtual ~StarTrackerHandler();
|
||||
|
||||
ReturnValue_t initialize() override;
|
||||
|
||||
/**
|
||||
* @brief Overwrite this function from DHB to handle commands executed by the str image
|
||||
* loader task.
|
||||
*/
|
||||
ReturnValue_t executeAction(ActionId_t actionId, MessageQueueId_t commandedBy,
|
||||
const uint8_t* data, size_t size) override;
|
||||
|
||||
void performOperationHook() override;
|
||||
|
||||
Submode_t getInitialSubmode() override;
|
||||
|
||||
static const Submode_t SUBMODE_BOOTLOADER = 1;
|
||||
static const Submode_t SUBMODE_FIRMWARE = 2;
|
||||
|
||||
protected:
|
||||
void doStartUp() override;
|
||||
void doShutDown() override;
|
||||
ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t* id) override;
|
||||
ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t* id) override;
|
||||
void fillCommandAndReplyMap() override;
|
||||
ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, const uint8_t* commandData,
|
||||
size_t commandDataLen) override;
|
||||
ReturnValue_t isModeCombinationValid(Mode_t mode, Submode_t submode) override;
|
||||
ReturnValue_t scanForReply(const uint8_t* start, size_t remainingSize, DeviceCommandId_t* foundId,
|
||||
size_t* foundLen) override;
|
||||
ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t* packet) override;
|
||||
void setNormalDatapoolEntriesInvalid() override;
|
||||
uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override;
|
||||
ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap,
|
||||
LocalDataPoolManager& poolManager) override;
|
||||
/**
|
||||
* @brief Overwritten here to always read all available data from theSerialComIF.
|
||||
*/
|
||||
virtual size_t getNextReplyLength(DeviceCommandId_t deviceCommand) override;
|
||||
virtual ReturnValue_t doSendReadHook() override;
|
||||
ReturnValue_t getSwitches(const uint8_t** switches, uint8_t* numberOfSwitches) override;
|
||||
virtual void doTransition(Mode_t modeFrom, Submode_t subModeFrom) override;
|
||||
|
||||
private:
|
||||
static const uint8_t INTERFACE_ID = CLASS_ID::STR_HANDLER;
|
||||
|
||||
//! [EXPORT] : [COMMENT] Status in temperature reply signals error
|
||||
static const ReturnValue_t TEMPERATURE_REQ_FAILED = MAKE_RETURN_CODE(0xA0);
|
||||
//! [EXPORT] : [COMMENT] Ping command failed
|
||||
static const ReturnValue_t PING_FAILED = MAKE_RETURN_CODE(0xA1);
|
||||
//! [EXPORT] : [COMMENT] Status in version reply signals error
|
||||
static const ReturnValue_t VERSION_REQ_FAILED = MAKE_RETURN_CODE(0xA2);
|
||||
//! [EXPORT] : [COMMENT] Status in interface reply signals error
|
||||
static const ReturnValue_t INTERFACE_REQ_FAILED = MAKE_RETURN_CODE(0xA3);
|
||||
//! [EXPORT] : [COMMENT] Status in power reply signals error
|
||||
static const ReturnValue_t POWER_REQ_FAILED = MAKE_RETURN_CODE(0xA4);
|
||||
//! [EXPORT] : [COMMENT] Status of reply to parameter set command signals error
|
||||
static const ReturnValue_t SET_PARAM_FAILED = MAKE_RETURN_CODE(0xA5);
|
||||
//! [EXPORT] : [COMMENT] Status of reply to action command signals error
|
||||
static const ReturnValue_t ACTION_FAILED = MAKE_RETURN_CODE(0xA6);
|
||||
//! [EXPORT] : [COMMENT] Received invalid path string. Exceeds allowed length
|
||||
static const ReturnValue_t FILE_PATH_TOO_LONG = MAKE_RETURN_CODE(0xA7);
|
||||
//! [EXPORT] : [COMMENT] Name of file received with command is too long
|
||||
static const ReturnValue_t FILENAME_TOO_LONG = MAKE_RETURN_CODE(0xA8);
|
||||
//! [EXPORT] : [COMMENT] Received version reply with invalid program ID
|
||||
static const ReturnValue_t INVALID_PROGRAM = MAKE_RETURN_CODE(0xA9);
|
||||
//! [EXPORT] : [COMMENT] Status field reply signals error
|
||||
static const ReturnValue_t REPLY_ERROR = MAKE_RETURN_CODE(0xAA);
|
||||
//! [EXPORT] : [COMMENT] Received command which is too short (some data is missing for proper
|
||||
//! execution)
|
||||
static const ReturnValue_t COMMAND_TOO_SHORT = MAKE_RETURN_CODE(0xAB);
|
||||
//! [EXPORT] : [COMMENT] Received command with invalid length (too few or too many parameters)
|
||||
static const ReturnValue_t INVALID_LENGTH = MAKE_RETURN_CODE(0xAC);
|
||||
//! [EXPORT] : [COMMENT] Region mismatch between send and received data
|
||||
static const ReturnValue_t REGION_MISMATCH = MAKE_RETURN_CODE(0xAD);
|
||||
//! [EXPORT] : [COMMENT] Address mismatch between send and received data
|
||||
static const ReturnValue_t ADDRESS_MISMATCH = MAKE_RETURN_CODE(0xAE);
|
||||
//! [EXPORT] : [COMMENT] Length field mismatch between send and received data
|
||||
static const ReturnValue_t lENGTH_MISMATCH = MAKE_RETURN_CODE(0xAF);
|
||||
//! [EXPORT] : [COMMENT] Specified file does not exist
|
||||
static const ReturnValue_t FILE_NOT_EXISTS = MAKE_RETURN_CODE(0xB0);
|
||||
//! [EXPORT] : [COMMENT] Download blob pixel command has invalid type field
|
||||
static const ReturnValue_t INVALID_TYPE = MAKE_RETURN_CODE(0xB1);
|
||||
//! [EXPORT] : [COMMENT] Received FPGA action command with invalid ID
|
||||
static const ReturnValue_t INVALID_ID = MAKE_RETURN_CODE(0xB2);
|
||||
//! [EXPORT] : [COMMENT] Received reply is too short
|
||||
static const ReturnValue_t REPLY_TOO_SHORT = MAKE_RETURN_CODE(0xB3);
|
||||
//! [EXPORT] : [COMMENT] Received reply with invalid CRC
|
||||
static const ReturnValue_t CRC_FAILURE = MAKE_RETURN_CODE(0xB4);
|
||||
//! [EXPORT] : [COMMENT] Star tracker handler currently executing a command and using the
|
||||
//! communication interface
|
||||
static const ReturnValue_t STR_HELPER_EXECUTING = MAKE_RETURN_CODE(0xB5);
|
||||
//! [EXPORT] : [COMMENT] Star tracker is already in firmware mode
|
||||
static const ReturnValue_t STARTRACKER_ALREADY_BOOTED = MAKE_RETURN_CODE(0xB6);
|
||||
//! [EXPORT] : [COMMENT] Star tracker must be in firmware mode to run this command
|
||||
static const ReturnValue_t STARTRACKER_NOT_RUNNING_FIRMWARE = MAKE_RETURN_CODE(0xB7);
|
||||
//! [EXPORT] : [COMMENT] Star tracker must be in bootloader mode to run this command
|
||||
static const ReturnValue_t STARTRACKER_NOT_RUNNING_BOOTLOADER = MAKE_RETURN_CODE(0xB8);
|
||||
|
||||
static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::STR_HANDLER;
|
||||
|
||||
//! [EXPORT] : [COMMENT] Failed to boot firmware
|
||||
static const Event BOOTING_FIRMWARE_FAILED_EVENT = MAKE_EVENT(1, severity::LOW);
|
||||
//! [EXPORT] : [COMMENT] Failed to boot star tracker into bootloader mode
|
||||
static const Event BOOTING_BOOTLOADER_FAILED_EVENT = MAKE_EVENT(2, severity::LOW);
|
||||
|
||||
static const size_t MAX_PATH_SIZE = 50;
|
||||
static const size_t MAX_FILE_NAME = 30;
|
||||
|
||||
static const uint8_t STATUS_OFFSET = 2;
|
||||
static const uint8_t PARAMS_OFFSET = 2;
|
||||
static const uint8_t TICKS_OFFSET = 3;
|
||||
static const uint8_t TIME_OFFSET = 7;
|
||||
static const uint8_t PARAMETER_ID_OFFSET = 1;
|
||||
static const uint8_t ACTION_ID_OFFSET = 1;
|
||||
static const uint8_t ACTION_DATA_OFFSET = 3;
|
||||
|
||||
// Ping request will reply ping with this ID (data field)
|
||||
static const uint32_t PING_ID = 0x55;
|
||||
static const uint32_t BOOT_REGION_ID = 1;
|
||||
static const MutexIF::TimeoutType TIMEOUT_TYPE = MutexIF::TimeoutType::WAITING;
|
||||
static const uint32_t MUTEX_TIMEOUT = 20;
|
||||
static const uint32_t BOOT_TIMEOUT = 1000;
|
||||
static const uint32_t DEFAULT_TRANSITION_DELAY = 15000;
|
||||
|
||||
struct FlashReadCmd {
|
||||
// Minimum length of a read command (region, length and filename)
|
||||
static const size_t MIN_LENGTH = 7;
|
||||
};
|
||||
|
||||
struct ChecksumCmd {
|
||||
static const uint8_t ADDRESS_OFFSET = 1;
|
||||
static const uint8_t LENGTH_OFFSET = 5;
|
||||
// Length of checksum command
|
||||
static const size_t LENGTH = 9;
|
||||
uint8_t rememberRegion = 0;
|
||||
uint32_t rememberAddress = 0;
|
||||
uint32_t rememberLength = 0;
|
||||
};
|
||||
|
||||
ChecksumCmd checksumCmd;
|
||||
|
||||
MessageQueueIF* eventQueue = nullptr;
|
||||
|
||||
startracker::TemperatureSet temperatureSet;
|
||||
startracker::VersionSet versionSet;
|
||||
startracker::PowerSet powerSet;
|
||||
startracker::InterfaceSet interfaceSet;
|
||||
startracker::TimeSet timeSet;
|
||||
startracker::SolutionSet solutionSet;
|
||||
startracker::HistogramSet histogramSet;
|
||||
startracker::ChecksumSet checksumSet;
|
||||
startracker::CameraSet cameraSet;
|
||||
startracker::LimitsSet limitsSet;
|
||||
startracker::LogLevelSet loglevelSet;
|
||||
startracker::MountingSet mountingSet;
|
||||
startracker::ImageProcessorSet imageProcessorSet;
|
||||
startracker::CentroidingSet centroidingSet;
|
||||
startracker::LisaSet lisaSet;
|
||||
startracker::MatchingSet matchingSet;
|
||||
startracker::TrackingSet trackingSet;
|
||||
startracker::ValidationSet validationSet;
|
||||
startracker::AlgoSet algoSet;
|
||||
startracker::SubscriptionSet subscriptionSet;
|
||||
startracker::LogSubscriptionSet logSubscriptionSet;
|
||||
startracker::DebugCameraSet debugCameraSet;
|
||||
|
||||
// Pointer to object responsible for uploading and downloading images to/from the star tracker
|
||||
StrComHandler* strHelper = nullptr;
|
||||
|
||||
uint8_t commandBuffer[startracker::MAX_FRAME_SIZE];
|
||||
|
||||
// Countdown to insert delay for star tracker to switch from bootloader to firmware program
|
||||
// Loading firmware requires some time and the command will not trigger a reply when executed
|
||||
Countdown bootCountdown;
|
||||
|
||||
struct JsonConfigs {
|
||||
Tracking tracking;
|
||||
LogLevel logLevel;
|
||||
LogSubscription logSubscription;
|
||||
DebugCamera debugCamera;
|
||||
Algo algo;
|
||||
Validation validation;
|
||||
Matching matching;
|
||||
Lisa lisa;
|
||||
Centroiding centroiding;
|
||||
Camera camera;
|
||||
ImageProcessor imageProcessor;
|
||||
Mounting mounting;
|
||||
Limits limits;
|
||||
Subscription subscription;
|
||||
};
|
||||
JsonConfigs jcfgs;
|
||||
Countdown jcfgCountdown = Countdown(250);
|
||||
bool commandExecuted = false;
|
||||
std::thread jsonCfgTask;
|
||||
static void setUpJsonCfgs(JsonConfigs& cfgs, const char* paramJsonFile);
|
||||
|
||||
std::string paramJsonFile;
|
||||
|
||||
enum class NormalState { TEMPERATURE_REQUEST, SOLUTION_REQUEST };
|
||||
|
||||
NormalState normalState = NormalState::TEMPERATURE_REQUEST;
|
||||
|
||||
enum class StartupState {
|
||||
IDLE,
|
||||
CHECK_PROGRAM,
|
||||
WAIT_CHECK_PROGRAM,
|
||||
BOOT_BOOTLOADER,
|
||||
WAIT_JCFG,
|
||||
DONE
|
||||
};
|
||||
StartupState startupState = StartupState::IDLE;
|
||||
|
||||
enum class InternalState {
|
||||
IDLE,
|
||||
BOOT_FIRMWARE,
|
||||
DONE,
|
||||
FAILED_FIRMWARE_BOOT,
|
||||
BOOT_BOOTLOADER,
|
||||
BOOTLOADER_CHECK,
|
||||
FAILED_BOOTLOADER_BOOT
|
||||
};
|
||||
|
||||
enum class FwBootState {
|
||||
NONE,
|
||||
BOOT_DELAY,
|
||||
REQ_VERSION,
|
||||
VERIFY_BOOT,
|
||||
LOGLEVEL,
|
||||
LIMITS,
|
||||
TRACKING,
|
||||
MOUNTING,
|
||||
IMAGE_PROCESSOR,
|
||||
CAMERA,
|
||||
BLOB,
|
||||
CENTROIDING,
|
||||
LISA,
|
||||
MATCHING,
|
||||
VALIDATION,
|
||||
ALGO,
|
||||
LOG_SUBSCRIPTION,
|
||||
DEBUG_CAMERA,
|
||||
WAIT_FOR_EXECUTION,
|
||||
};
|
||||
FwBootState bootState = FwBootState::NONE;
|
||||
|
||||
InternalState internalState = InternalState::IDLE;
|
||||
|
||||
bool reinitNextSetParam = false;
|
||||
|
||||
bool strHelperHandlingSpecialRequest = false;
|
||||
|
||||
const power::Switch_t powerSwitch = power::NO_SWITCH;
|
||||
|
||||
/**
|
||||
* @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(uint8_t replyId, DeviceCommandId_t* foundId);
|
||||
ReturnValue_t scanForSetParameterReply(uint8_t replyId, DeviceCommandId_t* foundId);
|
||||
ReturnValue_t scanForGetParameterReply(uint8_t replyId, DeviceCommandId_t* foundId);
|
||||
ReturnValue_t scanForTmReply(uint8_t replyId, DeviceCommandId_t* foundId);
|
||||
|
||||
/**
|
||||
* @brief Fills command buffer with data to ping the star tracker
|
||||
*/
|
||||
void preparePingRequest();
|
||||
|
||||
/**
|
||||
* @brief Fills command buffer with data to request the time telemetry.
|
||||
*/
|
||||
void prepareTimeRequest();
|
||||
|
||||
/**
|
||||
* @brief Handles all received event messages
|
||||
*/
|
||||
void handleEvent(EventMessage* eventMessage);
|
||||
|
||||
/**
|
||||
* @brief Extracts information for flash-read-command from TC data and starts execution of
|
||||
* flash-read-procedure
|
||||
*
|
||||
* @param commandData Pointer to received command data
|
||||
* @param commandDataLen Size of received command data
|
||||
*
|
||||
* @return returnvalue::OK if start of execution was successful, otherwise error return value
|
||||
*/
|
||||
ReturnValue_t executeFlashReadCommand(const uint8_t* commandData, size_t commandDataLen);
|
||||
|
||||
/**
|
||||
* @brief Fills command buffer with data to boot image (works only when star tracker is
|
||||
* in bootloader mode).
|
||||
*/
|
||||
void prepareBootCommand();
|
||||
|
||||
/**
|
||||
* @brief Fills command buffer with command to get the checksum of a flash part
|
||||
*/
|
||||
ReturnValue_t prepareChecksumCommand(const uint8_t* commandData, size_t commandDataLen);
|
||||
|
||||
/**
|
||||
* @brief Fills the command buffer with the command to take an image.
|
||||
*/
|
||||
void prepareTakeImageCommand(const uint8_t* commandData);
|
||||
|
||||
/**
|
||||
* @brief Fills command buffer with data to request the version telemetry packet
|
||||
*/
|
||||
void prepareVersionRequest();
|
||||
|
||||
/**
|
||||
* @brief Fills the command buffer with data to request the interface telemetry packet.
|
||||
*/
|
||||
void prepareInterfaceRequest();
|
||||
|
||||
/**
|
||||
* @brief Fills the command buffer with data to request the power telemetry packet.
|
||||
*/
|
||||
void preparePowerRequest();
|
||||
|
||||
/**
|
||||
* @brief Fills command buffer with data to reboot star tracker.
|
||||
*/
|
||||
void prepareSwitchToBootloaderCmd();
|
||||
|
||||
/**
|
||||
* @brief Fills command buffer with data to subscribe to a telemetry packet.
|
||||
*
|
||||
* @param tmId The ID of the telemetry packet to subscribe to
|
||||
*/
|
||||
void prepareSubscriptionCommand(const uint8_t* tmId);
|
||||
|
||||
/**
|
||||
* @brief Fills command buffer with data to request solution telemtry packet (contains
|
||||
* attitude information)
|
||||
*/
|
||||
void prepareSolutionRequest();
|
||||
|
||||
/**
|
||||
* @brief Fills command buffer with data to request temperature from star tracker
|
||||
*/
|
||||
void prepareTemperatureRequest();
|
||||
|
||||
/**
|
||||
* @brief Fills command buffer with data to request histogram
|
||||
*/
|
||||
void prepareHistogramRequest();
|
||||
|
||||
/**
|
||||
* @brief Reads parameters from json file specified by string in commandData and
|
||||
* prepares the command to apply the parameter set to the star tracker
|
||||
*
|
||||
* @param commandData Contains string with file name
|
||||
* @param commandDataLen Length of command
|
||||
* @param paramSet The object defining the command generation
|
||||
*
|
||||
* @return returnvalue::OK if successful, otherwise error return Value
|
||||
*/
|
||||
ReturnValue_t prepareParamCommand(const uint8_t* commandData, size_t commandDataLen,
|
||||
ArcsecJsonParamBase& paramSet, bool reinitSet);
|
||||
|
||||
/**
|
||||
* @brief The following function will fill the command buffer with the command to request
|
||||
* a parameter set.
|
||||
*/
|
||||
ReturnValue_t prepareRequestCameraParams();
|
||||
ReturnValue_t prepareRequestLimitsParams();
|
||||
ReturnValue_t prepareRequestLogLevelParams();
|
||||
ReturnValue_t prepareRequestMountingParams();
|
||||
ReturnValue_t prepareRequestImageProcessorParams();
|
||||
ReturnValue_t prepareRequestCentroidingParams();
|
||||
ReturnValue_t prepareRequestLisaParams();
|
||||
ReturnValue_t prepareRequestMatchingParams();
|
||||
ReturnValue_t prepareRequestTrackingParams();
|
||||
ReturnValue_t prepareRequestValidationParams();
|
||||
ReturnValue_t prepareRequestAlgoParams();
|
||||
ReturnValue_t prepareRequestSubscriptionParams();
|
||||
ReturnValue_t prepareRequestLogSubscriptionParams();
|
||||
ReturnValue_t prepareRequestDebugCameraParams();
|
||||
|
||||
/**
|
||||
* @brief Handles action replies with datasets.
|
||||
*/
|
||||
ReturnValue_t handleActionReplySet(const uint8_t* rawFrame, LocalPoolDataSetBase& dataset,
|
||||
size_t size);
|
||||
|
||||
/**
|
||||
* @brief Default function to handle action replies
|
||||
*/
|
||||
ReturnValue_t handleActionReply(const uint8_t* rawFrame);
|
||||
|
||||
/**
|
||||
* @brief Handles reply to upload centroid command
|
||||
*/
|
||||
ReturnValue_t handleUploadCentroidReply();
|
||||
|
||||
/**
|
||||
* @brief Handles reply to checksum command
|
||||
*/
|
||||
ReturnValue_t handleChecksumReply(const uint8_t* rawFrame);
|
||||
|
||||
/**
|
||||
* @brief Handles all set parameter replies
|
||||
*/
|
||||
ReturnValue_t handleSetParamReply(const uint8_t* rawFrame);
|
||||
|
||||
ReturnValue_t handlePingReply(const uint8_t* rawFrame);
|
||||
|
||||
ReturnValue_t handleParamRequest(const uint8_t* rawFrame, 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(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 returnvalue::OK if successful, otherwise error return value
|
||||
*/
|
||||
ReturnValue_t handleTm(const uint8_t* rawFrame, LocalPoolDataSetBase& dataset, size_t size);
|
||||
|
||||
/**
|
||||
* @brief Checks if star tracker is in valid mode for executing the received command.
|
||||
*
|
||||
* @param actioId Id of received command
|
||||
*
|
||||
* @return returnvalue::OK if star tracker is in valid mode, otherwise error return value
|
||||
*/
|
||||
ReturnValue_t checkCommand(ActionId_t actionId);
|
||||
|
||||
void doOnTransition(Submode_t subModeFrom);
|
||||
void doNormalTransition(Mode_t modeFrom, Submode_t subModeFrom);
|
||||
void bootFirmware(Mode_t toMode);
|
||||
void bootBootloader();
|
||||
};
|
||||
|
||||
#endif /* MISSION_DEVICES_STARTRACKERHANDLER_H_ */
|
181
mission/acs/str/arcsecJsonKeys.h
Normal file
181
mission/acs/str/arcsecJsonKeys.h
Normal file
@ -0,0 +1,181 @@
|
||||
#ifndef BSP_Q7S_DEVICES_DEVICEDEFINITIONS_ARCSECJSONKEYS_H_
|
||||
#define BSP_Q7S_DEVICES_DEVICEDEFINITIONS_ARCSECJSONKEYS_H_
|
||||
|
||||
/**
|
||||
* @brief Keys used in JSON file of ARCSEC.
|
||||
*/
|
||||
namespace arcseckeys {
|
||||
static const char PROPERTIES[] = "properties";
|
||||
static const char NAME[] = "name";
|
||||
static const char VALUE[] = "value";
|
||||
|
||||
static const char LIMITS[] = "limits";
|
||||
static const char ACTION[] = "action";
|
||||
static const char FPGA18CURRENT[] = "FPGA18Current";
|
||||
static const char FPGA25CURRENT[] = "FPGA25Current";
|
||||
static const char FPGA10CURRENT[] = "FPGA10Current";
|
||||
static const char MCUCURRENT[] = "MCUCurrent";
|
||||
static const char CMOS21CURRENT[] = "CMOS21Current";
|
||||
static const char CMOSPIXCURRENT[] = "CMOSPixCurrent";
|
||||
static const char CMOS33CURRENT[] = "CMOS33Current";
|
||||
static const char CMOSVRESCURRENT[] = "CMOSVResCurrent";
|
||||
static const char CMOS_TEMPERATURE[] = "CMOSTemperature";
|
||||
static const char MCU_TEMPERATURE[] = "MCUTemperature";
|
||||
|
||||
static const char MOUNTING[] = "mounting";
|
||||
static const char qw[] = "qw";
|
||||
static const char qx[] = "qx";
|
||||
static const char qy[] = "qy";
|
||||
static const char qz[] = "qz";
|
||||
|
||||
static const char IMAGE_PROCESSOR[] = "imageprocessor";
|
||||
static const char IMAGE_PROCESSOR_MODE[] = "mode";
|
||||
static const char STORE[] = "store";
|
||||
static const char SIGNAL_THRESHOLD[] = "signalThreshold";
|
||||
static const char IMAGE_PROCESSOR_DARK_THRESHOLD[] = "darkThreshold";
|
||||
static const char BACKGROUND_COMPENSATION[] = "backgroundcompensation";
|
||||
|
||||
static const char CAMERA[] = "camera";
|
||||
static const char MODE[] = "mode";
|
||||
static const char FOCALLENGTH[] = "focallength";
|
||||
static const char EXPOSURE[] = "exposure";
|
||||
static const char INTERVAL[] = "interval";
|
||||
static const char OFFSET[] = "offset";
|
||||
static const char PGAGAIN[] = "PGAGain";
|
||||
static const char ADCGAIN[] = "ADCGain";
|
||||
static const char REG_1[] = "reg1";
|
||||
static const char VAL_1[] = "val1";
|
||||
static const char REG_2[] = "reg2";
|
||||
static const char VAL_2[] = "val2";
|
||||
static const char REG_3[] = "reg3";
|
||||
static const char VAL_3[] = "val3";
|
||||
static const char REG_4[] = "reg4";
|
||||
static const char VAL_4[] = "val4";
|
||||
static const char REG_5[] = "reg5";
|
||||
static const char VAL_5[] = "val5";
|
||||
static const char REG_6[] = "reg6";
|
||||
static const char VAL_6[] = "val6";
|
||||
static const char REG_7[] = "reg7";
|
||||
static const char VAL_7[] = "val7";
|
||||
static const char REG_8[] = "reg8";
|
||||
static const char VAL_8[] = "val8";
|
||||
static const char FREQ_1[] = "freq1";
|
||||
|
||||
static const char BLOB[] = "blob";
|
||||
static const char MIN_VALUE[] = "minValue";
|
||||
static const char MIN_DISTANCE[] = "minDistance";
|
||||
static const char NEIGHBOUR_DISTANCE[] = "neighbourDistance";
|
||||
static const char NEIGHBOUR_BRIGHT_PIXELS[] = "neighbourBrightPixels";
|
||||
static const char MIN_TOTAL_VALUE[] = "minTotalValue";
|
||||
static const char MAX_TOTAL_VALUE[] = "maxTotalValue";
|
||||
static const char MIN_BRIGHT_NEIGHBOURS[] = "minBrightNeighbours";
|
||||
static const char MAX_BRIGHT_NEIGHBOURS[] = "maxBrightNeighbours";
|
||||
static const char MAX_PIXEL_TO_CONSIDER[] = "maxPixelsToConsider";
|
||||
// static const char SIGNAL_THRESHOLD[] = "signalThreshold";
|
||||
static const char BLOB_DARK_THRESHOLD[] = "darkThreshold";
|
||||
static const char ENABLE_HISTOGRAM[] = "enableHistogram";
|
||||
static const char ENABLE_CONTRAST[] = "enableContrast";
|
||||
static const char BIN_MODE[] = "binMode";
|
||||
|
||||
static const char CENTROIDING[] = "centroiding";
|
||||
static const char ENABLE_FILTER[] = "enableFilter";
|
||||
static const char MAX_QUALITY[] = "maxquality";
|
||||
static const char DARK_THRESHOLD[] = "darkthreshold";
|
||||
static const char MIN_QUALITY[] = "minquality";
|
||||
static const char MAX_INTENSITY[] = "maxintensity";
|
||||
static const char MIN_INTENSITY[] = "minintensity";
|
||||
static const char MAX_MAGNITUDE[] = "maxmagnitude";
|
||||
static const char GAUSSIAN_CMAX[] = "gaussianCmax";
|
||||
static const char GAUSSIAN_CMIN[] = "gaussianCmin";
|
||||
static const char TRANSMATRIX_00[] = "transmatrix00";
|
||||
static const char TRANSMATRIX_01[] = "transmatrix01";
|
||||
static const char TRANSMATRIX_10[] = "transmatrix10";
|
||||
static const char TRANSMATRIX_11[] = "transmatrix11";
|
||||
|
||||
static const char LISA[] = "lisa";
|
||||
static const char LISA_MODE[] = "mode";
|
||||
static const char PREFILTER_DIST_THRESHOLD[] = "prefilterDistThreshold";
|
||||
static const char PREFILTER_ANGLE_THRESHOLD[] = "prefilterAngleThreshold";
|
||||
static const char FOV_WIDTH[] = "fov_width";
|
||||
static const char FOV_HEIGHT[] = "fov_height";
|
||||
static const char FLOAT_STAR_LIMIT[] = "float_star_limit";
|
||||
static const char CLOSE_STAR_LIMIT[] = "close_star_limit";
|
||||
static const char RATING_WEIGHT_CLOSE_STAR_COUNT[] = "rating_weight_close_star_count";
|
||||
static const char RATING_WEIGHT_FRACTION_CLOSE[] = "rating_weight_fraction_close";
|
||||
static const char RATING_WEIGHT_MEAN_SUM[] = "rating_weight_mean_sum";
|
||||
static const char RATING_WEIGHT_DB_STAR_COUNT[] = "rating_weight_db_star_count";
|
||||
static const char MAX_COMBINATIONS[] = "max_combinations";
|
||||
static const char NR_STARS_STOP[] = "nr_stars_stop";
|
||||
static const char FRACTION_CLOSE_STOP[] = "fraction_close_stop";
|
||||
|
||||
static const char MATCHING[] = "matching";
|
||||
static const char SQUARED_DISTANCE_LIMIT[] = "squaredDistanceLimit";
|
||||
static const char SQUARED_SHIFT_LIMIT[] = "squaredShiftLimit";
|
||||
|
||||
static const char VALIDATION[] = "validation";
|
||||
static const char STABLE_COUNT[] = "stable_count";
|
||||
static const char MAX_DIFFERENCE[] = "max_difference";
|
||||
static const char MIN_TRACKER_CONFIDENCE[] = "min_trackerConfidence";
|
||||
static const char MIN_MATCHED_STARS[] = "min_matchedStars";
|
||||
|
||||
static const char TRACKING[] = "tracking";
|
||||
static const char THIN_LIMIT[] = "thinLimit";
|
||||
static const char OUTLIER_THRESHOLD[] = "outlierThreshold";
|
||||
static const char OUTLIER_THRESHOLD_QUEST[] = "outlierThresholdQUEST";
|
||||
static const char TRACKER_CHOICE[] = "trackerChoice";
|
||||
|
||||
static const char ALGO[] = "algo";
|
||||
static const char L2T_MIN_CONFIDENCE[] = "l2t_minConfidence";
|
||||
static const char L2T_MIN_MATCHED[] = "l2t_minMatched";
|
||||
static const char T2L_MIN_CONFIDENCE[] = "t2l_minConfidence";
|
||||
static const char T2L_MIN_MATCHED[] = "t2l_minMatched";
|
||||
|
||||
static const char LOGLEVEL[] = "loglevel";
|
||||
static const char LOGLEVEL1[] = "loglevel1";
|
||||
static const char LOGLEVEL2[] = "loglevel2";
|
||||
static const char LOGLEVEL3[] = "loglevel3";
|
||||
static const char LOGLEVEL4[] = "loglevel4";
|
||||
static const char LOGLEVEL5[] = "loglevel5";
|
||||
static const char LOGLEVEL6[] = "loglevel6";
|
||||
static const char LOGLEVEL7[] = "loglevel7";
|
||||
static const char LOGLEVEL8[] = "loglevel8";
|
||||
static const char LOGLEVEL9[] = "loglevel9";
|
||||
static const char LOGLEVEL10[] = "loglevel10";
|
||||
static const char LOGLEVEL11[] = "loglevel11";
|
||||
static const char LOGLEVEL12[] = "loglevel12";
|
||||
static const char LOGLEVEL13[] = "loglevel13";
|
||||
static const char LOGLEVEL14[] = "loglevel14";
|
||||
static const char LOGLEVEL15[] = "loglevel15";
|
||||
static const char LOGLEVEL16[] = "loglevel16";
|
||||
|
||||
static const char SUBSCRIPTION[] = "subscription";
|
||||
static const char TELEMETRY_1[] = "telemetry1";
|
||||
static const char TELEMETRY_2[] = "telemetry2";
|
||||
static const char TELEMETRY_3[] = "telemetry3";
|
||||
static const char TELEMETRY_4[] = "telemetry4";
|
||||
static const char TELEMETRY_5[] = "telemetry5";
|
||||
static const char TELEMETRY_6[] = "telemetry6";
|
||||
static const char TELEMETRY_7[] = "telemetry7";
|
||||
static const char TELEMETRY_8[] = "telemetry8";
|
||||
static const char TELEMETRY_9[] = "telemetry9";
|
||||
static const char TELEMETRY_10[] = "telemetry10";
|
||||
static const char TELEMETRY_11[] = "telemetry11";
|
||||
static const char TELEMETRY_12[] = "telemetry12";
|
||||
static const char TELEMETRY_13[] = "telemetry13";
|
||||
static const char TELEMETRY_14[] = "telemetry14";
|
||||
static const char TELEMETRY_15[] = "telemetry15";
|
||||
static const char TELEMETRY_16[] = "telemetry16";
|
||||
|
||||
static const char LOG_SUBSCRIPTION[] = "logsubscription";
|
||||
static const char LEVEL1[] = "level1";
|
||||
static const char MODULE1[] = "module1";
|
||||
static const char LEVEL2[] = "level2";
|
||||
static const char MODULE2[] = "module2";
|
||||
|
||||
static const char DEBUG_CAMERA[] = "debugcamera";
|
||||
static const char TIMING[] = "timing";
|
||||
static const char TEST[] = "test";
|
||||
|
||||
} // namespace arcseckeys
|
||||
|
||||
#endif /* BSP_Q7S_DEVICES_DEVICEDEFINITIONS_ARCSECJSONKEYS_H_ */
|
7
mission/acs/str/strHelpers.cpp
Normal file
7
mission/acs/str/strHelpers.cpp
Normal file
@ -0,0 +1,7 @@
|
||||
#include <mission/acs/str/strHelpers.h>
|
||||
|
||||
uint8_t startracker::getReplyFrameType(const uint8_t* rawFrame) { return rawFrame[0]; }
|
||||
|
||||
uint8_t startracker::getId(const uint8_t* rawFrame) { return rawFrame[1]; }
|
||||
|
||||
uint8_t startracker::getStatusField(const uint8_t* rawFrame) { return rawFrame[2]; }
|
1518
mission/acs/str/strHelpers.h
Normal file
1518
mission/acs/str/strHelpers.h
Normal file
File diff suppressed because it is too large
Load Diff
918
mission/acs/str/strJsonCommands.cpp
Normal file
918
mission/acs/str/strJsonCommands.cpp
Normal file
@ -0,0 +1,918 @@
|
||||
#include <mission/acs/str/arcsecJsonKeys.h>
|
||||
#include <mission/acs/str/strJsonCommands.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 = returnvalue::OK;
|
||||
uint8_t offset = 0;
|
||||
std::string param;
|
||||
addSetParamHeader(buffer, startracker::ID::LIMITS);
|
||||
offset = 2;
|
||||
result = getParam(arcseckeys::ACTION, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::FPGA18CURRENT, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
addfloat(param, buffer + offset);
|
||||
offset += sizeof(float);
|
||||
result = getParam(arcseckeys::FPGA25CURRENT, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
addfloat(param, buffer + offset);
|
||||
offset += sizeof(float);
|
||||
result = getParam(arcseckeys::FPGA10CURRENT, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
addfloat(param, buffer + offset);
|
||||
offset += sizeof(float);
|
||||
result = getParam(arcseckeys::MCUCURRENT, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
addfloat(param, buffer + offset);
|
||||
offset += sizeof(float);
|
||||
result = getParam(arcseckeys::CMOS21CURRENT, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
addfloat(param, buffer + offset);
|
||||
offset += sizeof(float);
|
||||
result = getParam(arcseckeys::CMOSPIXCURRENT, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
addfloat(param, buffer + offset);
|
||||
offset += sizeof(float);
|
||||
result = getParam(arcseckeys::CMOS33CURRENT, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
addfloat(param, buffer + offset);
|
||||
offset += sizeof(float);
|
||||
result = getParam(arcseckeys::CMOSVRESCURRENT, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
addfloat(param, buffer + offset);
|
||||
offset += sizeof(float);
|
||||
result = getParam(arcseckeys::CMOS_TEMPERATURE, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
addfloat(param, buffer + offset);
|
||||
offset += sizeof(float);
|
||||
result = getParam(arcseckeys::MCU_TEMPERATURE, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
addfloat(param, buffer + offset);
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
Tracking::Tracking() : ArcsecJsonParamBase(arcseckeys::TRACKING) {}
|
||||
|
||||
size_t Tracking::getSize() { return COMMAND_SIZE; }
|
||||
|
||||
ReturnValue_t Tracking::createCommand(uint8_t* buffer) {
|
||||
ReturnValue_t result = returnvalue::OK;
|
||||
uint8_t offset = 0;
|
||||
std::string param;
|
||||
addSetParamHeader(buffer, startracker::ID::TRACKING);
|
||||
offset = 2;
|
||||
result = getParam(arcseckeys::THIN_LIMIT, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
addfloat(param, buffer + offset);
|
||||
offset += sizeof(float);
|
||||
result = getParam(arcseckeys::OUTLIER_THRESHOLD, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
addfloat(param, buffer + offset);
|
||||
offset += sizeof(float);
|
||||
result = getParam(arcseckeys::OUTLIER_THRESHOLD_QUEST, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
addfloat(param, buffer + offset);
|
||||
offset += sizeof(float);
|
||||
result = getParam(arcseckeys::TRACKER_CHOICE, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
Mounting::Mounting() : ArcsecJsonParamBase(arcseckeys::MOUNTING) {}
|
||||
|
||||
size_t Mounting::getSize() { return COMMAND_SIZE; }
|
||||
|
||||
ReturnValue_t Mounting::createCommand(uint8_t* buffer) {
|
||||
ReturnValue_t result = returnvalue::OK;
|
||||
uint8_t offset = 0;
|
||||
std::string param;
|
||||
addSetParamHeader(buffer, startracker::ID::MOUNTING);
|
||||
offset = 2;
|
||||
result = getParam(arcseckeys::qw, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
addfloat(param, buffer + offset);
|
||||
offset += sizeof(float);
|
||||
result = getParam(arcseckeys::qx, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
addfloat(param, buffer + offset);
|
||||
offset += sizeof(float);
|
||||
result = getParam(arcseckeys::qy, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
addfloat(param, buffer + offset);
|
||||
offset += sizeof(float);
|
||||
result = getParam(arcseckeys::qz, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
addfloat(param, buffer + offset);
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ImageProcessor::ImageProcessor() : ArcsecJsonParamBase(arcseckeys::IMAGE_PROCESSOR) {}
|
||||
|
||||
size_t ImageProcessor::getSize() { return COMMAND_SIZE; }
|
||||
|
||||
ReturnValue_t ImageProcessor::createCommand(uint8_t* buffer) {
|
||||
ReturnValue_t result = returnvalue::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 != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::STORE, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::SIGNAL_THRESHOLD, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint16(param, buffer + offset);
|
||||
offset += sizeof(uint16_t);
|
||||
result = getParam(arcseckeys::IMAGE_PROCESSOR_DARK_THRESHOLD, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint16(param, buffer + offset);
|
||||
offset += sizeof(uint16_t);
|
||||
result = getParam(arcseckeys::BACKGROUND_COMPENSATION, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
Camera::Camera() : ArcsecJsonParamBase(arcseckeys::CAMERA) {}
|
||||
|
||||
size_t Camera::getSize() { return COMMAND_SIZE; }
|
||||
|
||||
ReturnValue_t Camera::createCommand(uint8_t* buffer) {
|
||||
ReturnValue_t result = returnvalue::OK;
|
||||
uint8_t offset = 0;
|
||||
std::string param;
|
||||
addSetParamHeader(buffer, startracker::ID::CAMERA);
|
||||
offset = 2;
|
||||
result = getParam(arcseckeys::MODE, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::FOCALLENGTH, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
addfloat(param, buffer + offset);
|
||||
offset += sizeof(float);
|
||||
result = getParam(arcseckeys::EXPOSURE, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
addfloat(param, buffer + offset);
|
||||
offset += sizeof(float);
|
||||
result = getParam(arcseckeys::INTERVAL, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
addfloat(param, buffer + offset);
|
||||
offset += sizeof(float);
|
||||
result = getParam(arcseckeys::OFFSET, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
addint16(param, buffer + offset);
|
||||
offset += sizeof(int16_t);
|
||||
result = getParam(arcseckeys::PGAGAIN, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::ADCGAIN, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::REG_1, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::VAL_1, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::REG_2, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::VAL_2, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::REG_3, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::VAL_3, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::REG_4, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::VAL_4, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::REG_5, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::VAL_5, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::REG_6, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::VAL_6, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::REG_7, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::VAL_7, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::REG_8, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::VAL_8, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::FREQ_1, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint32(param, buffer + offset);
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
Centroiding::Centroiding() : ArcsecJsonParamBase(arcseckeys::CENTROIDING) {}
|
||||
|
||||
size_t Centroiding::getSize() { return COMMAND_SIZE; }
|
||||
|
||||
ReturnValue_t Centroiding::createCommand(uint8_t* buffer) {
|
||||
ReturnValue_t result = returnvalue::OK;
|
||||
uint8_t offset = 0;
|
||||
std::string param;
|
||||
addSetParamHeader(buffer, startracker::ID::CENTROIDING);
|
||||
offset = 2;
|
||||
result = getParam(arcseckeys::ENABLE_FILTER, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::MAX_QUALITY, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
addfloat(param, buffer + offset);
|
||||
offset += sizeof(float);
|
||||
result = getParam(arcseckeys::DARK_THRESHOLD, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
addfloat(param, buffer + offset);
|
||||
offset += sizeof(float);
|
||||
result = getParam(arcseckeys::MIN_QUALITY, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
addfloat(param, buffer + offset);
|
||||
offset += sizeof(float);
|
||||
result = getParam(arcseckeys::MAX_INTENSITY, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
addfloat(param, buffer + offset);
|
||||
offset += sizeof(float);
|
||||
result = getParam(arcseckeys::MIN_INTENSITY, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
addfloat(param, buffer + offset);
|
||||
offset += sizeof(float);
|
||||
result = getParam(arcseckeys::MAX_MAGNITUDE, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
addfloat(param, buffer + offset);
|
||||
offset += sizeof(float);
|
||||
result = getParam(arcseckeys::GAUSSIAN_CMAX, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
addfloat(param, buffer + offset);
|
||||
offset += sizeof(float);
|
||||
result = getParam(arcseckeys::GAUSSIAN_CMIN, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
addfloat(param, buffer + offset);
|
||||
offset += sizeof(float);
|
||||
result = getParam(arcseckeys::TRANSMATRIX_00, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
addfloat(param, buffer + offset);
|
||||
offset += sizeof(float);
|
||||
result = getParam(arcseckeys::TRANSMATRIX_01, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
addfloat(param, buffer + offset);
|
||||
offset += sizeof(float);
|
||||
result = getParam(arcseckeys::TRANSMATRIX_10, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
addfloat(param, buffer + offset);
|
||||
offset += sizeof(float);
|
||||
result = getParam(arcseckeys::TRANSMATRIX_11, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
addfloat(param, buffer + offset);
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
Lisa::Lisa() : ArcsecJsonParamBase(arcseckeys::LISA) {}
|
||||
|
||||
size_t Lisa::getSize() { return COMMAND_SIZE; }
|
||||
|
||||
ReturnValue_t Lisa::createCommand(uint8_t* buffer) {
|
||||
ReturnValue_t result = returnvalue::OK;
|
||||
uint8_t offset = 0;
|
||||
std::string param;
|
||||
addSetParamHeader(buffer, startracker::ID::LISA);
|
||||
offset = 2;
|
||||
result = getParam(arcseckeys::LISA_MODE, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint32(param, buffer + offset);
|
||||
offset += sizeof(uint32_t);
|
||||
result = getParam(arcseckeys::PREFILTER_DIST_THRESHOLD, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
addfloat(param, buffer + offset);
|
||||
offset += sizeof(float);
|
||||
result = getParam(arcseckeys::PREFILTER_ANGLE_THRESHOLD, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
addfloat(param, buffer + offset);
|
||||
offset += sizeof(float);
|
||||
result = getParam(arcseckeys::FOV_WIDTH, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
addfloat(param, buffer + offset);
|
||||
offset += sizeof(float);
|
||||
result = getParam(arcseckeys::FOV_HEIGHT, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
addfloat(param, buffer + offset);
|
||||
offset += sizeof(float);
|
||||
result = getParam(arcseckeys::FLOAT_STAR_LIMIT, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
addfloat(param, buffer + offset);
|
||||
offset += sizeof(float);
|
||||
result = getParam(arcseckeys::CLOSE_STAR_LIMIT, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
addfloat(param, buffer + offset);
|
||||
offset += sizeof(float);
|
||||
result = getParam(arcseckeys::RATING_WEIGHT_CLOSE_STAR_COUNT, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
addfloat(param, buffer + offset);
|
||||
offset += sizeof(float);
|
||||
result = getParam(arcseckeys::RATING_WEIGHT_FRACTION_CLOSE, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
addfloat(param, buffer + offset);
|
||||
offset += sizeof(float);
|
||||
result = getParam(arcseckeys::RATING_WEIGHT_MEAN_SUM, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
addfloat(param, buffer + offset);
|
||||
offset += sizeof(float);
|
||||
result = getParam(arcseckeys::RATING_WEIGHT_DB_STAR_COUNT, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
addfloat(param, buffer + offset);
|
||||
offset += sizeof(float);
|
||||
result = getParam(arcseckeys::MAX_COMBINATIONS, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::NR_STARS_STOP, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::FRACTION_CLOSE_STOP, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
addfloat(param, buffer + offset);
|
||||
offset += sizeof(float);
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
Matching::Matching() : ArcsecJsonParamBase(arcseckeys::MATCHING) {}
|
||||
|
||||
size_t Matching::getSize() { return COMMAND_SIZE; }
|
||||
|
||||
ReturnValue_t Matching::createCommand(uint8_t* buffer) {
|
||||
ReturnValue_t result = returnvalue::OK;
|
||||
uint8_t offset = 0;
|
||||
std::string param;
|
||||
addSetParamHeader(buffer, startracker::ID::MATCHING);
|
||||
offset = 2;
|
||||
result = getParam(arcseckeys::SQUARED_DISTANCE_LIMIT, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
addfloat(param, buffer + offset);
|
||||
offset += sizeof(float);
|
||||
result = getParam(arcseckeys::SQUARED_SHIFT_LIMIT, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
addfloat(param, buffer + offset);
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
Validation::Validation() : ArcsecJsonParamBase(arcseckeys::VALIDATION) {}
|
||||
|
||||
size_t Validation::getSize() { return COMMAND_SIZE; }
|
||||
|
||||
ReturnValue_t Validation::createCommand(uint8_t* buffer) {
|
||||
ReturnValue_t result = returnvalue::OK;
|
||||
uint8_t offset = 0;
|
||||
std::string param;
|
||||
addSetParamHeader(buffer, startracker::ID::VALIDATION);
|
||||
offset = 2;
|
||||
result = getParam(arcseckeys::STABLE_COUNT, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::MAX_DIFFERENCE, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
addfloat(param, buffer + offset);
|
||||
offset += sizeof(float);
|
||||
result = getParam(arcseckeys::MIN_TRACKER_CONFIDENCE, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
addfloat(param, buffer + offset);
|
||||
offset += sizeof(float);
|
||||
result = getParam(arcseckeys::MIN_MATCHED_STARS, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
Algo::Algo() : ArcsecJsonParamBase(arcseckeys::ALGO) {}
|
||||
|
||||
size_t Algo::getSize() { return COMMAND_SIZE; }
|
||||
|
||||
ReturnValue_t Algo::createCommand(uint8_t* buffer) {
|
||||
ReturnValue_t result = returnvalue::OK;
|
||||
uint8_t offset = 0;
|
||||
std::string param;
|
||||
addSetParamHeader(buffer, startracker::ID::ALGO);
|
||||
offset = 2;
|
||||
result = getParam(arcseckeys::MODE, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::L2T_MIN_CONFIDENCE, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
addfloat(param, buffer + offset);
|
||||
offset += sizeof(float);
|
||||
result = getParam(arcseckeys::L2T_MIN_MATCHED, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::T2L_MIN_CONFIDENCE, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
addfloat(param, buffer + offset);
|
||||
offset += sizeof(float);
|
||||
result = getParam(arcseckeys::T2L_MIN_MATCHED, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
LogLevel::LogLevel() : ArcsecJsonParamBase(arcseckeys::LOGLEVEL) {}
|
||||
|
||||
size_t LogLevel::getSize() { return COMMAND_SIZE; }
|
||||
|
||||
ReturnValue_t LogLevel::createCommand(uint8_t* buffer) {
|
||||
ReturnValue_t result = returnvalue::OK;
|
||||
uint8_t offset = 0;
|
||||
std::string param;
|
||||
addSetParamHeader(buffer, startracker::ID::LOG_LEVEL);
|
||||
offset = 2;
|
||||
result = getParam(arcseckeys::LOGLEVEL1, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::LOGLEVEL2, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::LOGLEVEL3, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::LOGLEVEL4, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::LOGLEVEL5, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::LOGLEVEL6, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::LOGLEVEL7, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::LOGLEVEL8, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::LOGLEVEL9, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::LOGLEVEL10, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::LOGLEVEL11, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::LOGLEVEL12, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::LOGLEVEL13, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::LOGLEVEL14, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::LOGLEVEL15, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::LOGLEVEL16, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
Subscription::Subscription() : ArcsecJsonParamBase(arcseckeys::SUBSCRIPTION) {}
|
||||
|
||||
size_t Subscription::getSize() { return COMMAND_SIZE; }
|
||||
|
||||
ReturnValue_t Subscription::createCommand(uint8_t* buffer) {
|
||||
ReturnValue_t result = returnvalue::OK;
|
||||
uint8_t offset = 0;
|
||||
std::string param;
|
||||
addSetParamHeader(buffer, startracker::ID::SUBSCRIPTION);
|
||||
offset = 2;
|
||||
result = getParam(arcseckeys::TELEMETRY_1, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::TELEMETRY_2, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::TELEMETRY_3, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::TELEMETRY_4, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::TELEMETRY_5, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::TELEMETRY_6, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::TELEMETRY_7, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::TELEMETRY_8, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::TELEMETRY_9, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::TELEMETRY_10, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::TELEMETRY_11, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::TELEMETRY_12, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::TELEMETRY_13, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::TELEMETRY_14, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::TELEMETRY_15, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::TELEMETRY_16, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
LogSubscription::LogSubscription() : ArcsecJsonParamBase(arcseckeys::LOG_SUBSCRIPTION) {}
|
||||
|
||||
size_t LogSubscription::getSize() { return COMMAND_SIZE; }
|
||||
|
||||
ReturnValue_t LogSubscription::createCommand(uint8_t* buffer) {
|
||||
ReturnValue_t result = returnvalue::OK;
|
||||
uint8_t offset = 0;
|
||||
std::string param;
|
||||
addSetParamHeader(buffer, startracker::ID::LOG_SUBSCRIPTION);
|
||||
offset = 2;
|
||||
result = getParam(arcseckeys::LEVEL1, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::MODULE1, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::LEVEL2, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
offset += sizeof(uint8_t);
|
||||
result = getParam(arcseckeys::MODULE2, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint8(param, buffer + offset);
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
DebugCamera::DebugCamera() : ArcsecJsonParamBase(arcseckeys::DEBUG_CAMERA) {}
|
||||
|
||||
size_t DebugCamera::getSize() { return COMMAND_SIZE; }
|
||||
|
||||
ReturnValue_t DebugCamera::createCommand(uint8_t* buffer) {
|
||||
ReturnValue_t result = returnvalue::OK;
|
||||
uint8_t offset = 0;
|
||||
std::string param;
|
||||
addSetParamHeader(buffer, startracker::ID::DEBUG_CAMERA);
|
||||
offset = 2;
|
||||
result = getParam(arcseckeys::TIMING, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint32(param, buffer + offset);
|
||||
offset += sizeof(uint32_t);
|
||||
result = getParam(arcseckeys::TEST, param);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
adduint32(param, buffer + offset);
|
||||
return returnvalue::OK;
|
||||
}
|
241
mission/acs/str/strJsonCommands.h
Normal file
241
mission/acs/str/strJsonCommands.h
Normal file
@ -0,0 +1,241 @@
|
||||
#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 <mission/acs/str/ArcsecJsonParamBase.h>
|
||||
|
||||
#include <string>
|
||||
|
||||
#include "fsfw/serviceinterface/ServiceInterface.h"
|
||||
|
||||
/**
|
||||
* @brief Generates command to set the limit parameters
|
||||
*
|
||||
*/
|
||||
class Limits : public ArcsecJsonParamBase {
|
||||
public:
|
||||
Limits();
|
||||
|
||||
size_t getSize();
|
||||
|
||||
private:
|
||||
static const size_t COMMAND_SIZE = 43;
|
||||
|
||||
virtual ReturnValue_t createCommand(uint8_t* buffer) override;
|
||||
};
|
||||
|
||||
/**
|
||||
* @brief Generates the command to configure the tracking algorithm.
|
||||
*
|
||||
*/
|
||||
class Tracking : public ArcsecJsonParamBase {
|
||||
public:
|
||||
Tracking();
|
||||
|
||||
size_t getSize();
|
||||
|
||||
private:
|
||||
static const size_t COMMAND_SIZE = 15;
|
||||
|
||||
ReturnValue_t createCommand(uint8_t* buffer) override;
|
||||
};
|
||||
|
||||
/**
|
||||
* @brief Generates the command to set the mounting quaternion
|
||||
*
|
||||
*/
|
||||
class Mounting : public ArcsecJsonParamBase {
|
||||
public:
|
||||
Mounting();
|
||||
|
||||
size_t getSize();
|
||||
|
||||
private:
|
||||
static const size_t COMMAND_SIZE = 18;
|
||||
|
||||
ReturnValue_t createCommand(uint8_t* buffer) override;
|
||||
};
|
||||
|
||||
/**
|
||||
* @brief Generates the command to configure the image processor
|
||||
*
|
||||
*/
|
||||
class ImageProcessor : public ArcsecJsonParamBase {
|
||||
public:
|
||||
ImageProcessor();
|
||||
|
||||
size_t getSize();
|
||||
|
||||
private:
|
||||
static const size_t COMMAND_SIZE = 9;
|
||||
|
||||
ReturnValue_t createCommand(uint8_t* buffer) override;
|
||||
};
|
||||
|
||||
/**
|
||||
* @brief Generates the command to set the mounting quaternion
|
||||
*
|
||||
*/
|
||||
class Camera : public ArcsecJsonParamBase {
|
||||
public:
|
||||
Camera();
|
||||
|
||||
size_t getSize();
|
||||
|
||||
private:
|
||||
static const size_t COMMAND_SIZE = 39;
|
||||
|
||||
ReturnValue_t createCommand(uint8_t* buffer) override;
|
||||
};
|
||||
|
||||
/**
|
||||
* @brief Generates the command to configure the centroiding algorithm
|
||||
*
|
||||
*/
|
||||
class Centroiding : public ArcsecJsonParamBase {
|
||||
public:
|
||||
Centroiding();
|
||||
|
||||
size_t getSize();
|
||||
|
||||
private:
|
||||
static const size_t COMMAND_SIZE = 51;
|
||||
|
||||
ReturnValue_t createCommand(uint8_t* buffer) override;
|
||||
};
|
||||
|
||||
/**
|
||||
* @brief Generates the command to configure the LISA (lost in space algorithm)
|
||||
*
|
||||
*/
|
||||
class Lisa : public ArcsecJsonParamBase {
|
||||
public:
|
||||
Lisa();
|
||||
|
||||
size_t getSize();
|
||||
|
||||
private:
|
||||
static const size_t COMMAND_SIZE = 52;
|
||||
|
||||
ReturnValue_t createCommand(uint8_t* buffer) override;
|
||||
};
|
||||
|
||||
/**
|
||||
* @brief Generates the command to configure the matching algorithm
|
||||
*
|
||||
*/
|
||||
class Matching : public ArcsecJsonParamBase {
|
||||
public:
|
||||
Matching();
|
||||
|
||||
size_t getSize();
|
||||
|
||||
private:
|
||||
static const size_t COMMAND_SIZE = 10;
|
||||
|
||||
ReturnValue_t createCommand(uint8_t* buffer) override;
|
||||
};
|
||||
|
||||
/**
|
||||
* @brief Generates the command to configure the validation parameters
|
||||
*
|
||||
*/
|
||||
class Validation : public ArcsecJsonParamBase {
|
||||
public:
|
||||
Validation();
|
||||
|
||||
size_t getSize();
|
||||
|
||||
private:
|
||||
static const size_t COMMAND_SIZE = 12;
|
||||
|
||||
ReturnValue_t createCommand(uint8_t* buffer) override;
|
||||
};
|
||||
|
||||
/**
|
||||
* @brief Generates command to configure the mechanism of automatically switching between the
|
||||
* LISA and other algorithms.
|
||||
*
|
||||
*/
|
||||
class Algo : public ArcsecJsonParamBase {
|
||||
public:
|
||||
Algo();
|
||||
|
||||
size_t getSize();
|
||||
|
||||
private:
|
||||
static const size_t COMMAND_SIZE = 13;
|
||||
|
||||
ReturnValue_t createCommand(uint8_t* buffer) override;
|
||||
};
|
||||
|
||||
/**
|
||||
* @brief Generates command to configure the log level parameters.
|
||||
*
|
||||
*/
|
||||
class LogLevel : public ArcsecJsonParamBase {
|
||||
public:
|
||||
LogLevel();
|
||||
|
||||
size_t getSize();
|
||||
|
||||
private:
|
||||
static const size_t COMMAND_SIZE = 18;
|
||||
|
||||
ReturnValue_t createCommand(uint8_t* buffer) override;
|
||||
};
|
||||
|
||||
/**
|
||||
* @brief Generates command to set subscription parameters.
|
||||
*
|
||||
*/
|
||||
class Subscription : public ArcsecJsonParamBase {
|
||||
public:
|
||||
Subscription();
|
||||
|
||||
size_t getSize();
|
||||
|
||||
private:
|
||||
static const size_t COMMAND_SIZE = 18;
|
||||
|
||||
ReturnValue_t createCommand(uint8_t* buffer) override;
|
||||
};
|
||||
|
||||
/**
|
||||
* @brief Generates command to set log subscription parameters.
|
||||
*
|
||||
*/
|
||||
class LogSubscription : public ArcsecJsonParamBase {
|
||||
public:
|
||||
LogSubscription();
|
||||
|
||||
size_t getSize();
|
||||
|
||||
private:
|
||||
static const size_t COMMAND_SIZE = 6;
|
||||
|
||||
ReturnValue_t createCommand(uint8_t* buffer) override;
|
||||
};
|
||||
|
||||
/**
|
||||
* @brief Generates command to set debug camera parameters
|
||||
*
|
||||
*/
|
||||
class DebugCamera : public ArcsecJsonParamBase {
|
||||
public:
|
||||
DebugCamera();
|
||||
|
||||
size_t getSize();
|
||||
|
||||
private:
|
||||
static const size_t COMMAND_SIZE = 10;
|
||||
|
||||
ReturnValue_t createCommand(uint8_t* buffer) override;
|
||||
};
|
||||
|
||||
#endif /* BSP_Q7S_DEVICES_DEVICEDEFINITIONS_STARTRACKERJSONCOMMANDS_H_ */
|
77
mission/acs/susMax1227Helpers.h
Normal file
77
mission/acs/susMax1227Helpers.h
Normal file
@ -0,0 +1,77 @@
|
||||
#ifndef MISSION_DEVICES_DEVICEDEFINITIONS_SUS_H_
|
||||
#define MISSION_DEVICES_DEVICEDEFINITIONS_SUS_H_
|
||||
|
||||
#include <fsfw/datapoollocal/StaticLocalDataSet.h>
|
||||
#include <fsfw/devicehandlers/DeviceHandlerIF.h>
|
||||
|
||||
#include <cstdint>
|
||||
|
||||
namespace susMax1227 {
|
||||
|
||||
static const DeviceCommandId_t NONE = 0x0; // Set when no command is pending
|
||||
|
||||
static const DeviceCommandId_t WRITE_SETUP = 1;
|
||||
/**
|
||||
* This command initiates the ADC conversion for all channels including the internal
|
||||
* temperature sensor.
|
||||
*/
|
||||
static const DeviceCommandId_t START_INT_TIMED_CONVERSIONS = 2;
|
||||
/**
|
||||
* This command reads the internal fifo which holds the temperature and the channel
|
||||
* conversions.
|
||||
*/
|
||||
static constexpr DeviceCommandId_t READ_INT_TIMED_CONVERSIONS = 3;
|
||||
|
||||
static constexpr DeviceCommandId_t READ_EXT_TIMED_CONVERSIONS = 4;
|
||||
|
||||
static constexpr DeviceCommandId_t READ_EXT_TIMED_TEMPS = 5;
|
||||
|
||||
/**
|
||||
* @brief This is the configuration byte which will be written to the setup register after
|
||||
* power on.
|
||||
*
|
||||
* @note Bit1 (DIFFSEL1) - Bit0 (DIFFSEL0): 0b00, No byte is following the setup byte
|
||||
* Bit3 (REFSEL1) - Bit2 (REFSEL0): 0b10, Internal reference, no wake-up delay
|
||||
* Bit5 (CLKSEL1) - Bit4 (CLKSEL0): 0b10, Internally clocked
|
||||
* Bit7 - Bit6: 0b01, Tells MAX1227 that this byte should be
|
||||
* written to the setup register
|
||||
*
|
||||
*/
|
||||
static constexpr uint8_t SETUP_INT_CLOKED = 0b01101000;
|
||||
static constexpr uint8_t SETUP_EXT_CLOCKED = 0b01111000;
|
||||
|
||||
/**
|
||||
* @brief This values will always be written to the ADC conversion register to specify the
|
||||
* conversions to perform.
|
||||
* @details Bit0: 1 - Enables temperature conversion
|
||||
* Bit2 (SCAN1) and Bit1 (SCAN0): 0b00, Scans channels 0 through N
|
||||
* Bit6 - Bit3 defines N: 0b0101 (N = 5)
|
||||
* Bit7: Always 1. Tells the ADC that this is the conversion register.
|
||||
*/
|
||||
static const uint8_t CONVERSION = 0b10101001;
|
||||
|
||||
static const uint8_t SUS_DATA_SET_ID = READ_INT_TIMED_CONVERSIONS;
|
||||
|
||||
/** Size of data replies. Temperature and 6 channel convesions (AIN0 - AIN5) */
|
||||
static const uint8_t SIZE_READ_INT_CONVERSIONS = 14;
|
||||
// 6 * conv byte, 6 * 0 and one trailing zero
|
||||
static constexpr uint8_t SIZE_READ_EXT_CONVERSIONS = 13;
|
||||
|
||||
static const uint8_t MAX_CMD_SIZE = 32;
|
||||
|
||||
static const uint8_t POOL_ENTRIES = 7;
|
||||
|
||||
enum SusPoolIds : lp_id_t { TEMPERATURE_C, CHANNEL_VEC };
|
||||
|
||||
class SusDataset : public StaticLocalDataSet<POOL_ENTRIES> {
|
||||
public:
|
||||
SusDataset(HasLocalDataPoolIF* owner) : StaticLocalDataSet(owner, SUS_DATA_SET_ID) {}
|
||||
|
||||
SusDataset(object_id_t objectId) : StaticLocalDataSet(sid_t(objectId, SUS_DATA_SET_ID)) {}
|
||||
|
||||
lp_var_t<float> tempC = lp_var_t<float>(sid.objectId, TEMPERATURE_C, this);
|
||||
lp_vec_t<uint16_t, 6> channels = lp_vec_t<uint16_t, 6>(sid.objectId, CHANNEL_VEC, this);
|
||||
};
|
||||
} // namespace susMax1227
|
||||
|
||||
#endif /* MISSION_DEVICES_DEVICEDEFINITIONS_SUS_H_ */
|
Reference in New Issue
Block a user