This commit is contained in:
parent
af8b4d5bc8
commit
4893af07ae
@ -3,13 +3,24 @@
|
|||||||
#include <mission/acs/rwHelpers.h>
|
#include <mission/acs/rwHelpers.h>
|
||||||
|
|
||||||
RwDummy::RwDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie)
|
RwDummy::RwDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie)
|
||||||
: DeviceHandlerBase(objectId, comif, comCookie) {}
|
: DeviceHandlerBase(objectId, comif, comCookie),
|
||||||
|
|
||||||
|
statusSet(this),
|
||||||
|
lastResetStatusSet(this),
|
||||||
|
tmDataset(this),
|
||||||
|
rwSpeedActuationSet(*this) {}
|
||||||
|
|
||||||
RwDummy::~RwDummy() {}
|
RwDummy::~RwDummy() {}
|
||||||
|
|
||||||
void RwDummy::doStartUp() { setMode(MODE_ON); }
|
void RwDummy::doStartUp() {
|
||||||
|
statusSet.setReportingEnabled(true);
|
||||||
|
setMode(MODE_ON);
|
||||||
|
}
|
||||||
|
|
||||||
void RwDummy::doShutDown() { setMode(MODE_OFF); }
|
void RwDummy::doShutDown() {
|
||||||
|
statusSet.setReportingEnabled(false);
|
||||||
|
setMode(MODE_OFF);
|
||||||
|
}
|
||||||
|
|
||||||
ReturnValue_t RwDummy::buildNormalDeviceCommand(DeviceCommandId_t *id) { return NOTHING_TO_SEND; }
|
ReturnValue_t RwDummy::buildNormalDeviceCommand(DeviceCommandId_t *id) { return NOTHING_TO_SEND; }
|
||||||
|
|
||||||
@ -74,5 +85,11 @@ ReturnValue_t RwDummy::initializeLocalDataPool(localpool::DataPool &localDataPoo
|
|||||||
localDataPoolMap.emplace(rws::SPI_BYTES_READ, 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_REG_OVERRUN_ERRORS, new PoolEntry<uint32_t>({0}));
|
||||||
localDataPoolMap.emplace(rws::SPI_TOTAL_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;
|
return returnvalue::OK;
|
||||||
}
|
}
|
||||||
|
@ -2,6 +2,7 @@
|
|||||||
#define DUMMIES_RWDUMMY_H_
|
#define DUMMIES_RWDUMMY_H_
|
||||||
|
|
||||||
#include <fsfw/devicehandlers/DeviceHandlerBase.h>
|
#include <fsfw/devicehandlers/DeviceHandlerBase.h>
|
||||||
|
#include <mission/acs/rwHelpers.h>
|
||||||
|
|
||||||
class RwDummy : public DeviceHandlerBase {
|
class RwDummy : public DeviceHandlerBase {
|
||||||
public:
|
public:
|
||||||
@ -15,6 +16,11 @@ class RwDummy : public DeviceHandlerBase {
|
|||||||
virtual ~RwDummy();
|
virtual ~RwDummy();
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
rws::StatusSet statusSet;
|
||||||
|
rws::LastResetSatus lastResetStatusSet;
|
||||||
|
rws::TmDataset tmDataset;
|
||||||
|
rws::RwSpeedActuationSet rwSpeedActuationSet;
|
||||||
|
|
||||||
PoolEntry<int32_t> rwSpeed = PoolEntry<int32_t>({0});
|
PoolEntry<int32_t> rwSpeed = PoolEntry<int32_t>({0});
|
||||||
PoolEntry<uint16_t> rampTime = PoolEntry<uint16_t>({10});
|
PoolEntry<uint16_t> rampTime = PoolEntry<uint16_t>({10});
|
||||||
|
|
||||||
|
@ -268,7 +268,7 @@ ReturnValue_t PersistentTmStore::getNextDumpPacket(PusTmReader& reader, bool& fi
|
|||||||
// restore the file dump, but for now do not trust the file.
|
// restore the file dump, but for now do not trust the file.
|
||||||
std::error_code e;
|
std::error_code e;
|
||||||
std::filesystem::remove(dumpParams.dirEntry.path().c_str(), e);
|
std::filesystem::remove(dumpParams.dirEntry.path().c_str(), e);
|
||||||
if(dumpParams.dirEntry.path() == activeFile) {
|
if (dumpParams.dirEntry.path() == activeFile) {
|
||||||
activeFile == std::nullopt;
|
activeFile == std::nullopt;
|
||||||
assignAndOrCreateMostRecentFile();
|
assignAndOrCreateMostRecentFile();
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user