From 22558a2f3929692503119e4f6f654441642bc262 Mon Sep 17 00:00:00 2001 From: meggert Date: Mon, 27 Feb 2023 14:02:35 +0100 Subject: [PATCH 001/112] fixed some param types --- mission/controller/acs/AcsParameters.h | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/mission/controller/acs/AcsParameters.h b/mission/controller/acs/AcsParameters.h index 11de10a3..f44f4a61 100644 --- a/mission/controller/acs/AcsParameters.h +++ b/mission/controller/acs/AcsParameters.h @@ -783,9 +783,9 @@ class AcsParameters : public HasParametersIF { struct RwHandlingParameters { double inertiaWheel = 0.000028198; - double maxTrq = 0.0032; // 3.2 [mNm] - int32_t stictionSpeed = 100; // RPM - int32_t stictionReleaseSpeed = 120; // RPM + double maxTrq = 0.0032; // 3.2 [mNm] + int32_t stictionSpeed = 100; // RPM + int32_t stictionReleaseSpeed = 120; // RPM double stictionTorque = 0.0006; uint16_t rampTime = 10; @@ -843,7 +843,7 @@ class AcsParameters : public HasParametersIF { double refDirection[3] = {-1, 0, 0}; // Antenna double refRotRate[3] = {0, 0, 0}; double quatRef[4] = {0, 0, 0, 1}; - int8_t timeElapsedMax = 10; // rot rate calculations + uint8_t timeElapsedMax = 10; // rot rate calculations // Default is Stuttgart GS double latitudeTgt = 48.7495 * M_PI / 180.; // [rad] Latitude @@ -859,7 +859,7 @@ class AcsParameters : public HasParametersIF { struct GsTargetModeControllerParameters : PointingLawParameters { double refDirection[3] = {-1, 0, 0}; // Antenna - int8_t timeElapsedMax = 10; // rot rate calculations + uint8_t timeElapsedMax = 10; // rot rate calculations // Default is Stuttgart GS double latitudeTgt = 48.7495 * M_PI / 180.; // [rad] Latitude @@ -871,7 +871,7 @@ class AcsParameters : public HasParametersIF { double refDirection[3] = {-1, 0, 0}; // Antenna double quatRef[4] = {0, 0, 0, 1}; double refRotRate[3] = {0, 0, 0}; - int8_t timeElapsedMax = 10; // rot rate calculations + uint8_t timeElapsedMax = 10; // rot rate calculations } nadirModeControllerParameters; struct InertialModeControllerParameters : PointingLawParameters { From 17a1a5a655a8ded27f382dbbc23fc65de632042f Mon Sep 17 00:00:00 2001 From: meggert Date: Mon, 27 Feb 2023 14:29:23 +0100 Subject: [PATCH 002/112] fixed paramerterWrapper setter to match type of parameter --- mission/controller/acs/AcsParameters.cpp | 202 +++++++++++------------ 1 file changed, 101 insertions(+), 101 deletions(-) diff --git a/mission/controller/acs/AcsParameters.cpp b/mission/controller/acs/AcsParameters.cpp index 2e5fbb1b..351601c3 100644 --- a/mission/controller/acs/AcsParameters.cpp +++ b/mission/controller/acs/AcsParameters.cpp @@ -30,19 +30,19 @@ ReturnValue_t AcsParameters::getParameter(uint8_t domainId, uint8_t parameterId, case 0x2: // InertiaEIVE switch (parameterId) { case 0x0: - parameterWrapper->set(inertiaEIVE.inertiaMatrix); + parameterWrapper->setMatrix(inertiaEIVE.inertiaMatrix); break; case 0x1: - parameterWrapper->set(inertiaEIVE.inertiaMatrixDeployed); + parameterWrapper->setMatrix(inertiaEIVE.inertiaMatrixDeployed); break; case 0x2: - parameterWrapper->set(inertiaEIVE.inertiaMatrixUndeployed); + parameterWrapper->setMatrix(inertiaEIVE.inertiaMatrixUndeployed); break; case 0x3: - parameterWrapper->set(inertiaEIVE.inertiaMatrixPanel1); + parameterWrapper->setMatrix(inertiaEIVE.inertiaMatrixPanel1); break; case 0x4: - parameterWrapper->set(inertiaEIVE.inertiaMatrixPanel3); + parameterWrapper->setMatrix(inertiaEIVE.inertiaMatrixPanel3); break; default: return INVALID_IDENTIFIER_ID; @@ -51,58 +51,58 @@ ReturnValue_t AcsParameters::getParameter(uint8_t domainId, uint8_t parameterId, case 0x3: // MgmHandlingParameters switch (parameterId) { case 0x0: - parameterWrapper->set(mgmHandlingParameters.mgm0orientationMatrix); + parameterWrapper->setMatrix(mgmHandlingParameters.mgm0orientationMatrix); break; case 0x1: - parameterWrapper->set(mgmHandlingParameters.mgm1orientationMatrix); + parameterWrapper->setMatrix(mgmHandlingParameters.mgm1orientationMatrix); break; case 0x2: - parameterWrapper->set(mgmHandlingParameters.mgm2orientationMatrix); + parameterWrapper->setMatrix(mgmHandlingParameters.mgm2orientationMatrix); break; case 0x3: - parameterWrapper->set(mgmHandlingParameters.mgm3orientationMatrix); + parameterWrapper->setMatrix(mgmHandlingParameters.mgm3orientationMatrix); break; case 0x4: - parameterWrapper->set(mgmHandlingParameters.mgm4orientationMatrix); + parameterWrapper->setMatrix(mgmHandlingParameters.mgm4orientationMatrix); break; case 0x5: - parameterWrapper->set(mgmHandlingParameters.mgm0hardIronOffset); + parameterWrapper->setVector(mgmHandlingParameters.mgm0hardIronOffset); break; case 0x6: - parameterWrapper->set(mgmHandlingParameters.mgm1hardIronOffset); + parameterWrapper->setVector(mgmHandlingParameters.mgm1hardIronOffset); break; case 0x7: - parameterWrapper->set(mgmHandlingParameters.mgm2hardIronOffset); + parameterWrapper->setVector(mgmHandlingParameters.mgm2hardIronOffset); break; case 0x8: - parameterWrapper->set(mgmHandlingParameters.mgm3hardIronOffset); + parameterWrapper->setVector(mgmHandlingParameters.mgm3hardIronOffset); break; case 0x9: - parameterWrapper->set(mgmHandlingParameters.mgm4hardIronOffset); + parameterWrapper->setVector(mgmHandlingParameters.mgm4hardIronOffset); break; case 0xA: - parameterWrapper->set(mgmHandlingParameters.mgm0softIronInverse); + parameterWrapper->setMatrix(mgmHandlingParameters.mgm0softIronInverse); break; case 0xB: - parameterWrapper->set(mgmHandlingParameters.mgm1softIronInverse); + parameterWrapper->setMatrix(mgmHandlingParameters.mgm1softIronInverse); break; case 0xC: - parameterWrapper->set(mgmHandlingParameters.mgm2softIronInverse); + parameterWrapper->setMatrix(mgmHandlingParameters.mgm2softIronInverse); break; case 0xD: - parameterWrapper->set(mgmHandlingParameters.mgm3softIronInverse); + parameterWrapper->setMatrix(mgmHandlingParameters.mgm3softIronInverse); break; case 0xE: - parameterWrapper->set(mgmHandlingParameters.mgm4softIronInverse); + parameterWrapper->setMatrix(mgmHandlingParameters.mgm4softIronInverse); break; case 0xF: - parameterWrapper->set(mgmHandlingParameters.mgm02variance); + parameterWrapper->setVector(mgmHandlingParameters.mgm02variance); break; case 0x10: - parameterWrapper->set(mgmHandlingParameters.mgm13variance); + parameterWrapper->setVector(mgmHandlingParameters.mgm13variance); break; case 0x11: - parameterWrapper->set(mgmHandlingParameters.mgm4variance); + parameterWrapper->setVector(mgmHandlingParameters.mgm4variance); break; default: return INVALID_IDENTIFIER_ID; @@ -111,112 +111,112 @@ ReturnValue_t AcsParameters::getParameter(uint8_t domainId, uint8_t parameterId, case 0x4: // SusHandlingParameters switch (parameterId) { case 0x0: - parameterWrapper->set(susHandlingParameters.sus0orientationMatrix); + parameterWrapper->setMatrix(susHandlingParameters.sus0orientationMatrix); break; case 0x1: - parameterWrapper->set(susHandlingParameters.sus1orientationMatrix); + parameterWrapper->setMatrix(susHandlingParameters.sus1orientationMatrix); break; case 0x2: - parameterWrapper->set(susHandlingParameters.sus2orientationMatrix); + parameterWrapper->setMatrix(susHandlingParameters.sus2orientationMatrix); break; case 0x3: - parameterWrapper->set(susHandlingParameters.sus3orientationMatrix); + parameterWrapper->setMatrix(susHandlingParameters.sus3orientationMatrix); break; case 0x4: - parameterWrapper->set(susHandlingParameters.sus4orientationMatrix); + parameterWrapper->setMatrix(susHandlingParameters.sus4orientationMatrix); break; case 0x5: - parameterWrapper->set(susHandlingParameters.sus5orientationMatrix); + parameterWrapper->setMatrix(susHandlingParameters.sus5orientationMatrix); break; case 0x6: - parameterWrapper->set(susHandlingParameters.sus6orientationMatrix); + parameterWrapper->setMatrix(susHandlingParameters.sus6orientationMatrix); break; case 0x7: - parameterWrapper->set(susHandlingParameters.sus7orientationMatrix); + parameterWrapper->setMatrix(susHandlingParameters.sus7orientationMatrix); break; case 0x8: - parameterWrapper->set(susHandlingParameters.sus8orientationMatrix); + parameterWrapper->setMatrix(susHandlingParameters.sus8orientationMatrix); break; case 0x9: - parameterWrapper->set(susHandlingParameters.sus9orientationMatrix); + parameterWrapper->setMatrix(susHandlingParameters.sus9orientationMatrix); break; case 0xA: - parameterWrapper->set(susHandlingParameters.sus10orientationMatrix); + parameterWrapper->setMatrix(susHandlingParameters.sus10orientationMatrix); break; case 0xB: - parameterWrapper->set(susHandlingParameters.sus11orientationMatrix); + parameterWrapper->setMatrix(susHandlingParameters.sus11orientationMatrix); break; case 0xC: - parameterWrapper->set(susHandlingParameters.sus0coeffAlpha); + parameterWrapper->setMatrix(susHandlingParameters.sus0coeffAlpha); break; case 0xD: - parameterWrapper->set(susHandlingParameters.sus0coeffBeta); + parameterWrapper->setMatrix(susHandlingParameters.sus0coeffBeta); break; case 0xE: - parameterWrapper->set(susHandlingParameters.sus1coeffAlpha); + parameterWrapper->setMatrix(susHandlingParameters.sus1coeffAlpha); break; case 0xF: - parameterWrapper->set(susHandlingParameters.sus1coeffBeta); + parameterWrapper->setMatrix(susHandlingParameters.sus1coeffBeta); break; case 0x10: - parameterWrapper->set(susHandlingParameters.sus2coeffAlpha); + parameterWrapper->setMatrix(susHandlingParameters.sus2coeffAlpha); break; case 0x11: - parameterWrapper->set(susHandlingParameters.sus2coeffBeta); + parameterWrapper->setMatrix(susHandlingParameters.sus2coeffBeta); break; case 0x12: - parameterWrapper->set(susHandlingParameters.sus3coeffAlpha); + parameterWrapper->setMatrix(susHandlingParameters.sus3coeffAlpha); break; case 0x13: - parameterWrapper->set(susHandlingParameters.sus3coeffBeta); + parameterWrapper->setMatrix(susHandlingParameters.sus3coeffBeta); break; case 0x14: - parameterWrapper->set(susHandlingParameters.sus4coeffAlpha); + parameterWrapper->setMatrix(susHandlingParameters.sus4coeffAlpha); break; case 0x15: - parameterWrapper->set(susHandlingParameters.sus4coeffBeta); + parameterWrapper->setMatrix(susHandlingParameters.sus4coeffBeta); break; case 0x16: - parameterWrapper->set(susHandlingParameters.sus5coeffAlpha); + parameterWrapper->setMatrix(susHandlingParameters.sus5coeffAlpha); break; case 0x17: - parameterWrapper->set(susHandlingParameters.sus5coeffBeta); + parameterWrapper->setMatrix(susHandlingParameters.sus5coeffBeta); break; case 0x18: - parameterWrapper->set(susHandlingParameters.sus6coeffAlpha); + parameterWrapper->setMatrix(susHandlingParameters.sus6coeffAlpha); break; case 0x19: - parameterWrapper->set(susHandlingParameters.sus6coeffBeta); + parameterWrapper->setMatrix(susHandlingParameters.sus6coeffBeta); break; case 0x1A: - parameterWrapper->set(susHandlingParameters.sus7coeffAlpha); + parameterWrapper->setMatrix(susHandlingParameters.sus7coeffAlpha); break; case 0x1B: - parameterWrapper->set(susHandlingParameters.sus7coeffBeta); + parameterWrapper->setMatrix(susHandlingParameters.sus7coeffBeta); break; case 0x1C: - parameterWrapper->set(susHandlingParameters.sus8coeffAlpha); + parameterWrapper->setMatrix(susHandlingParameters.sus8coeffAlpha); break; case 0x1D: - parameterWrapper->set(susHandlingParameters.sus8coeffBeta); + parameterWrapper->setMatrix(susHandlingParameters.sus8coeffBeta); break; case 0x1E: - parameterWrapper->set(susHandlingParameters.sus9coeffAlpha); + parameterWrapper->setMatrix(susHandlingParameters.sus9coeffAlpha); break; case 0x1F: - parameterWrapper->set(susHandlingParameters.sus9coeffBeta); + parameterWrapper->setMatrix(susHandlingParameters.sus9coeffBeta); break; case 0x20: - parameterWrapper->set(susHandlingParameters.sus10coeffAlpha); + parameterWrapper->setMatrix(susHandlingParameters.sus10coeffAlpha); break; case 0x21: - parameterWrapper->set(susHandlingParameters.sus10coeffBeta); + parameterWrapper->setMatrix(susHandlingParameters.sus10coeffBeta); break; case 0x22: - parameterWrapper->set(susHandlingParameters.sus11coeffAlpha); + parameterWrapper->setMatrix(susHandlingParameters.sus11coeffAlpha); break; case 0x23: - parameterWrapper->set(susHandlingParameters.sus11coeffBeta); + parameterWrapper->setMatrix(susHandlingParameters.sus11coeffBeta); break; default: return INVALID_IDENTIFIER_ID; @@ -225,34 +225,34 @@ ReturnValue_t AcsParameters::getParameter(uint8_t domainId, uint8_t parameterId, case (0x5): // GyrHandlingParameters switch (parameterId) { case 0x0: - parameterWrapper->set(gyrHandlingParameters.gyr0orientationMatrix); + parameterWrapper->setMatrix(gyrHandlingParameters.gyr0orientationMatrix); break; case 0x1: - parameterWrapper->set(gyrHandlingParameters.gyr1orientationMatrix); + parameterWrapper->setMatrix(gyrHandlingParameters.gyr1orientationMatrix); break; case 0x2: - parameterWrapper->set(gyrHandlingParameters.gyr2orientationMatrix); + parameterWrapper->setMatrix(gyrHandlingParameters.gyr2orientationMatrix); break; case 0x3: - parameterWrapper->set(gyrHandlingParameters.gyr3orientationMatrix); + parameterWrapper->setMatrix(gyrHandlingParameters.gyr3orientationMatrix); break; case 0x4: - parameterWrapper->set(gyrHandlingParameters.gyr0bias); + parameterWrapper->setVector(gyrHandlingParameters.gyr0bias); break; case 0x5: - parameterWrapper->set(gyrHandlingParameters.gyr1bias); + parameterWrapper->setVector(gyrHandlingParameters.gyr1bias); break; case 0x6: - parameterWrapper->set(gyrHandlingParameters.gyr2bias); + parameterWrapper->setVector(gyrHandlingParameters.gyr2bias); break; case 0x7: - parameterWrapper->set(gyrHandlingParameters.gyr3bias); + parameterWrapper->setVector(gyrHandlingParameters.gyr3bias); break; case 0x8: - parameterWrapper->set(gyrHandlingParameters.gyr02variance); + parameterWrapper->setVector(gyrHandlingParameters.gyr02variance); break; case 0x9: - parameterWrapper->set(gyrHandlingParameters.gyr13variance); + parameterWrapper->setVector(gyrHandlingParameters.gyr13variance); break; case 0xA: parameterWrapper->set(gyrHandlingParameters.preferAdis); @@ -288,25 +288,25 @@ ReturnValue_t AcsParameters::getParameter(uint8_t domainId, uint8_t parameterId, case (0x7): // RwMatrices switch (parameterId) { case 0x0: - parameterWrapper->set(rwMatrices.alignmentMatrix); + parameterWrapper->setMatrix(rwMatrices.alignmentMatrix); break; case 0x1: - parameterWrapper->set(rwMatrices.pseudoInverse); + parameterWrapper->setMatrix(rwMatrices.pseudoInverse); break; case 0x2: - parameterWrapper->set(rwMatrices.without1); + parameterWrapper->setMatrix(rwMatrices.without1); break; case 0x3: - parameterWrapper->set(rwMatrices.without2); + parameterWrapper->setMatrix(rwMatrices.without2); break; case 0x4: - parameterWrapper->set(rwMatrices.without3); + parameterWrapper->setMatrix(rwMatrices.without3); break; case 0x5: - parameterWrapper->set(rwMatrices.without4); + parameterWrapper->setMatrix(rwMatrices.without4); break; case 0x6: - parameterWrapper->set(rwMatrices.nullspace); + parameterWrapper->setVector(rwMatrices.nullspace); break; default: return INVALID_IDENTIFIER_ID; @@ -330,13 +330,13 @@ ReturnValue_t AcsParameters::getParameter(uint8_t domainId, uint8_t parameterId, parameterWrapper->set(safeModeControllerParameters.sunMagAngleMin); break; case 0x5: - parameterWrapper->set(safeModeControllerParameters.sunTargetDirLeop); + parameterWrapper->setVector(safeModeControllerParameters.sunTargetDirLeop); break; case 0x6: - parameterWrapper->set(safeModeControllerParameters.sunTargetDir); + parameterWrapper->setVector(safeModeControllerParameters.sunTargetDir); break; case 0x7: - parameterWrapper->set(safeModeControllerParameters.satRateRef); + parameterWrapper->setVector(safeModeControllerParameters.satRateRef); break; default: return INVALID_IDENTIFIER_ID; @@ -360,7 +360,7 @@ ReturnValue_t AcsParameters::getParameter(uint8_t domainId, uint8_t parameterId, parameterWrapper->set(targetModeControllerParameters.gainNullspace); break; case 0x5: - parameterWrapper->set(targetModeControllerParameters.desatMomentumRef); + parameterWrapper->setVector(targetModeControllerParameters.desatMomentumRef); break; case 0x6: parameterWrapper->set(targetModeControllerParameters.deSatGainFactor); @@ -394,7 +394,7 @@ ReturnValue_t AcsParameters::getParameter(uint8_t domainId, uint8_t parameterId, parameterWrapper->set(targetModeControllerParameters.gainNullspace); break; case 0x5: - parameterWrapper->set(targetModeControllerParameters.desatMomentumRef); + parameterWrapper->setVector(targetModeControllerParameters.desatMomentumRef); break; case 0x6: parameterWrapper->set(targetModeControllerParameters.deSatGainFactor); @@ -406,13 +406,13 @@ ReturnValue_t AcsParameters::getParameter(uint8_t domainId, uint8_t parameterId, parameterWrapper->set(targetModeControllerParameters.enableAntiStiction); break; case 0x9: - parameterWrapper->set(targetModeControllerParameters.refDirection); + parameterWrapper->setVector(targetModeControllerParameters.refDirection); break; case 0xA: - parameterWrapper->set(targetModeControllerParameters.refRotRate); + parameterWrapper->setVector(targetModeControllerParameters.refRotRate); break; case 0xB: - parameterWrapper->set(targetModeControllerParameters.quatRef); + parameterWrapper->setVector(targetModeControllerParameters.quatRef); break; case 0xC: parameterWrapper->set(targetModeControllerParameters.timeElapsedMax); @@ -460,7 +460,7 @@ ReturnValue_t AcsParameters::getParameter(uint8_t domainId, uint8_t parameterId, parameterWrapper->set(targetModeControllerParameters.gainNullspace); break; case 0x5: - parameterWrapper->set(targetModeControllerParameters.desatMomentumRef); + parameterWrapper->setVector(targetModeControllerParameters.desatMomentumRef); break; case 0x6: parameterWrapper->set(targetModeControllerParameters.deSatGainFactor); @@ -472,13 +472,13 @@ ReturnValue_t AcsParameters::getParameter(uint8_t domainId, uint8_t parameterId, parameterWrapper->set(targetModeControllerParameters.enableAntiStiction); break; case 0x9: - parameterWrapper->set(targetModeControllerParameters.refDirection); + parameterWrapper->setVector(targetModeControllerParameters.refDirection); break; case 0xA: - parameterWrapper->set(targetModeControllerParameters.refRotRate); + parameterWrapper->setVector(targetModeControllerParameters.refRotRate); break; case 0xB: - parameterWrapper->set(targetModeControllerParameters.quatRef); + parameterWrapper->setVector(targetModeControllerParameters.quatRef); break; case 0xC: parameterWrapper->set(targetModeControllerParameters.timeElapsedMax); @@ -514,7 +514,7 @@ ReturnValue_t AcsParameters::getParameter(uint8_t domainId, uint8_t parameterId, parameterWrapper->set(nadirModeControllerParameters.gainNullspace); break; case 0x5: - parameterWrapper->set(nadirModeControllerParameters.desatMomentumRef); + parameterWrapper->setVector(nadirModeControllerParameters.desatMomentumRef); break; case 0x6: parameterWrapper->set(nadirModeControllerParameters.deSatGainFactor); @@ -526,10 +526,10 @@ ReturnValue_t AcsParameters::getParameter(uint8_t domainId, uint8_t parameterId, parameterWrapper->set(nadirModeControllerParameters.enableAntiStiction); break; case 0x9: - parameterWrapper->set(nadirModeControllerParameters.refDirection); + parameterWrapper->setVector(nadirModeControllerParameters.refDirection); break; case 0xA: - parameterWrapper->set(nadirModeControllerParameters.quatRef); + parameterWrapper->setVector(nadirModeControllerParameters.quatRef); break; case 0xC: parameterWrapper->set(nadirModeControllerParameters.timeElapsedMax); @@ -556,7 +556,7 @@ ReturnValue_t AcsParameters::getParameter(uint8_t domainId, uint8_t parameterId, parameterWrapper->set(inertialModeControllerParameters.gainNullspace); break; case 0x5: - parameterWrapper->set(inertialModeControllerParameters.desatMomentumRef); + parameterWrapper->setVector(inertialModeControllerParameters.desatMomentumRef); break; case 0x6: parameterWrapper->set(inertialModeControllerParameters.deSatGainFactor); @@ -568,13 +568,13 @@ ReturnValue_t AcsParameters::getParameter(uint8_t domainId, uint8_t parameterId, parameterWrapper->set(inertialModeControllerParameters.enableAntiStiction); break; case 0x9: - parameterWrapper->set(inertialModeControllerParameters.tgtQuat); + parameterWrapper->setVector(inertialModeControllerParameters.tgtQuat); break; case 0xA: - parameterWrapper->set(inertialModeControllerParameters.refRotRate); + parameterWrapper->setVector(inertialModeControllerParameters.refRotRate); break; case 0xC: - parameterWrapper->set(inertialModeControllerParameters.quatRef); + parameterWrapper->setVector(inertialModeControllerParameters.quatRef); break; default: return INVALID_IDENTIFIER_ID; @@ -586,7 +586,7 @@ ReturnValue_t AcsParameters::getParameter(uint8_t domainId, uint8_t parameterId, parameterWrapper->set(strParameters.exclusionAngle); break; case 0x1: - parameterWrapper->set(strParameters.boresightAxis); + parameterWrapper->setVector(strParameters.boresightAxis); break; default: return INVALID_IDENTIFIER_ID; @@ -658,19 +658,19 @@ ReturnValue_t AcsParameters::getParameter(uint8_t domainId, uint8_t parameterId, case (0x12): // MagnetorquesParameter switch (parameterId) { case 0x0: - parameterWrapper->set(magnetorquesParameter.mtq0orientationMatrix); + parameterWrapper->setMatrix(magnetorquesParameter.mtq0orientationMatrix); break; case 0x1: - parameterWrapper->set(magnetorquesParameter.mtq1orientationMatrix); + parameterWrapper->setMatrix(magnetorquesParameter.mtq1orientationMatrix); break; case 0x2: - parameterWrapper->set(magnetorquesParameter.mtq2orientationMatrix); + parameterWrapper->setMatrix(magnetorquesParameter.mtq2orientationMatrix); break; case 0x3: - parameterWrapper->set(magnetorquesParameter.alignmentMatrixMtq); + parameterWrapper->setMatrix(magnetorquesParameter.alignmentMatrixMtq); break; case 0x4: - parameterWrapper->set(magnetorquesParameter.inverseAlignment); + parameterWrapper->setMatrix(magnetorquesParameter.inverseAlignment); break; case 0x5: parameterWrapper->set(magnetorquesParameter.DipolMax); From afb9303dcb5e54d90338f7d244a77c7dee71599d Mon Sep 17 00:00:00 2001 From: meggert Date: Mon, 27 Feb 2023 16:35:32 +0100 Subject: [PATCH 003/112] naming fixes --- mission/controller/acs/AcsParameters.cpp | 14 +++++++------- mission/controller/acs/AcsParameters.h | 6 +++--- mission/controller/acs/control/Detumble.cpp | 4 ++-- mission/controller/acs/control/Detumble.h | 2 +- 4 files changed, 13 insertions(+), 13 deletions(-) diff --git a/mission/controller/acs/AcsParameters.cpp b/mission/controller/acs/AcsParameters.cpp index 351601c3..459d5ee4 100644 --- a/mission/controller/acs/AcsParameters.cpp +++ b/mission/controller/acs/AcsParameters.cpp @@ -658,25 +658,25 @@ ReturnValue_t AcsParameters::getParameter(uint8_t domainId, uint8_t parameterId, case (0x12): // MagnetorquesParameter switch (parameterId) { case 0x0: - parameterWrapper->setMatrix(magnetorquesParameter.mtq0orientationMatrix); + parameterWrapper->setMatrix(magnetorquerParameter.mtq0orientationMatrix); break; case 0x1: - parameterWrapper->setMatrix(magnetorquesParameter.mtq1orientationMatrix); + parameterWrapper->setMatrix(magnetorquerParameter.mtq1orientationMatrix); break; case 0x2: - parameterWrapper->setMatrix(magnetorquesParameter.mtq2orientationMatrix); + parameterWrapper->setMatrix(magnetorquerParameter.mtq2orientationMatrix); break; case 0x3: - parameterWrapper->setMatrix(magnetorquesParameter.alignmentMatrixMtq); + parameterWrapper->setMatrix(magnetorquerParameter.alignmentMatrixMtq); break; case 0x4: - parameterWrapper->setMatrix(magnetorquesParameter.inverseAlignment); + parameterWrapper->setMatrix(magnetorquerParameter.inverseAlignment); break; case 0x5: - parameterWrapper->set(magnetorquesParameter.DipolMax); + parameterWrapper->set(magnetorquerParameter.dipolMax); break; case 0x6: - parameterWrapper->set(magnetorquesParameter.torqueDuration); + parameterWrapper->set(magnetorquerParameter.torqueDuration); break; default: return INVALID_IDENTIFIER_ID; diff --git a/mission/controller/acs/AcsParameters.h b/mission/controller/acs/AcsParameters.h index f44f4a61..ea867c65 100644 --- a/mission/controller/acs/AcsParameters.h +++ b/mission/controller/acs/AcsParameters.h @@ -912,16 +912,16 @@ class AcsParameters : public HasParametersIF { double sensorNoiseBsGYR = 3 * M_PI / 180 / 3600; // Bias Stability } kalmanFilterParameters; - struct MagnetorquesParameter { + struct MagnetorquerParameter { double mtq0orientationMatrix[3][3] = {{1, 0, 0}, {0, 0, 1}, {0, -1, 0}}; double mtq1orientationMatrix[3][3] = {{1, 0, 0}, {0, 1, 0}, {0, 0, 1}}; double mtq2orientationMatrix[3][3] = {{0, 0, 1}, {0, 1, 0}, {-1, 0, 0}}; double alignmentMatrixMtq[3][3] = {{0, 0, -1}, {-1, 0, 0}, {0, 1, 0}}; double inverseAlignment[3][3] = {{0, -1, 0}, {0, 0, 1}, {-1, 0, 0}}; - double DipolMax = 0.2; // [Am^2] + double dipolMax = 0.2; // [Am^2] uint16_t torqueDuration = 300; // [ms] - } magnetorquesParameter; + } magnetorquerParameter; struct DetumbleParameter { uint8_t detumblecounter = 75; // 30 s diff --git a/mission/controller/acs/control/Detumble.cpp b/mission/controller/acs/control/Detumble.cpp index 705bf599..222a0ec2 100644 --- a/mission/controller/acs/control/Detumble.cpp +++ b/mission/controller/acs/control/Detumble.cpp @@ -23,7 +23,7 @@ Detumble::~Detumble() {} void Detumble::loadAcsParameters(AcsParameters *acsParameters_) { detumbleParameter = &(acsParameters_->detumbleParameter); - magnetorquesParameter = &(acsParameters_->magnetorquesParameter); + magnetorquesParameter = &(acsParameters_->magnetorquerParameter); } ReturnValue_t Detumble::bDotLaw(const double *magRate, const bool magRateValid, @@ -43,7 +43,7 @@ ReturnValue_t Detumble::bangbangLaw(const double *magRate, const bool magRateVal return DETUMBLE_NO_SENSORDATA; } - double dipolMax = magnetorquesParameter->DipolMax; + double dipolMax = magnetorquesParameter->dipolMax; for (int i = 0; i < 3; i++) { magMom[i] = -dipolMax * sign(magRate[i]); } diff --git a/mission/controller/acs/control/Detumble.h b/mission/controller/acs/control/Detumble.h index 65e5ec28..dee82271 100644 --- a/mission/controller/acs/control/Detumble.h +++ b/mission/controller/acs/control/Detumble.h @@ -35,7 +35,7 @@ class Detumble { private: AcsParameters::DetumbleParameter *detumbleParameter; - AcsParameters::MagnetorquesParameter *magnetorquesParameter; + AcsParameters::MagnetorquerParameter *magnetorquesParameter; }; #endif /*ACS_CONTROL_DETUMBLE_H_*/ From fd4be08796cc1b1e94f2b00d8b623416c905098a Mon Sep 17 00:00:00 2001 From: meggert Date: Mon, 27 Feb 2023 16:37:09 +0100 Subject: [PATCH 004/112] removed instance of AcsParameters as part of actuatorCmd --- mission/controller/acs/ActuatorCmd.cpp | 25 ++++++++++++++----------- mission/controller/acs/ActuatorCmd.h | 12 +++++++----- 2 files changed, 21 insertions(+), 16 deletions(-) diff --git a/mission/controller/acs/ActuatorCmd.cpp b/mission/controller/acs/ActuatorCmd.cpp index 8cda84d6..7ea6d567 100644 --- a/mission/controller/acs/ActuatorCmd.cpp +++ b/mission/controller/acs/ActuatorCmd.cpp @@ -10,13 +10,14 @@ #include "util/CholeskyDecomposition.h" #include "util/MathOperations.h" -ActuatorCmd::ActuatorCmd(AcsParameters *acsParameters_) { acsParameters = *acsParameters_; } +ActuatorCmd::ActuatorCmd() {} ActuatorCmd::~ActuatorCmd() {} -void ActuatorCmd::scalingTorqueRws(const double *rwTrq, double *rwTrqScaled) { +void ActuatorCmd::scalingTorqueRws(const double *rwTrq, double *rwTrqScaled, + AcsParameters::RwHandlingParameters *rwHandlingParameters) { // Scaling the commanded torque to a maximum value - double maxTrq = acsParameters.rwHandlingParameters.maxTrq; + double maxTrq = rwHandlingParameters->maxTrq; double maxValue = 0; for (int i = 0; i < 4; i++) { // size of torque, always 4 ? @@ -33,17 +34,17 @@ void ActuatorCmd::scalingTorqueRws(const double *rwTrq, double *rwTrqScaled) { void ActuatorCmd::cmdSpeedToRws(const int32_t speedRw0, const int32_t speedRw1, const int32_t speedRw2, const int32_t speedRw3, - const double *rwTorque, int32_t *rwCmdSpeed) { + const double *rwTorque, int32_t *rwCmdSpeed, + AcsParameters *acsParameters) { using namespace Math; // Calculating the commanded speed in RPM for every reaction wheel int32_t speedRws[4] = {speedRw0, speedRw1, speedRw2, speedRw3}; double deltaSpeed[4] = {0, 0, 0, 0}; - double commandTime = acsParameters.onBoardParams.sampleTime, - inertiaWheel = acsParameters.rwHandlingParameters.inertiaWheel; double radToRpm = 60 / (2 * PI); // factor for conversion to RPM // W_RW = Torque_RW / I_RW * delta t [rad/s] - double factor = commandTime / inertiaWheel * radToRpm; + double factor = acsParameters->onBoardParams.sampleTime / + acsParameters->rwHandlingParameters.inertiaWheel * radToRpm; int32_t deltaSpeedInt[4] = {0, 0, 0, 0}; VectorOperations::mulScalar(rwTorque, factor, deltaSpeed, 4); for (int i = 0; i < 4; i++) { @@ -53,13 +54,15 @@ void ActuatorCmd::cmdSpeedToRws(const int32_t speedRw0, const int32_t speedRw1, VectorOperations::mulScalar(rwCmdSpeed, 10, rwCmdSpeed, 4); } -void ActuatorCmd::cmdDipolMtq(const double *dipolMoment, int16_t *dipolMomentActuator) { +void ActuatorCmd::cmdDipolMtq(const double *dipolMoment, int16_t *dipolMomentActuator, + AcsParameters::MagnetorquerParameter *magnetorquerParameter) { + sif::debug << magnetorquerParameter->dipolMax << std::endl; // Convert to actuator frame double dipolMomentActuatorDouble[3] = {0, 0, 0}; - MatrixOperations::multiply(*acsParameters.magnetorquesParameter.inverseAlignment, - dipolMoment, dipolMomentActuatorDouble, 3, 3, 1); + MatrixOperations::multiply(*magnetorquerParameter->inverseAlignment, dipolMoment, + dipolMomentActuatorDouble, 3, 3, 1); // Scaling along largest element if dipol exceeds maximum - double maxDipol = acsParameters.magnetorquesParameter.DipolMax; + double maxDipol = magnetorquerParameter->dipolMax; double maxValue = 0; for (int i = 0; i < 3; i++) { if (abs(dipolMomentActuator[i]) > maxDipol) { diff --git a/mission/controller/acs/ActuatorCmd.h b/mission/controller/acs/ActuatorCmd.h index 969bd782..ca0deb5b 100644 --- a/mission/controller/acs/ActuatorCmd.h +++ b/mission/controller/acs/ActuatorCmd.h @@ -8,7 +8,7 @@ class ActuatorCmd { public: - ActuatorCmd(AcsParameters *acsParameters_); // Input mode ? + ActuatorCmd(); // Input mode ? virtual ~ActuatorCmd(); /* @@ -17,7 +17,8 @@ class ActuatorCmd { * @param: rwTrq given torque for reaction wheels * rwTrqScaled possible scaled torque */ - void scalingTorqueRws(const double *rwTrq, double *rwTrqScaled); + void scalingTorqueRws(const double *rwTrq, double *rwTrqScaled, + AcsParameters::RwHandlingParameters *rwHandlingParameters); /* * @brief: cmdSpeedToRws() will set the maximum possible torque for the reaction @@ -29,7 +30,8 @@ class ActuatorCmd { * reaction wheel */ void cmdSpeedToRws(const int32_t speedRw0, const int32_t speedRw1, const int32_t speedRw2, - const int32_t speedRw3, const double *rwTorque, int32_t *rwCmdSpeed); + const int32_t speedRw3, const double *rwTorque, int32_t *rwCmdSpeed, + AcsParameters *acsParameters); /* * @brief: cmdDipolMtq() gives the commanded dipol moment for the magnetorques @@ -37,11 +39,11 @@ class ActuatorCmd { * @param: dipolMoment given dipol moment in spacecraft frame * dipolMomentActuator resulting dipol moment in actuator reference frame */ - void cmdDipolMtq(const double *dipolMoment, int16_t *dipolMomentActuator); + void cmdDipolMtq(const double *dipolMoment, int16_t *dipolMomentActuator, + AcsParameters::MagnetorquerParameter *magnetorquerParameter); protected: private: - AcsParameters acsParameters; }; #endif /* ACTUATORCMD_H_ */ From 92f5a8bf896ee840eeee202fb8e75b7f393ecf19 Mon Sep 17 00:00:00 2001 From: meggert Date: Mon, 27 Feb 2023 16:37:46 +0100 Subject: [PATCH 005/112] removed AcsParameters as part of Navigation --- .../acs/MultiplicativeKalmanFilter.cpp | 96 +++++++++---------- .../acs/MultiplicativeKalmanFilter.h | 22 ++--- mission/controller/acs/Navigation.cpp | 11 +-- mission/controller/acs/Navigation.h | 6 +- 4 files changed, 64 insertions(+), 71 deletions(-) diff --git a/mission/controller/acs/MultiplicativeKalmanFilter.cpp b/mission/controller/acs/MultiplicativeKalmanFilter.cpp index a700c6a6..77a3ef00 100644 --- a/mission/controller/acs/MultiplicativeKalmanFilter.cpp +++ b/mission/controller/acs/MultiplicativeKalmanFilter.cpp @@ -12,33 +12,22 @@ #include "util/CholeskyDecomposition.h" #include "util/MathOperations.h" -/*Initialisation of values for parameters in constructor*/ -MultiplicativeKalmanFilter::MultiplicativeKalmanFilter(AcsParameters *acsParameters_) - : initialQuaternion{0, 0, 0, 1}, - initialCovarianceMatrix{{0, 0, 0, 0, 0, 0}, {0, 0, 0, 0, 0, 0}, {0, 0, 0, 0, 0, 0}, - {0, 0, 0, 0, 0, 0}, {0, 0, 0, 0, 0, 0}, {0, 0, 0, 0, 0, 0}} { - loadAcsParameters(acsParameters_); -} +MultiplicativeKalmanFilter::MultiplicativeKalmanFilter() {} MultiplicativeKalmanFilter::~MultiplicativeKalmanFilter() {} -void MultiplicativeKalmanFilter::loadAcsParameters(AcsParameters *acsParameters_) { - inertiaEIVE = &(acsParameters_->inertiaEIVE); - kalmanFilterParameters = &(acsParameters_->kalmanFilterParameters); -} - ReturnValue_t MultiplicativeKalmanFilter::init( const double *magneticField_, const bool validMagField_, const double *sunDir_, const bool validSS, const double *sunDirJ, const bool validSSModel, const double *magFieldJ, - const bool validMagModel, acsctrl::MekfData *mekfData) { // valids for "model measurements"? + const bool validMagModel, acsctrl::MekfData *mekfData, + AcsParameters *acsParameters) { // valids for "model measurements"? // check for valid mag/sun if (validMagField_ && validSS && validSSModel && validMagModel) { - validInit = true; // QUEST ALGO ----------------------------------------------------------------------- double sigmaSun = 0, sigmaMag = 0, sigmaGyro = 0; - sigmaSun = kalmanFilterParameters->sensorNoiseSS; - sigmaMag = kalmanFilterParameters->sensorNoiseMAG; - sigmaGyro = kalmanFilterParameters->sensorNoiseGYR; + sigmaSun = acsParameters->kalmanFilterParameters.sensorNoiseSS; + sigmaMag = acsParameters->kalmanFilterParameters.sensorNoiseMAG; + sigmaGyro = acsParameters->kalmanFilterParameters.sensorNoiseGYR; double normMagB[3] = {0, 0, 0}, normSunB[3] = {0, 0, 0}, normMagJ[3] = {0, 0, 0}, normSunJ[3] = {0, 0, 0}; @@ -192,21 +181,18 @@ ReturnValue_t MultiplicativeKalmanFilter::init( return MEKF_INITIALIZED; } else { // no initialisation possible, no valid measurements - validInit = false; updateDataSetWithoutData(mekfData, MekfStatus::UNINITIALIZED); return MEKF_UNINITIALIZED; } } // --------------- MEKF DISCRETE TIME STEP ------------------------------- -ReturnValue_t MultiplicativeKalmanFilter::mekfEst(const double *quaternionSTR, const bool validSTR_, - const double *rateGYRs_, const bool validGYRs_, - const double *magneticField_, - const bool validMagField_, const double *sunDir_, - const bool validSS, const double *sunDirJ, - const bool validSSModel, const double *magFieldJ, - const bool validMagModel, double sampleTime, - acsctrl::MekfData *mekfData) { +ReturnValue_t MultiplicativeKalmanFilter::mekfEst( + const double *quaternionSTR, const bool validSTR_, const double *rateGYRs_, + const bool validGYRs_, const double *magneticField_, const bool validMagField_, + const double *sunDir_, const bool validSS, const double *sunDirJ, const bool validSSModel, + const double *magFieldJ, const bool validMagModel, acsctrl::MekfData *mekfData, + AcsParameters *acsParameters) { // Check for GYR Measurements int MDF = 0; // Matrix Dimension Factor if (!validGYRs_) { @@ -248,9 +234,9 @@ ReturnValue_t MultiplicativeKalmanFilter::mekfEst(const double *quaternionSTR, c // If we are here, MEKF will perform double sigmaSun = 0, sigmaMag = 0, sigmaStr = 0; - sigmaSun = kalmanFilterParameters->sensorNoiseSS; - sigmaMag = kalmanFilterParameters->sensorNoiseMAG; - sigmaStr = kalmanFilterParameters->sensorNoiseSTR; + sigmaSun = acsParameters->kalmanFilterParameters.sensorNoiseSS; + sigmaMag = acsParameters->kalmanFilterParameters.sensorNoiseMAG; + sigmaStr = acsParameters->kalmanFilterParameters.sensorNoiseSTR; double normMagB[3] = {0, 0, 0}, normSunB[3] = {0, 0, 0}, normMagJ[3] = {0, 0, 0}, normSunJ[3] = {0, 0, 0}; @@ -912,8 +898,8 @@ ReturnValue_t MultiplicativeKalmanFilter::mekfEst(const double *quaternionSTR, c biasGYR[2] = updatedGyroBias[2]; /* ----------- PROPAGATION ----------*/ - double sigmaU = kalmanFilterParameters->sensorNoiseBsGYR; - double sigmaV = kalmanFilterParameters->sensorNoiseArwGYR; + double sigmaU = acsParameters->kalmanFilterParameters.sensorNoiseBsGYR; + double sigmaV = acsParameters->kalmanFilterParameters.sensorNoiseArwGYR; double discTimeMatrix[6][6] = {{-1, 0, 0, 0, 0, 0}, {0, -1, 0, 0, 0, 0}, {0, 0, -1, 0, 0, 0}, {0, 0, 0, 1, 0, 0}, {0, 0, 0, 0, 1, 0}, {0, 0, 0, 0, 0, 1}}; @@ -931,27 +917,31 @@ ReturnValue_t MultiplicativeKalmanFilter::mekfEst(const double *quaternionSTR, c covQ12[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}, covQ22[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}, covQ12trans[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; - if (normRotEst * sampleTime < M_PI / 10) { - double fact11 = pow(sigmaV, 2) * sampleTime + 1. / 3. * pow(sigmaU, 2) * pow(sampleTime, 3); + if (normRotEst * acsParameters->onBoardParams.sampleTime < M_PI / 10) { + double fact11 = pow(sigmaV, 2) * acsParameters->onBoardParams.sampleTime + + 1. / 3. * pow(sigmaU, 2) * pow(acsParameters->onBoardParams.sampleTime, 3); MatrixOperations::multiplyScalar(*identityMatrix3, fact11, *covQ11, 3, 3); - double fact12 = -(1. / 2. * pow(sigmaU, 2) * pow(sampleTime, 2)); + double fact12 = -(1. / 2. * pow(sigmaU, 2) * pow(acsParameters->onBoardParams.sampleTime, 2)); MatrixOperations::multiplyScalar(*identityMatrix3, fact12, *covQ12, 3, 3); std::memcpy(*covQ12trans, *covQ12, 3 * 3 * sizeof(double)); - double fact22 = pow(sigmaU, 2) * sampleTime; + double fact22 = pow(sigmaU, 2) * acsParameters->onBoardParams.sampleTime; MatrixOperations::multiplyScalar(*identityMatrix3, fact22, *covQ22, 3, 3); } else { - double fact22 = pow(sigmaU, 2) * sampleTime; + double fact22 = pow(sigmaU, 2) * acsParameters->onBoardParams.sampleTime; MatrixOperations::multiplyScalar(*identityMatrix3, fact22, *covQ22, 3, 3); double covQ12_0[3][3], covQ12_1[3][3], covQ12_2[3][3], covQ12_01[3][3]; - double fact12_0 = (normRotEst * sampleTime - sin(normRotEst * sampleTime) / pow(normRotEst, 3)); + double fact12_0 = + (normRotEst * acsParameters->onBoardParams.sampleTime - + sin(normRotEst * acsParameters->onBoardParams.sampleTime) / pow(normRotEst, 3)); MatrixOperations::multiplyScalar(*crossRotEst, fact12_0, *covQ12_0, 3, 3); - double fact12_1 = 1. / 2. * pow(sampleTime, 2); + double fact12_1 = 1. / 2. * pow(acsParameters->onBoardParams.sampleTime, 2); MatrixOperations::multiplyScalar(*identityMatrix3, fact12_1, *covQ12_1, 3, 3); double fact12_2 = - (1. / 2. * pow(normRotEst, 2) * pow(sampleTime, 2) + cos(normRotEst * sampleTime) - 1) / + (1. / 2. * pow(normRotEst, 2) * pow(acsParameters->onBoardParams.sampleTime, 2) + + cos(normRotEst * acsParameters->onBoardParams.sampleTime) - 1) / pow(normRotEst, 4); MatrixOperations::multiply(*crossRotEst, *crossRotEst, *covQ12_2, 3, 3, 3); MatrixOperations::multiplyScalar(*covQ12_2, fact12_2, *covQ12_2, 3, 3); @@ -961,13 +951,15 @@ ReturnValue_t MultiplicativeKalmanFilter::mekfEst(const double *quaternionSTR, c MatrixOperations::transpose(*covQ12, *covQ12trans, 3); double covQ11_0[3][3], covQ11_1[3][3], covQ11_2[3][3], covQ11_12[3][3]; - double fact11_0 = pow(sigmaV, 2) * sampleTime; + double fact11_0 = pow(sigmaV, 2) * acsParameters->onBoardParams.sampleTime; MatrixOperations::multiplyScalar(*identityMatrix3, fact11_0, *covQ11_0, 3, 3); - double fact11_1 = 1. / 3. * pow(sampleTime, 3); + double fact11_1 = 1. / 3. * pow(acsParameters->onBoardParams.sampleTime, 3); MatrixOperations::multiplyScalar(*identityMatrix3, fact11_1, *covQ11_1, 3, 3); - double fact11_2 = (2 * normRotEst * sampleTime - 2 * sin(normRotEst * sampleTime) - - 1. / 3. * pow(normRotEst, 3) * pow(sampleTime, 3)) / - pow(normRotEst, 5); + double fact11_2 = + (2 * normRotEst * acsParameters->onBoardParams.sampleTime - + 2 * sin(normRotEst * acsParameters->onBoardParams.sampleTime) - + 1. / 3. * pow(normRotEst, 3) * pow(acsParameters->onBoardParams.sampleTime, 3)) / + pow(normRotEst, 5); MatrixOperations::multiply(*crossRotEst, *crossRotEst, *covQ11_2, 3, 3, 3); MatrixOperations::multiplyScalar(*covQ11_2, fact11_2, *covQ11_2, 3, 3); MatrixOperations::subtract(*covQ11_1, *covQ11_2, *covQ11_12, 3, 3); @@ -1017,9 +1009,10 @@ ReturnValue_t MultiplicativeKalmanFilter::mekfEst(const double *quaternionSTR, c phi[6][6] = {{0, 0, 0, 0, 0, 0}, {0, 0, 0, 0, 0, 0}, {0, 0, 0, 0, 0, 0}, {0, 0, 0, 1, 0, 0}, {0, 0, 0, 0, 1, 0}, {0, 0, 0, 0, 0, 1}}; double phi11_1[3][3], phi11_2[3][3], phi11_01[3][3]; - double fact11_1 = sin(normRotEst * sampleTime) / normRotEst; + double fact11_1 = sin(normRotEst * acsParameters->onBoardParams.sampleTime) / normRotEst; MatrixOperations::multiplyScalar(*crossRotEst, fact11_1, *phi11_1, 3, 3); - double fact11_2 = (1 - cos(normRotEst * sampleTime)) / pow(normRotEst, 2); + double fact11_2 = + (1 - cos(normRotEst * acsParameters->onBoardParams.sampleTime)) / pow(normRotEst, 2); MatrixOperations::multiply(*crossRotEst, *crossRotEst, *phi11_2, 3, 3, 3); MatrixOperations::multiplyScalar(*phi11_2, fact11_2, *phi11_2, 3, 3); MatrixOperations::subtract(*identityMatrix3, *phi11_1, *phi11_01, 3, 3); @@ -1028,8 +1021,11 @@ ReturnValue_t MultiplicativeKalmanFilter::mekfEst(const double *quaternionSTR, c double phi12_0[3][3], phi12_1[3][3], phi12_2[3][3], phi12_01[3][3]; double fact12_0 = fact11_2; MatrixOperations::multiplyScalar(*crossRotEst, fact12_0, *phi12_0, 3, 3); - MatrixOperations::multiplyScalar(*identityMatrix3, sampleTime, *phi12_1, 3, 3); - double fact12_2 = (normRotEst * sampleTime - sin(normRotEst * sampleTime) / pow(normRotEst, 3)); + MatrixOperations::multiplyScalar(*identityMatrix3, + acsParameters->onBoardParams.sampleTime, *phi12_1, 3, 3); + double fact12_2 = + (normRotEst * acsParameters->onBoardParams.sampleTime - + sin(normRotEst * acsParameters->onBoardParams.sampleTime) / pow(normRotEst, 3)); MatrixOperations::multiply(*crossRotEst, *crossRotEst, *phi12_2, 3, 3, 3); MatrixOperations::multiplyScalar(*phi12_2, fact12_2, *phi12_2, 3, 3); MatrixOperations::subtract(*phi12_0, *phi12_1, *phi12_01, 3, 3); @@ -1056,8 +1052,8 @@ ReturnValue_t MultiplicativeKalmanFilter::mekfEst(const double *quaternionSTR, c // Propagated Quaternion double rotSin[3] = {0, 0, 0}, rotCosMat[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; - double rotCos = cos(0.5 * normRotEst * sampleTime); - double sinFac = sin(0.5 * normRotEst * sampleTime) / normRotEst; + double rotCos = cos(0.5 * normRotEst * acsParameters->onBoardParams.sampleTime); + double sinFac = sin(0.5 * normRotEst * acsParameters->onBoardParams.sampleTime) / normRotEst; VectorOperations::mulScalar(rotRateEst, sinFac, rotSin, 3); double skewSin[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; diff --git a/mission/controller/acs/MultiplicativeKalmanFilter.h b/mission/controller/acs/MultiplicativeKalmanFilter.h index 47e1f807..3e9bfa49 100644 --- a/mission/controller/acs/MultiplicativeKalmanFilter.h +++ b/mission/controller/acs/MultiplicativeKalmanFilter.h @@ -17,9 +17,8 @@ class MultiplicativeKalmanFilter { */ public: /* @brief: Constructor - * @param: acsParameters_ Pointer to object which defines the ACS configuration parameters */ - MultiplicativeKalmanFilter(AcsParameters *acsParameters_); + MultiplicativeKalmanFilter(); virtual ~MultiplicativeKalmanFilter(); ReturnValue_t reset(acsctrl::MekfData *mekfData); @@ -33,8 +32,8 @@ class MultiplicativeKalmanFilter { */ ReturnValue_t init(const double *magneticField_, const bool validMagField_, const double *sunDir_, const bool validSS, const double *sunDirJ, const bool validSSModel, - const double *magFieldJ, const bool validMagModel, - acsctrl::MekfData *mekfData); + const double *magFieldJ, const bool validMagModel, acsctrl::MekfData *mekfData, + AcsParameters *acsParameters); /* @brief: mekfEst() - This function calculates the quaternion and gyro bias of the Kalman Filter * for the current step after the initalization @@ -54,7 +53,8 @@ class MultiplicativeKalmanFilter { const bool validGYRs_, const double *magneticField_, const bool validMagField_, const double *sunDir_, const bool validSS, const double *sunDirJ, const bool validSSModel, const double *magFieldJ, - const bool validMagModel, double sampleTime, acsctrl::MekfData *mekfData); + const bool validMagModel, acsctrl::MekfData *mekfData, + AcsParameters *acsParameters); enum MekfStatus : uint8_t { UNINITIALIZED = 0, @@ -79,23 +79,21 @@ class MultiplicativeKalmanFilter { private: /*Parameters*/ - AcsParameters::InertiaEIVE *inertiaEIVE; - AcsParameters::KalmanFilterParameters *kalmanFilterParameters; double quaternion_STR_SB[4]; - bool validInit; /*States*/ - double initialQuaternion[4]; /*after reset?QUEST*/ - double initialCovarianceMatrix[6][6]; /*after reset?QUEST*/ + double initialQuaternion[4] = {0, 0, 0, 1}; /*after reset?QUEST*/ + double initialCovarianceMatrix[6][6] = {{0, 0, 0, 0, 0, 0}, {0, 0, 0, 0, 0, 0}, + {0, 0, 0, 0, 0, 0}, {0, 0, 0, 0, 0, 0}, + {0, 0, 0, 0, 0, 0}, {0, 0, 0, 0, 0, 0}}; double propagatedQuaternion[4]; /*Filter Quaternion for next step*/ - uint8_t sensorsAvail; + uint8_t sensorsAvail = 0; /*Outputs*/ double quatBJ[4]; /* Output Quaternion */ double biasGYR[3]; /*Between measured and estimated sat Rate*/ /*Parameter INIT*/ /*Functions*/ - void loadAcsParameters(AcsParameters *acsParameters_); void updateDataSetWithoutData(acsctrl::MekfData *mekfData, MekfStatus mekfStatus); void updateDataSet(acsctrl::MekfData *mekfData, MekfStatus mekfStatus, double quat[4], double satRotRate[3]); diff --git a/mission/controller/acs/Navigation.cpp b/mission/controller/acs/Navigation.cpp index 03446609..9e8b3719 100644 --- a/mission/controller/acs/Navigation.cpp +++ b/mission/controller/acs/Navigation.cpp @@ -8,9 +8,7 @@ #include "util/CholeskyDecomposition.h" #include "util/MathOperations.h" -Navigation::Navigation(AcsParameters *acsParameters_) : multiplicativeKalmanFilter(acsParameters_) { - acsParameters = *acsParameters_; -} +Navigation::Navigation() {} Navigation::~Navigation() {} @@ -18,7 +16,7 @@ ReturnValue_t Navigation::useMekf(ACS::SensorValues *sensorValues, acsctrl::GyrDataProcessed *gyrDataProcessed, acsctrl::MgmDataProcessed *mgmDataProcessed, acsctrl::SusDataProcessed *susDataProcessed, - acsctrl::MekfData *mekfData) { + acsctrl::MekfData *mekfData, AcsParameters *acsParameters) { double quatIB[4] = {sensorValues->strSet.caliQx.value, sensorValues->strSet.caliQy.value, sensorValues->strSet.caliQz.value, sensorValues->strSet.caliQw.value}; bool quatIBValid = sensorValues->strSet.caliQx.isValid() && @@ -30,7 +28,8 @@ ReturnValue_t Navigation::useMekf(ACS::SensorValues *sensorValues, mgmDataProcessed->mgmVecTot.value, mgmDataProcessed->mgmVecTot.isValid(), susDataProcessed->susVecTot.value, susDataProcessed->susVecTot.isValid(), susDataProcessed->sunIjkModel.value, susDataProcessed->sunIjkModel.isValid(), - mgmDataProcessed->magIgrfModel.value, mgmDataProcessed->magIgrfModel.isValid(), mekfData); + mgmDataProcessed->magIgrfModel.value, mgmDataProcessed->magIgrfModel.isValid(), mekfData, + acsParameters); return mekfStatus; } else { mekfStatus = multiplicativeKalmanFilter.mekfEst( @@ -39,7 +38,7 @@ ReturnValue_t Navigation::useMekf(ACS::SensorValues *sensorValues, mgmDataProcessed->mgmVecTot.isValid(), susDataProcessed->susVecTot.value, susDataProcessed->susVecTot.isValid(), susDataProcessed->sunIjkModel.value, susDataProcessed->sunIjkModel.isValid(), mgmDataProcessed->magIgrfModel.value, - mgmDataProcessed->magIgrfModel.isValid(), acsParameters.onBoardParams.sampleTime, mekfData); + mgmDataProcessed->magIgrfModel.isValid(), mekfData, acsParameters); return mekfStatus; } } diff --git a/mission/controller/acs/Navigation.h b/mission/controller/acs/Navigation.h index cf9e81e3..b567fbdd 100644 --- a/mission/controller/acs/Navigation.h +++ b/mission/controller/acs/Navigation.h @@ -9,19 +9,19 @@ class Navigation { public: - Navigation(AcsParameters *acsParameters_); + Navigation(); virtual ~Navigation(); ReturnValue_t useMekf(ACS::SensorValues *sensorValues, acsctrl::GyrDataProcessed *gyrDataProcessed, acsctrl::MgmDataProcessed *mgmDataProcessed, - acsctrl::SusDataProcessed *susDataProcessed, acsctrl::MekfData *mekfData); + acsctrl::SusDataProcessed *susDataProcessed, acsctrl::MekfData *mekfData, + AcsParameters *acsParameters); void resetMekf(acsctrl::MekfData *mekfData); protected: private: MultiplicativeKalmanFilter multiplicativeKalmanFilter; - AcsParameters acsParameters; ReturnValue_t mekfStatus = MultiplicativeKalmanFilter::MEKF_UNINITIALIZED; }; From 12ac8f7c708a1fbdb20f093bce9bfeccb249548d Mon Sep 17 00:00:00 2001 From: meggert Date: Mon, 27 Feb 2023 16:38:59 +0100 Subject: [PATCH 006/112] removed AcsParameters as part of SensorProcessing --- mission/controller/acs/SensorProcessing.cpp | 5 +++-- mission/controller/acs/SensorProcessing.h | 3 +-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/mission/controller/acs/SensorProcessing.cpp b/mission/controller/acs/SensorProcessing.cpp index e268d786..466d9ed5 100644 --- a/mission/controller/acs/SensorProcessing.cpp +++ b/mission/controller/acs/SensorProcessing.cpp @@ -14,7 +14,7 @@ using namespace Math; -SensorProcessing::SensorProcessing(AcsParameters *acsParameters_) {} +SensorProcessing::SensorProcessing() {} SensorProcessing::~SensorProcessing() {} @@ -26,7 +26,8 @@ void SensorProcessing::processMgm(const float *mgm0Value, bool mgm0valid, const acsctrl::GpsDataProcessed *gpsDataProcessed, const double gpsAltitude, bool gpsValid, acsctrl::MgmDataProcessed *mgmDataProcessed) { - // ---------------- IGRF- 13 Implementation here ------------------------------------------------ + // ---------------- IGRF- 13 Implementation here + // ------------------------------------------------ double magIgrfModel[3] = {0.0, 0.0, 0.0}; if (gpsValid) { // Should be existing class object which will be called and modified here. diff --git a/mission/controller/acs/SensorProcessing.h b/mission/controller/acs/SensorProcessing.h index cdd29d8b..d845c2f3 100644 --- a/mission/controller/acs/SensorProcessing.h +++ b/mission/controller/acs/SensorProcessing.h @@ -15,7 +15,7 @@ class SensorProcessing { public: void reset(); - SensorProcessing(AcsParameters *acsParameters_); + SensorProcessing(); virtual ~SensorProcessing(); void process(timeval now, ACS::SensorValues *sensorValues, @@ -77,7 +77,6 @@ class SensorProcessing { bool validSavedPosSatE = false; SusConverter susConverter; - AcsParameters acsParameters; }; #endif /*SENSORPROCESSING_H_*/ From 7bf72e3c18ee97c07acc5a0c64ad684c7c3b5999 Mon Sep 17 00:00:00 2001 From: meggert Date: Mon, 27 Feb 2023 16:43:31 +0100 Subject: [PATCH 007/112] changelog --- CHANGELOG.md | 3 +++ 1 file changed, 3 insertions(+) diff --git a/CHANGELOG.md b/CHANGELOG.md index b078c4d7..9a4d88e0 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -20,6 +20,9 @@ will consitute of a breaking change warranting a new major release: - Linux GPS handler now checks the individual `*_SET` flags when analysing the `gpsd` struct. PR: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/400 +- Several `AcsController` components had their own implementation of `AcsParameters`. This resulted + in those parameters not being updated, while the actual ones were updated. All instances of + `AcsParameters` not belonging to `AcsController` are removed now. # [v1.32.0] From 309358f44708981a14f6ad03849dadd20e14f520 Mon Sep 17 00:00:00 2001 From: meggert Date: Mon, 27 Feb 2023 17:05:09 +0100 Subject: [PATCH 008/112] fixed updating wrong parameter set --- CHANGELOG.md | 5 +++- mission/controller/acs/AcsParameters.cpp | 34 ++++++++++-------------- 2 files changed, 18 insertions(+), 21 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 9a4d88e0..d96c36ab 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -22,7 +22,10 @@ will consitute of a breaking change warranting a new major release: PR: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/400 - Several `AcsController` components had their own implementation of `AcsParameters`. This resulted in those parameters not being updated, while the actual ones were updated. All instances of - `AcsParameters` not belonging to `AcsController` are removed now. + `AcsParameters` not belonging to `AcsController` are eiter removed or replaced by pointer + instances. +- Instead of updating the `gsTargetModeControllerParameters`, the `targetModeControllerParameters` + were updated. # [v1.32.0] diff --git a/mission/controller/acs/AcsParameters.cpp b/mission/controller/acs/AcsParameters.cpp index 459d5ee4..a19571eb 100644 --- a/mission/controller/acs/AcsParameters.cpp +++ b/mission/controller/acs/AcsParameters.cpp @@ -445,52 +445,46 @@ ReturnValue_t AcsParameters::getParameter(uint8_t domainId, uint8_t parameterId, case (0xB): // GsTargetModeControllerParameters switch (parameterId) { case 0x0: - parameterWrapper->set(targetModeControllerParameters.zeta); + parameterWrapper->set(gsTargetModeControllerParameters.zeta); break; case 0x1: - parameterWrapper->set(targetModeControllerParameters.om); + parameterWrapper->set(gsTargetModeControllerParameters.om); break; case 0x2: - parameterWrapper->set(targetModeControllerParameters.omMax); + parameterWrapper->set(gsTargetModeControllerParameters.omMax); break; case 0x3: - parameterWrapper->set(targetModeControllerParameters.qiMin); + parameterWrapper->set(gsTargetModeControllerParameters.qiMin); break; case 0x4: - parameterWrapper->set(targetModeControllerParameters.gainNullspace); + parameterWrapper->set(gsTargetModeControllerParameters.gainNullspace); break; case 0x5: - parameterWrapper->setVector(targetModeControllerParameters.desatMomentumRef); + parameterWrapper->setVector(gsTargetModeControllerParameters.desatMomentumRef); break; case 0x6: - parameterWrapper->set(targetModeControllerParameters.deSatGainFactor); + parameterWrapper->set(gsTargetModeControllerParameters.deSatGainFactor); break; case 0x7: - parameterWrapper->set(targetModeControllerParameters.desatOn); + parameterWrapper->set(gsTargetModeControllerParameters.desatOn); break; case 0x8: - parameterWrapper->set(targetModeControllerParameters.enableAntiStiction); + parameterWrapper->set(gsTargetModeControllerParameters.enableAntiStiction); break; case 0x9: - parameterWrapper->setVector(targetModeControllerParameters.refDirection); + parameterWrapper->setVector(gsTargetModeControllerParameters.refDirection); break; case 0xA: - parameterWrapper->setVector(targetModeControllerParameters.refRotRate); + parameterWrapper->set(gsTargetModeControllerParameters.timeElapsedMax); break; case 0xB: - parameterWrapper->setVector(targetModeControllerParameters.quatRef); + parameterWrapper->set(gsTargetModeControllerParameters.latitudeTgt); break; case 0xC: - parameterWrapper->set(targetModeControllerParameters.timeElapsedMax); + parameterWrapper->set(gsTargetModeControllerParameters.longitudeTgt); break; case 0xD: - parameterWrapper->set(targetModeControllerParameters.latitudeTgt); - break; - case 0xE: - parameterWrapper->set(targetModeControllerParameters.longitudeTgt); - break; - case 0xF: - parameterWrapper->set(targetModeControllerParameters.altitudeTgt); + parameterWrapper->set(gsTargetModeControllerParameters.altitudeTgt); break; default: return INVALID_IDENTIFIER_ID; From 5c30adb9bb9f4f8fecc1d6aa27de39ce404b5100 Mon Sep 17 00:00:00 2001 From: meggert Date: Mon, 27 Feb 2023 17:08:48 +0100 Subject: [PATCH 009/112] changed AcsParameters instance in guidance to const pointer --- mission/controller/AcsController.cpp | 33 ++++++------- mission/controller/acs/ActuatorCmd.cpp | 1 - mission/controller/acs/Guidance.cpp | 67 +++++++++++++------------- mission/controller/acs/Guidance.h | 3 +- 4 files changed, 51 insertions(+), 53 deletions(-) diff --git a/mission/controller/AcsController.cpp b/mission/controller/AcsController.cpp index f3269285..b056f093 100644 --- a/mission/controller/AcsController.cpp +++ b/mission/controller/AcsController.cpp @@ -6,9 +6,6 @@ AcsController::AcsController(object_id_t objectId) : ExtendedControllerBase(objectId), - sensorProcessing(&acsParameters), - navigation(&acsParameters), - actuatorCmd(&acsParameters), guidance(&acsParameters), safeCtrl(&acsParameters), detumble(&acsParameters), @@ -142,7 +139,7 @@ void AcsController::performSafe() { sensorProcessing.process(now, &sensorValues, &mgmDataProcessed, &susDataProcessed, &gyrDataProcessed, &gpsDataProcessed, &acsParameters); ReturnValue_t result = navigation.useMekf(&sensorValues, &gyrDataProcessed, &mgmDataProcessed, - &susDataProcessed, &mekfData); + &susDataProcessed, &mekfData, &acsParameters); if (result != MultiplicativeKalmanFilter::MEKF_RUNNING && result != MultiplicativeKalmanFilter::MEKF_INITIALIZED) { if (not mekfInvalidFlag) { @@ -173,7 +170,7 @@ void AcsController::performSafe() { sunTargetDir, satRateSafe, &errAng, magMomMtq, &magMomMtqValid); } - actuatorCmd.cmdDipolMtq(magMomMtq, cmdDipolMtqs); + actuatorCmd.cmdDipolMtq(magMomMtq, cmdDipolMtqs, &acsParameters.magnetorquerParameter); // detumble check and switch if (mekfData.satRotRateMekf.isValid() && @@ -207,7 +204,7 @@ void AcsController::performDetumble() { sensorProcessing.process(now, &sensorValues, &mgmDataProcessed, &susDataProcessed, &gyrDataProcessed, &gpsDataProcessed, &acsParameters); ReturnValue_t result = navigation.useMekf(&sensorValues, &gyrDataProcessed, &mgmDataProcessed, - &susDataProcessed, &mekfData); + &susDataProcessed, &mekfData, &acsParameters); if (result != MultiplicativeKalmanFilter::MEKF_RUNNING && result != MultiplicativeKalmanFilter::MEKF_INITIALIZED) { if (not mekfInvalidFlag) { @@ -221,7 +218,7 @@ void AcsController::performDetumble() { detumble.bDotLaw(mgmDataProcessed.mgmVecTotDerivative.value, mgmDataProcessed.mgmVecTotDerivative.isValid(), mgmDataProcessed.mgmVecTot.value, mgmDataProcessed.mgmVecTot.isValid(), magMomMtq); - actuatorCmd.cmdDipolMtq(magMomMtq, cmdDipolMtqs); + actuatorCmd.cmdDipolMtq(magMomMtq, cmdDipolMtqs, &acsParameters.magnetorquerParameter); if (mekfData.satRotRateMekf.isValid() && VectorOperations::norm(mekfData.satRotRateMekf.value, 3) < @@ -254,7 +251,7 @@ void AcsController::performPointingCtrl() { sensorProcessing.process(now, &sensorValues, &mgmDataProcessed, &susDataProcessed, &gyrDataProcessed, &gpsDataProcessed, &acsParameters); ReturnValue_t result = navigation.useMekf(&sensorValues, &gyrDataProcessed, &mgmDataProcessed, - &susDataProcessed, &mekfData); + &susDataProcessed, &mekfData, &acsParameters); if (result != MultiplicativeKalmanFilter::MEKF_RUNNING && result != MultiplicativeKalmanFilter::MEKF_INITIALIZED) { if (not mekfInvalidFlag) { @@ -303,7 +300,7 @@ void AcsController::performPointingCtrl() { &(sensorValues.rw2Set.currSpeed.value), &(sensorValues.rw3Set.currSpeed.value), &(sensorValues.rw4Set.currSpeed.value), rwTrqNs); VectorOperations::add(torquePtgRws, rwTrqNs, torqueRws, 4); - actuatorCmd.scalingTorqueRws(torqueRws, torqueRwsScaled); + actuatorCmd.scalingTorqueRws(torqueRws, torqueRwsScaled, &acsParameters.rwHandlingParameters); ptgCtrl.ptgDesaturation( &acsParameters.idleModeControllerParameters, mgmDataProcessed.mgmVecTot.value, mgmDataProcessed.mgmVecTot.isValid(), mekfData.satRotRateMekf.value, @@ -327,7 +324,7 @@ void AcsController::performPointingCtrl() { &(sensorValues.rw2Set.currSpeed.value), &(sensorValues.rw3Set.currSpeed.value), &(sensorValues.rw4Set.currSpeed.value), rwTrqNs); VectorOperations::add(torquePtgRws, rwTrqNs, torqueRws, 4); - actuatorCmd.scalingTorqueRws(torqueRws, torqueRwsScaled); + actuatorCmd.scalingTorqueRws(torqueRws, torqueRwsScaled, &acsParameters.rwHandlingParameters); ptgCtrl.ptgDesaturation( &acsParameters.targetModeControllerParameters, mgmDataProcessed.mgmVecTot.value, mgmDataProcessed.mgmVecTot.isValid(), mekfData.satRotRateMekf.value, @@ -348,7 +345,7 @@ void AcsController::performPointingCtrl() { &(sensorValues.rw2Set.currSpeed.value), &(sensorValues.rw3Set.currSpeed.value), &(sensorValues.rw4Set.currSpeed.value), rwTrqNs); VectorOperations::add(torquePtgRws, rwTrqNs, torqueRws, 4); - actuatorCmd.scalingTorqueRws(torqueRws, torqueRwsScaled); + actuatorCmd.scalingTorqueRws(torqueRws, torqueRwsScaled, &acsParameters.rwHandlingParameters); ptgCtrl.ptgDesaturation( &acsParameters.targetModeControllerParameters, mgmDataProcessed.mgmVecTot.value, mgmDataProcessed.mgmVecTot.isValid(), mekfData.satRotRateMekf.value, @@ -372,7 +369,7 @@ void AcsController::performPointingCtrl() { &(sensorValues.rw2Set.currSpeed.value), &(sensorValues.rw3Set.currSpeed.value), &(sensorValues.rw4Set.currSpeed.value), rwTrqNs); VectorOperations::add(torquePtgRws, rwTrqNs, torqueRws, 4); - actuatorCmd.scalingTorqueRws(torqueRws, torqueRwsScaled); + actuatorCmd.scalingTorqueRws(torqueRws, torqueRwsScaled, &acsParameters.rwHandlingParameters); ptgCtrl.ptgDesaturation( &acsParameters.nadirModeControllerParameters, mgmDataProcessed.mgmVecTot.value, mgmDataProcessed.mgmVecTot.isValid(), mekfData.satRotRateMekf.value, @@ -395,7 +392,7 @@ void AcsController::performPointingCtrl() { &(sensorValues.rw2Set.currSpeed.value), &(sensorValues.rw3Set.currSpeed.value), &(sensorValues.rw4Set.currSpeed.value), rwTrqNs); VectorOperations::add(torquePtgRws, rwTrqNs, torqueRws, 4); - actuatorCmd.scalingTorqueRws(torqueRws, torqueRwsScaled); + actuatorCmd.scalingTorqueRws(torqueRws, torqueRwsScaled, &acsParameters.rwHandlingParameters); ptgCtrl.ptgDesaturation( &acsParameters.inertialModeControllerParameters, mgmDataProcessed.mgmVecTot.value, mgmDataProcessed.mgmVecTot.isValid(), mekfData.satRotRateMekf.value, @@ -409,11 +406,11 @@ void AcsController::performPointingCtrl() { ptgCtrl.rwAntistiction(&sensorValues, torqueRwsScaled); } - actuatorCmd.cmdSpeedToRws(sensorValues.rw1Set.currSpeed.value, - sensorValues.rw2Set.currSpeed.value, - sensorValues.rw3Set.currSpeed.value, - sensorValues.rw4Set.currSpeed.value, torqueRwsScaled, cmdSpeedRws); - actuatorCmd.cmdDipolMtq(mgtDpDes, cmdDipolMtqs); + actuatorCmd.cmdSpeedToRws( + sensorValues.rw1Set.currSpeed.value, sensorValues.rw2Set.currSpeed.value, + sensorValues.rw3Set.currSpeed.value, sensorValues.rw4Set.currSpeed.value, torqueRwsScaled, + cmdSpeedRws, &acsParameters); + actuatorCmd.cmdDipolMtq(mgtDpDes, cmdDipolMtqs, &acsParameters.magnetorquerParameter); updateCtrlValData(targetQuat, errorQuat, errorAngle, targetSatRotRate); updateActuatorCmdData(rwTrqNs, cmdSpeedRws, cmdDipolMtqs); diff --git a/mission/controller/acs/ActuatorCmd.cpp b/mission/controller/acs/ActuatorCmd.cpp index 7ea6d567..7173151d 100644 --- a/mission/controller/acs/ActuatorCmd.cpp +++ b/mission/controller/acs/ActuatorCmd.cpp @@ -56,7 +56,6 @@ void ActuatorCmd::cmdSpeedToRws(const int32_t speedRw0, const int32_t speedRw1, void ActuatorCmd::cmdDipolMtq(const double *dipolMoment, int16_t *dipolMomentActuator, AcsParameters::MagnetorquerParameter *magnetorquerParameter) { - sif::debug << magnetorquerParameter->dipolMax << std::endl; // Convert to actuator frame double dipolMomentActuatorDouble[3] = {0, 0, 0}; MatrixOperations::multiply(*magnetorquerParameter->inverseAlignment, dipolMoment, diff --git a/mission/controller/acs/Guidance.cpp b/mission/controller/acs/Guidance.cpp index 09f0be20..9e9c04f9 100644 --- a/mission/controller/acs/Guidance.cpp +++ b/mission/controller/acs/Guidance.cpp @@ -12,7 +12,7 @@ #include "util/CholeskyDecomposition.h" #include "util/MathOperations.h" -Guidance::Guidance(AcsParameters *acsParameters_) : acsParameters(*acsParameters_) {} +Guidance::Guidance(AcsParameters *acsParameters_) { acsParameters = acsParameters_; } Guidance::~Guidance() {} @@ -26,9 +26,9 @@ void Guidance::targetQuatPtgSingleAxis(timeval now, double posSatE[3], double ve double targetE[3] = {0, 0, 0}; MathOperations::cartesianFromLatLongAlt( - acsParameters.targetModeControllerParameters.latitudeTgt, - acsParameters.targetModeControllerParameters.longitudeTgt, - acsParameters.targetModeControllerParameters.altitudeTgt, targetE); + acsParameters->targetModeControllerParameters.latitudeTgt, + acsParameters->targetModeControllerParameters.longitudeTgt, + acsParameters->targetModeControllerParameters.altitudeTgt, targetE); // target direction in the ECEF frame double targetDirE[3] = {0, 0, 0}; @@ -57,9 +57,9 @@ void Guidance::targetQuatPtgSingleAxis(timeval now, double posSatE[3], double ve // rotation quaternion from two vectors double refDir[3] = {0, 0, 0}; - refDir[0] = acsParameters.targetModeControllerParameters.refDirection[0]; - refDir[1] = acsParameters.targetModeControllerParameters.refDirection[1]; - refDir[2] = acsParameters.targetModeControllerParameters.refDirection[2]; + refDir[0] = acsParameters->targetModeControllerParameters.refDirection[0]; + refDir[1] = acsParameters->targetModeControllerParameters.refDirection[1]; + refDir[2] = acsParameters->targetModeControllerParameters.refDirection[2]; double noramlizedTargetDirB[3] = {0, 0, 0}; VectorOperations::normalize(targetDirB, noramlizedTargetDirB, 3); VectorOperations::normalize(refDir, refDir, 3); @@ -96,15 +96,15 @@ void Guidance::targetQuatPtgSingleAxis(timeval now, double posSatE[3], double ve //------------------------------------------------------------------------------------- // Calculation of reference rotation rate in case of star tracker blinding //------------------------------------------------------------------------------------- - if (acsParameters.targetModeControllerParameters.avoidBlindStr) { + if (acsParameters->targetModeControllerParameters.avoidBlindStr) { double sunDirB[3] = {0, 0, 0}; MatrixOperations::multiply(*dcmBI, sunDirI, sunDirB, 3, 3, 1); - double exclAngle = acsParameters.strParameters.exclusionAngle, - blindStart = acsParameters.targetModeControllerParameters.blindAvoidStart, - blindEnd = acsParameters.targetModeControllerParameters.blindAvoidStop; + double exclAngle = acsParameters->strParameters.exclusionAngle, + blindStart = acsParameters->targetModeControllerParameters.blindAvoidStart, + blindEnd = acsParameters->targetModeControllerParameters.blindAvoidStop; double sightAngleSun = - VectorOperations::dot(acsParameters.strParameters.boresightAxis, sunDirB); + VectorOperations::dot(acsParameters->strParameters.boresightAxis, sunDirB); if (!(strBlindAvoidFlag)) { double critSightAngle = blindStart * exclAngle; @@ -113,7 +113,7 @@ void Guidance::targetQuatPtgSingleAxis(timeval now, double posSatE[3], double ve } } else { if (sightAngleSun < blindEnd * exclAngle) { - double normBlindRefRate = acsParameters.targetModeControllerParameters.blindRotRate; + double normBlindRefRate = acsParameters->targetModeControllerParameters.blindRotRate; double blindRefRate[3] = {0, 0, 0}; if (sunDirB[1] < 0) { blindRefRate[0] = normBlindRefRate; @@ -144,9 +144,9 @@ void Guidance::targetQuatPtgThreeAxes(timeval now, double posSatE[3], double vel // transform longitude, latitude and altitude to cartesian coordiantes (ECEF) double targetE[3] = {0, 0, 0}; MathOperations::cartesianFromLatLongAlt( - acsParameters.targetModeControllerParameters.latitudeTgt, - acsParameters.targetModeControllerParameters.longitudeTgt, - acsParameters.targetModeControllerParameters.altitudeTgt, targetE); + acsParameters->targetModeControllerParameters.latitudeTgt, + acsParameters->targetModeControllerParameters.longitudeTgt, + acsParameters->targetModeControllerParameters.altitudeTgt, targetE); double targetDirE[3] = {0, 0, 0}; VectorOperations::subtract(targetE, posSatE, targetDirE, 3); @@ -198,12 +198,13 @@ void Guidance::targetQuatPtgThreeAxes(timeval now, double posSatE[3], double vel {xAxis[2], yAxis[2], zAxis[2]}}; QuaternionOperations::fromDcm(dcmIX, targetQuat); - int8_t timeElapsedMax = acsParameters.targetModeControllerParameters.timeElapsedMax; + int8_t timeElapsedMax = acsParameters->targetModeControllerParameters.timeElapsedMax; targetRotationRate(timeElapsedMax, now, targetQuat, targetSatRotRate); } void Guidance::targetQuatPtgGs(timeval now, double posSatE[3], double sunDirI[3], double targetQuat[4], double targetSatRotRate[3]) { + sif::debug << acsParameters->gsTargetModeControllerParameters.altitudeTgt << std::endl; //------------------------------------------------------------------------------------- // Calculation of target quaternion for ground station pointing //------------------------------------------------------------------------------------- @@ -211,9 +212,9 @@ void Guidance::targetQuatPtgGs(timeval now, double posSatE[3], double sunDirI[3] double groundStationE[3] = {0, 0, 0}; MathOperations::cartesianFromLatLongAlt( - acsParameters.gsTargetModeControllerParameters.latitudeTgt, - acsParameters.gsTargetModeControllerParameters.longitudeTgt, - acsParameters.gsTargetModeControllerParameters.altitudeTgt, groundStationE); + acsParameters->gsTargetModeControllerParameters.latitudeTgt, + acsParameters->gsTargetModeControllerParameters.longitudeTgt, + acsParameters->gsTargetModeControllerParameters.altitudeTgt, groundStationE); double targetDirE[3] = {0, 0, 0}; VectorOperations::subtract(groundStationE, posSatE, targetDirE, 3); @@ -262,7 +263,7 @@ void Guidance::targetQuatPtgGs(timeval now, double posSatE[3], double sunDirI[3] {xAxis[2], yAxis[2], zAxis[2]}}; QuaternionOperations::fromDcm(dcmTgt, targetQuat); - int8_t timeElapsedMax = acsParameters.gsTargetModeControllerParameters.timeElapsedMax; + int8_t timeElapsedMax = acsParameters->gsTargetModeControllerParameters.timeElapsedMax; targetRotationRate(timeElapsedMax, now, targetQuat, targetSatRotRate); } @@ -332,9 +333,9 @@ void Guidance::targetQuatPtgNadirSingleAxis(timeval now, double posSatE[3], doub // rotation quaternion from two vectors double refDir[3] = {0, 0, 0}; - refDir[0] = acsParameters.nadirModeControllerParameters.refDirection[0]; - refDir[1] = acsParameters.nadirModeControllerParameters.refDirection[1]; - refDir[2] = acsParameters.nadirModeControllerParameters.refDirection[2]; + refDir[0] = acsParameters->nadirModeControllerParameters.refDirection[0]; + refDir[1] = acsParameters->nadirModeControllerParameters.refDirection[1]; + refDir[2] = acsParameters->nadirModeControllerParameters.refDirection[2]; double noramlizedTargetDirB[3] = {0, 0, 0}; VectorOperations::normalize(targetDirB, noramlizedTargetDirB, 3); VectorOperations::normalize(refDir, refDir, 3); @@ -406,7 +407,7 @@ void Guidance::targetQuatPtgNadirThreeAxes(timeval now, double posSatE[3], doubl {xAxis[2], yAxis[2], zAxis[2]}}; QuaternionOperations::fromDcm(dcmTgt, targetQuat); - int8_t timeElapsedMax = acsParameters.nadirModeControllerParameters.timeElapsedMax; + int8_t timeElapsedMax = acsParameters->nadirModeControllerParameters.timeElapsedMax; targetRotationRate(timeElapsedMax, now, targetQuat, refSatRate); } @@ -516,19 +517,19 @@ ReturnValue_t Guidance::getDistributionMatrixRw(ACS::SensorValues *sensorValues, bool rw4valid = (sensorValues->rw4Set.state.value && sensorValues->rw4Set.state.isValid()); if (rw1valid && rw2valid && rw3valid && rw4valid) { - std::memcpy(rwPseudoInv, acsParameters.rwMatrices.pseudoInverse, 12 * sizeof(double)); + std::memcpy(rwPseudoInv, acsParameters->rwMatrices.pseudoInverse, 12 * sizeof(double)); return returnvalue::OK; } else if (!rw1valid && rw2valid && rw3valid && rw4valid) { - std::memcpy(rwPseudoInv, acsParameters.rwMatrices.without1, 12 * sizeof(double)); + std::memcpy(rwPseudoInv, acsParameters->rwMatrices.without1, 12 * sizeof(double)); return returnvalue::OK; } else if (rw1valid && !rw2valid && rw3valid && rw4valid) { - std::memcpy(rwPseudoInv, acsParameters.rwMatrices.without2, 12 * sizeof(double)); + std::memcpy(rwPseudoInv, acsParameters->rwMatrices.without2, 12 * sizeof(double)); return returnvalue::OK; } else if (rw1valid && rw2valid && !rw3valid && rw4valid) { - std::memcpy(rwPseudoInv, acsParameters.rwMatrices.without3, 12 * sizeof(double)); + std::memcpy(rwPseudoInv, acsParameters->rwMatrices.without3, 12 * sizeof(double)); return returnvalue::OK; } else if (rw1valid && rw2valid && rw3valid && !rw4valid) { - std::memcpy(rwPseudoInv, acsParameters.rwMatrices.without4, 12 * sizeof(double)); + std::memcpy(rwPseudoInv, acsParameters->rwMatrices.without4, 12 * sizeof(double)); return returnvalue::OK; } else { // @note: This one takes the normal pseudoInverse of all four raction wheels valid. @@ -542,13 +543,13 @@ ReturnValue_t Guidance::getDistributionMatrixRw(ACS::SensorValues *sensorValues, void Guidance::getTargetParamsSafe(double sunTargetSafe[3], double satRateSafe[3]) { if (not std::filesystem::exists(SD_0_SKEWED_PTG_FILE) or not std::filesystem::exists(SD_1_SKEWED_PTG_FILE)) { // ToDo: if file does not exist anymore - std::memcpy(sunTargetSafe, acsParameters.safeModeControllerParameters.sunTargetDir, + std::memcpy(sunTargetSafe, acsParameters->safeModeControllerParameters.sunTargetDir, 3 * sizeof(double)); } else { - std::memcpy(sunTargetSafe, acsParameters.safeModeControllerParameters.sunTargetDirLeop, + std::memcpy(sunTargetSafe, acsParameters->safeModeControllerParameters.sunTargetDirLeop, 3 * sizeof(double)); } - std::memcpy(satRateSafe, acsParameters.safeModeControllerParameters.satRateRef, + std::memcpy(satRateSafe, acsParameters->safeModeControllerParameters.satRateRef, 3 * sizeof(double)); } diff --git a/mission/controller/acs/Guidance.h b/mission/controller/acs/Guidance.h index da9d429b..c7f465f8 100644 --- a/mission/controller/acs/Guidance.h +++ b/mission/controller/acs/Guidance.h @@ -55,7 +55,8 @@ class Guidance { ReturnValue_t getDistributionMatrixRw(ACS::SensorValues *sensorValues, double *rwPseudoInv); private: - AcsParameters acsParameters; + const AcsParameters *acsParameters; + bool strBlindAvoidFlag = false; timeval timeSavedQuaternion; double savedQuaternion[4] = {0, 0, 0, 0}; From 26369039dada40cba14c824a606f8de523a3a159 Mon Sep 17 00:00:00 2001 From: meggert Date: Mon, 27 Feb 2023 17:36:33 +0100 Subject: [PATCH 010/112] better solution for actuatorCmd --- mission/controller/AcsController.cpp | 30 ++++++++++++++++++-------- mission/controller/acs/ActuatorCmd.cpp | 27 +++++++++-------------- mission/controller/acs/ActuatorCmd.h | 14 ++++++------ 3 files changed, 37 insertions(+), 34 deletions(-) diff --git a/mission/controller/AcsController.cpp b/mission/controller/AcsController.cpp index b056f093..d6d2fab6 100644 --- a/mission/controller/AcsController.cpp +++ b/mission/controller/AcsController.cpp @@ -170,7 +170,9 @@ void AcsController::performSafe() { sunTargetDir, satRateSafe, &errAng, magMomMtq, &magMomMtqValid); } - actuatorCmd.cmdDipolMtq(magMomMtq, cmdDipolMtqs, &acsParameters.magnetorquerParameter); + actuatorCmd.cmdDipolMtq(magMomMtq, cmdDipolMtqs, + *acsParameters.magnetorquerParameter.inverseAlignment, + acsParameters.magnetorquerParameter.dipolMax); // detumble check and switch if (mekfData.satRotRateMekf.isValid() && @@ -218,7 +220,9 @@ void AcsController::performDetumble() { detumble.bDotLaw(mgmDataProcessed.mgmVecTotDerivative.value, mgmDataProcessed.mgmVecTotDerivative.isValid(), mgmDataProcessed.mgmVecTot.value, mgmDataProcessed.mgmVecTot.isValid(), magMomMtq); - actuatorCmd.cmdDipolMtq(magMomMtq, cmdDipolMtqs, &acsParameters.magnetorquerParameter); + actuatorCmd.cmdDipolMtq(magMomMtq, cmdDipolMtqs, + *acsParameters.magnetorquerParameter.inverseAlignment, + acsParameters.magnetorquerParameter.dipolMax); if (mekfData.satRotRateMekf.isValid() && VectorOperations::norm(mekfData.satRotRateMekf.value, 3) < @@ -300,7 +304,8 @@ void AcsController::performPointingCtrl() { &(sensorValues.rw2Set.currSpeed.value), &(sensorValues.rw3Set.currSpeed.value), &(sensorValues.rw4Set.currSpeed.value), rwTrqNs); VectorOperations::add(torquePtgRws, rwTrqNs, torqueRws, 4); - actuatorCmd.scalingTorqueRws(torqueRws, torqueRwsScaled, &acsParameters.rwHandlingParameters); + actuatorCmd.scalingTorqueRws(torqueRws, torqueRwsScaled, + acsParameters.rwHandlingParameters.maxTrq); ptgCtrl.ptgDesaturation( &acsParameters.idleModeControllerParameters, mgmDataProcessed.mgmVecTot.value, mgmDataProcessed.mgmVecTot.isValid(), mekfData.satRotRateMekf.value, @@ -324,7 +329,8 @@ void AcsController::performPointingCtrl() { &(sensorValues.rw2Set.currSpeed.value), &(sensorValues.rw3Set.currSpeed.value), &(sensorValues.rw4Set.currSpeed.value), rwTrqNs); VectorOperations::add(torquePtgRws, rwTrqNs, torqueRws, 4); - actuatorCmd.scalingTorqueRws(torqueRws, torqueRwsScaled, &acsParameters.rwHandlingParameters); + actuatorCmd.scalingTorqueRws(torqueRws, torqueRwsScaled, + acsParameters.rwHandlingParameters.maxTrq); ptgCtrl.ptgDesaturation( &acsParameters.targetModeControllerParameters, mgmDataProcessed.mgmVecTot.value, mgmDataProcessed.mgmVecTot.isValid(), mekfData.satRotRateMekf.value, @@ -345,7 +351,8 @@ void AcsController::performPointingCtrl() { &(sensorValues.rw2Set.currSpeed.value), &(sensorValues.rw3Set.currSpeed.value), &(sensorValues.rw4Set.currSpeed.value), rwTrqNs); VectorOperations::add(torquePtgRws, rwTrqNs, torqueRws, 4); - actuatorCmd.scalingTorqueRws(torqueRws, torqueRwsScaled, &acsParameters.rwHandlingParameters); + actuatorCmd.scalingTorqueRws(torqueRws, torqueRwsScaled, + acsParameters.rwHandlingParameters.maxTrq); ptgCtrl.ptgDesaturation( &acsParameters.targetModeControllerParameters, mgmDataProcessed.mgmVecTot.value, mgmDataProcessed.mgmVecTot.isValid(), mekfData.satRotRateMekf.value, @@ -369,7 +376,8 @@ void AcsController::performPointingCtrl() { &(sensorValues.rw2Set.currSpeed.value), &(sensorValues.rw3Set.currSpeed.value), &(sensorValues.rw4Set.currSpeed.value), rwTrqNs); VectorOperations::add(torquePtgRws, rwTrqNs, torqueRws, 4); - actuatorCmd.scalingTorqueRws(torqueRws, torqueRwsScaled, &acsParameters.rwHandlingParameters); + actuatorCmd.scalingTorqueRws(torqueRws, torqueRwsScaled, + acsParameters.rwHandlingParameters.maxTrq); ptgCtrl.ptgDesaturation( &acsParameters.nadirModeControllerParameters, mgmDataProcessed.mgmVecTot.value, mgmDataProcessed.mgmVecTot.isValid(), mekfData.satRotRateMekf.value, @@ -392,7 +400,8 @@ void AcsController::performPointingCtrl() { &(sensorValues.rw2Set.currSpeed.value), &(sensorValues.rw3Set.currSpeed.value), &(sensorValues.rw4Set.currSpeed.value), rwTrqNs); VectorOperations::add(torquePtgRws, rwTrqNs, torqueRws, 4); - actuatorCmd.scalingTorqueRws(torqueRws, torqueRwsScaled, &acsParameters.rwHandlingParameters); + actuatorCmd.scalingTorqueRws(torqueRws, torqueRwsScaled, + acsParameters.rwHandlingParameters.maxTrq); ptgCtrl.ptgDesaturation( &acsParameters.inertialModeControllerParameters, mgmDataProcessed.mgmVecTot.value, mgmDataProcessed.mgmVecTot.isValid(), mekfData.satRotRateMekf.value, @@ -409,8 +418,11 @@ void AcsController::performPointingCtrl() { actuatorCmd.cmdSpeedToRws( sensorValues.rw1Set.currSpeed.value, sensorValues.rw2Set.currSpeed.value, sensorValues.rw3Set.currSpeed.value, sensorValues.rw4Set.currSpeed.value, torqueRwsScaled, - cmdSpeedRws, &acsParameters); - actuatorCmd.cmdDipolMtq(mgtDpDes, cmdDipolMtqs, &acsParameters.magnetorquerParameter); + cmdSpeedRws, acsParameters.onBoardParams.sampleTime, + acsParameters.rwHandlingParameters.inertiaWheel); + actuatorCmd.cmdDipolMtq(mgtDpDes, cmdDipolMtqs, + *acsParameters.magnetorquerParameter.inverseAlignment, + acsParameters.magnetorquerParameter.dipolMax); updateCtrlValData(targetQuat, errorQuat, errorAngle, targetSatRotRate); updateActuatorCmdData(rwTrqNs, cmdSpeedRws, cmdDipolMtqs); diff --git a/mission/controller/acs/ActuatorCmd.cpp b/mission/controller/acs/ActuatorCmd.cpp index 7173151d..cbe6b504 100644 --- a/mission/controller/acs/ActuatorCmd.cpp +++ b/mission/controller/acs/ActuatorCmd.cpp @@ -14,11 +14,7 @@ ActuatorCmd::ActuatorCmd() {} ActuatorCmd::~ActuatorCmd() {} -void ActuatorCmd::scalingTorqueRws(const double *rwTrq, double *rwTrqScaled, - AcsParameters::RwHandlingParameters *rwHandlingParameters) { - // Scaling the commanded torque to a maximum value - double maxTrq = rwHandlingParameters->maxTrq; - +void ActuatorCmd::scalingTorqueRws(const double *rwTrq, double *rwTrqScaled, double maxTorque) { double maxValue = 0; for (int i = 0; i < 4; i++) { // size of torque, always 4 ? if (abs(rwTrq[i]) > maxValue) { @@ -26,16 +22,15 @@ void ActuatorCmd::scalingTorqueRws(const double *rwTrq, double *rwTrqScaled, } } - if (maxValue > maxTrq) { - double scalingFactor = maxTrq / maxValue; + if (maxValue > maxTorque) { + double scalingFactor = maxTorque / maxValue; VectorOperations::mulScalar(rwTrq, scalingFactor, rwTrqScaled, 4); } } -void ActuatorCmd::cmdSpeedToRws(const int32_t speedRw0, const int32_t speedRw1, - const int32_t speedRw2, const int32_t speedRw3, - const double *rwTorque, int32_t *rwCmdSpeed, - AcsParameters *acsParameters) { +void ActuatorCmd::cmdSpeedToRws(int32_t speedRw0, int32_t speedRw1, int32_t speedRw2, + int32_t speedRw3, const double *rwTorque, int32_t *rwCmdSpeed, + double sampleTime, double inertiaWheel) { using namespace Math; // Calculating the commanded speed in RPM for every reaction wheel @@ -43,8 +38,7 @@ void ActuatorCmd::cmdSpeedToRws(const int32_t speedRw0, const int32_t speedRw1, double deltaSpeed[4] = {0, 0, 0, 0}; double radToRpm = 60 / (2 * PI); // factor for conversion to RPM // W_RW = Torque_RW / I_RW * delta t [rad/s] - double factor = acsParameters->onBoardParams.sampleTime / - acsParameters->rwHandlingParameters.inertiaWheel * radToRpm; + double factor = sampleTime / inertiaWheel * radToRpm; int32_t deltaSpeedInt[4] = {0, 0, 0, 0}; VectorOperations::mulScalar(rwTorque, factor, deltaSpeed, 4); for (int i = 0; i < 4; i++) { @@ -55,13 +49,12 @@ void ActuatorCmd::cmdSpeedToRws(const int32_t speedRw0, const int32_t speedRw1, } void ActuatorCmd::cmdDipolMtq(const double *dipolMoment, int16_t *dipolMomentActuator, - AcsParameters::MagnetorquerParameter *magnetorquerParameter) { + const double *inverseAlignment, double maxDipol) { // Convert to actuator frame double dipolMomentActuatorDouble[3] = {0, 0, 0}; - MatrixOperations::multiply(*magnetorquerParameter->inverseAlignment, dipolMoment, - dipolMomentActuatorDouble, 3, 3, 1); + MatrixOperations::multiply(inverseAlignment, dipolMoment, dipolMomentActuatorDouble, 3, 3, + 1); // Scaling along largest element if dipol exceeds maximum - double maxDipol = magnetorquerParameter->dipolMax; double maxValue = 0; for (int i = 0; i < 3; i++) { if (abs(dipolMomentActuator[i]) > maxDipol) { diff --git a/mission/controller/acs/ActuatorCmd.h b/mission/controller/acs/ActuatorCmd.h index ca0deb5b..def3c1b6 100644 --- a/mission/controller/acs/ActuatorCmd.h +++ b/mission/controller/acs/ActuatorCmd.h @@ -1,14 +1,13 @@ #ifndef ACTUATORCMD_H_ #define ACTUATORCMD_H_ -#include "AcsParameters.h" #include "MultiplicativeKalmanFilter.h" #include "SensorProcessing.h" #include "SensorValues.h" class ActuatorCmd { public: - ActuatorCmd(); // Input mode ? + ActuatorCmd(); virtual ~ActuatorCmd(); /* @@ -17,8 +16,7 @@ class ActuatorCmd { * @param: rwTrq given torque for reaction wheels * rwTrqScaled possible scaled torque */ - void scalingTorqueRws(const double *rwTrq, double *rwTrqScaled, - AcsParameters::RwHandlingParameters *rwHandlingParameters); + void scalingTorqueRws(const double *rwTrq, double *rwTrqScaled, double maxTorque); /* * @brief: cmdSpeedToRws() will set the maximum possible torque for the reaction @@ -29,9 +27,9 @@ class ActuatorCmd { * rwCmdSpeed output revolutions per minute for every * reaction wheel */ - void cmdSpeedToRws(const int32_t speedRw0, const int32_t speedRw1, const int32_t speedRw2, - const int32_t speedRw3, const double *rwTorque, int32_t *rwCmdSpeed, - AcsParameters *acsParameters); + void cmdSpeedToRws(int32_t speedRw0, int32_t speedRw1, int32_t speedRw2, int32_t speedRw3, + const double *rwTorque, int32_t *rwCmdSpeed, double sampleTime, + double inertiaWheel); /* * @brief: cmdDipolMtq() gives the commanded dipol moment for the magnetorques @@ -40,7 +38,7 @@ class ActuatorCmd { * dipolMomentActuator resulting dipol moment in actuator reference frame */ void cmdDipolMtq(const double *dipolMoment, int16_t *dipolMomentActuator, - AcsParameters::MagnetorquerParameter *magnetorquerParameter); + const double *inverseAlignment, double maxDipol); protected: private: From d86b9d55da217901badce30b199268ee9c14281b Mon Sep 17 00:00:00 2001 From: meggert Date: Tue, 28 Feb 2023 09:18:44 +0100 Subject: [PATCH 011/112] cleaned up SafeCtrl --- mission/controller/acs/control/SafeCtrl.cpp | 35 +++++++-------------- mission/controller/acs/control/SafeCtrl.h | 7 +---- 2 files changed, 12 insertions(+), 30 deletions(-) diff --git a/mission/controller/acs/control/SafeCtrl.cpp b/mission/controller/acs/control/SafeCtrl.cpp index aa04cbb6..734c6a0c 100644 --- a/mission/controller/acs/control/SafeCtrl.cpp +++ b/mission/controller/acs/control/SafeCtrl.cpp @@ -1,10 +1,3 @@ -/* - * SafeCtrl.cpp - * - * Created on: 19 Apr 2022 - * Author: Robin Marquardt - */ - #include "SafeCtrl.h" #include @@ -15,19 +8,10 @@ #include "../util/MathOperations.h" -SafeCtrl::SafeCtrl(AcsParameters *acsParameters_) { - loadAcsParameters(acsParameters_); - MatrixOperations::multiplyScalar(*(inertiaEIVE->inertiaMatrix), 10, *gainMatrixInertia, 3, - 3); -} +SafeCtrl::SafeCtrl(AcsParameters *acsParameters_) { acsParameters = acsParameters_; } SafeCtrl::~SafeCtrl() {} -void SafeCtrl::loadAcsParameters(AcsParameters *acsParameters_) { - safeModeControllerParameters = &(acsParameters_->safeModeControllerParameters); - inertiaEIVE = &(acsParameters_->inertiaEIVE); -} - ReturnValue_t SafeCtrl::safeMekf(timeval now, double *quatBJ, bool quatBJValid, double *magFieldModel, bool magFieldModelValid, double *sunDirModel, bool sunDirModelValid, double *satRateMekf, @@ -39,8 +23,8 @@ ReturnValue_t SafeCtrl::safeMekf(timeval now, double *quatBJ, bool quatBJValid, } double kRate = 0, kAlign = 0; - kRate = safeModeControllerParameters->k_rate_mekf; - kAlign = safeModeControllerParameters->k_align_mekf; + kRate = acsParameters->safeModeControllerParameters.k_rate_mekf; + kAlign = acsParameters->safeModeControllerParameters.k_align_mekf; // Calc sunDirB ,magFieldB with mekf output and model double dcmBJ[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; @@ -73,6 +57,9 @@ ReturnValue_t SafeCtrl::safeMekf(timeval now, double *quatBJ, bool quatBJValid, VectorOperations::add(torqueRate, torqueAlign, torqueAll, 3); // Adding factor of inertia for axes + MatrixOperations::multiplyScalar(*(acsParameters->inertiaEIVE.inertiaMatrix), 10, + *gainMatrixInertia, 3, + 3); // why only for mekf one and not for no mekf MatrixOperations::multiply(*gainMatrixInertia, torqueAll, torqueCmd, 3, 3, 1); // MagMom B (orthogonal torque) @@ -129,7 +116,7 @@ void SafeCtrl::safeNoMekf(timeval now, double *susDirB, bool susDirBValid, doubl /* Only valid if angle between sun direction and magnetic field direction * is sufficiently large */ double angleSunMag = acos(cosAngleSunMag); - if (angleSunMag < safeModeControllerParameters->sunMagAngleMin) { + if (angleSunMag < acsParameters->safeModeControllerParameters.sunMagAngleMin) { return; } @@ -139,8 +126,8 @@ void SafeCtrl::safeNoMekf(timeval now, double *susDirB, bool susDirBValid, doubl // Torque Align calculation double kRateNoMekf = 0, kAlignNoMekf = 0; - kRateNoMekf = safeModeControllerParameters->k_rate_no_mekf; - kAlignNoMekf = safeModeControllerParameters->k_align_no_mekf; + kRateNoMekf = acsParameters->safeModeControllerParameters.k_rate_no_mekf; + kAlignNoMekf = acsParameters->safeModeControllerParameters.k_align_no_mekf; double cosAngleAlignErr = VectorOperations::dot(sunDirRef, susDirB); double crossSusSunRef[3] = {0, 0, 0}; @@ -159,8 +146,8 @@ void SafeCtrl::safeNoMekf(timeval now, double *susDirB, bool susDirBValid, doubl // Final torque double torqueB[3] = {0, 0, 0}, torqueAlignRate[3] = {0, 0, 0}; VectorOperations::add(torqueRate, torqueAlign, torqueAlignRate, 3); - MatrixOperations::multiply(*(inertiaEIVE->inertiaMatrix), torqueAlignRate, torqueB, 3, 3, - 1); + MatrixOperations::multiply(*(acsParameters->inertiaEIVE.inertiaMatrix), torqueAlignRate, + torqueB, 3, 3, 1); // Magnetic moment double magMomB[3] = {0, 0, 0}; diff --git a/mission/controller/acs/control/SafeCtrl.h b/mission/controller/acs/control/SafeCtrl.h index 1784f9ca..f14bc464 100644 --- a/mission/controller/acs/control/SafeCtrl.h +++ b/mission/controller/acs/control/SafeCtrl.h @@ -17,8 +17,6 @@ class SafeCtrl { static const uint8_t INTERFACE_ID = CLASS_ID::ACS_SAFE; static const ReturnValue_t SAFECTRL_MEKF_INPUT_INVALID = MAKE_RETURN_CODE(0x01); - void loadAcsParameters(AcsParameters *acsParameters_); - ReturnValue_t safeMekf(timeval now, double *quatBJ, bool quatBJValid, double *magFieldModel, bool magFieldModelValid, double *sunDirModel, bool sunDirModelValid, double *satRateMekf, bool rateMekfValid, double *sunDirRef, @@ -30,12 +28,9 @@ class SafeCtrl { bool magRateBValid, double *sunDirRef, double *satRateRef, double *outputAngle, double *outputMagMomB, bool *outputValid); - void idleSunPointing(); // with reaction wheels - protected: private: - AcsParameters::SafeModeControllerParameters *safeModeControllerParameters; - AcsParameters::InertiaEIVE *inertiaEIVE; + AcsParameters *acsParameters; double gainMatrixInertia[3][3]; double magFieldBState[3]; From 04a561b9a0a342cf88e9ece24b39c90b5a54989a Mon Sep 17 00:00:00 2001 From: meggert Date: Tue, 28 Feb 2023 10:12:25 +0100 Subject: [PATCH 012/112] cleaned up detumble and fixed gyr detumble law to actual bdot law --- mission/controller/AcsController.cpp | 4 +-- mission/controller/acs/control/Detumble.cpp | 28 +++++++++------------ mission/controller/acs/control/Detumble.h | 20 +++++---------- 3 files changed, 20 insertions(+), 32 deletions(-) diff --git a/mission/controller/AcsController.cpp b/mission/controller/AcsController.cpp index d6d2fab6..260b793a 100644 --- a/mission/controller/AcsController.cpp +++ b/mission/controller/AcsController.cpp @@ -8,7 +8,6 @@ AcsController::AcsController(object_id_t objectId) : ExtendedControllerBase(objectId), guidance(&acsParameters), safeCtrl(&acsParameters), - detumble(&acsParameters), ptgCtrl(&acsParameters), parameterHelper(this), mgmDataRaw(this), @@ -219,7 +218,8 @@ void AcsController::performDetumble() { double magMomMtq[3] = {0, 0, 0}; detumble.bDotLaw(mgmDataProcessed.mgmVecTotDerivative.value, mgmDataProcessed.mgmVecTotDerivative.isValid(), mgmDataProcessed.mgmVecTot.value, - mgmDataProcessed.mgmVecTot.isValid(), magMomMtq); + mgmDataProcessed.mgmVecTot.isValid(), magMomMtq, + acsParameters.detumbleParameter.gainD); actuatorCmd.cmdDipolMtq(magMomMtq, cmdDipolMtqs, *acsParameters.magnetorquerParameter.inverseAlignment, acsParameters.magnetorquerParameter.dipolMax); diff --git a/mission/controller/acs/control/Detumble.cpp b/mission/controller/acs/control/Detumble.cpp index 222a0ec2..28cbefbf 100644 --- a/mission/controller/acs/control/Detumble.cpp +++ b/mission/controller/acs/control/Detumble.cpp @@ -17,33 +17,27 @@ #include "../util/MathOperations.h" -Detumble::Detumble(AcsParameters *acsParameters_) { loadAcsParameters(acsParameters_); } +Detumble::Detumble() {} Detumble::~Detumble() {} -void Detumble::loadAcsParameters(AcsParameters *acsParameters_) { - detumbleParameter = &(acsParameters_->detumbleParameter); - magnetorquesParameter = &(acsParameters_->magnetorquerParameter); -} - ReturnValue_t Detumble::bDotLaw(const double *magRate, const bool magRateValid, - const double *magField, const bool magFieldValid, double *magMom) { + const double *magField, const bool magFieldValid, double *magMom, + double gain) { if (!magRateValid || !magFieldValid) { return DETUMBLE_NO_SENSORDATA; } - double gain = detumbleParameter->gainD; double factor = -gain / pow(VectorOperations::norm(magField, 3), 2); VectorOperations::mulScalar(magRate, factor, magMom, 3); return returnvalue::OK; } -ReturnValue_t Detumble::bangbangLaw(const double *magRate, const bool magRateValid, - double *magMom) { +ReturnValue_t Detumble::bangbangLaw(const double *magRate, const bool magRateValid, double *magMom, + double dipolMax) { if (!magRateValid) { return DETUMBLE_NO_SENSORDATA; } - double dipolMax = magnetorquesParameter->dipolMax; for (int i = 0; i < 3; i++) { magMom[i] = -dipolMax * sign(magRate[i]); } @@ -51,14 +45,16 @@ ReturnValue_t Detumble::bangbangLaw(const double *magRate, const bool magRateVal return returnvalue::OK; } -ReturnValue_t Detumble::bDotLawGyro(const double *satRate, const bool *satRateValid, +ReturnValue_t Detumble::bDotLawFull(const double *satRate, const bool *satRateValid, const double *magField, const bool *magFieldValid, - double *magMom) { + double *magMom, double gain) { if (!satRateValid || !magFieldValid) { return DETUMBLE_NO_SENSORDATA; } - double gain = detumbleParameter->gainD; - double factor = -gain / pow(VectorOperations::norm(magField, 3), 2); - VectorOperations::mulScalar(satRate, factor, magMom, 3); + double factor = gain / pow(VectorOperations::norm(magField, 3), 2); + double magFieldNormed[3] = {0, 0, 0}, crossProduct[3] = {0, 0, 0}; + VectorOperations::normalize(magField, magFieldNormed, 3); + VectorOperations::cross(satRate, magFieldNormed, crossProduct); + VectorOperations::mulScalar(crossProduct, factor, magMom, 3); return returnvalue::OK; } diff --git a/mission/controller/acs/control/Detumble.h b/mission/controller/acs/control/Detumble.h index dee82271..2bf3607d 100644 --- a/mission/controller/acs/control/Detumble.h +++ b/mission/controller/acs/control/Detumble.h @@ -12,30 +12,22 @@ class Detumble { public: - Detumble(AcsParameters *acsParameters_); + Detumble(); virtual ~Detumble(); static const uint8_t INTERFACE_ID = CLASS_ID::ACS_DETUMBLE; static const ReturnValue_t DETUMBLE_NO_SENSORDATA = MAKE_RETURN_CODE(0x01); - /* @brief: Load AcsParameters for this class - * @param: acsParameters_ Pointer to object which defines the ACS configuration parameters - */ - void loadAcsParameters(AcsParameters *acsParameters_); - ReturnValue_t bDotLaw(const double *magRate, const bool magRateValid, const double *magField, - const bool magFieldValid, double *magMom); + const bool magFieldValid, double *magMom, double gain); - ReturnValue_t bangbangLaw(const double *magRate, const bool magRateValid, double *magMom); + ReturnValue_t bangbangLaw(const double *magRate, const bool magRateValid, double *magMom, + double dipolMax); - ReturnValue_t bangbangLaw(const double *magRate, const bool *magRateValid, double *magMom); - - ReturnValue_t bDotLawGyro(const double *satRate, const bool *satRateValid, const double *magField, - const bool *magFieldValid, double *magMom); + ReturnValue_t bDotLawFull(const double *satRate, const bool *satRateValid, const double *magField, + const bool *magFieldValid, double *magMom, double gain); private: - AcsParameters::DetumbleParameter *detumbleParameter; - AcsParameters::MagnetorquerParameter *magnetorquesParameter; }; #endif /*ACS_CONTROL_DETUMBLE_H_*/ From 84643020da498b4499d0858b33fbb8ce6415e68f Mon Sep 17 00:00:00 2001 From: meggert Date: Tue, 28 Feb 2023 10:43:17 +0100 Subject: [PATCH 013/112] fixed gs target mode using wrong parameter set --- mission/controller/AcsController.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/mission/controller/AcsController.cpp b/mission/controller/AcsController.cpp index 260b793a..27f8eaf4 100644 --- a/mission/controller/AcsController.cpp +++ b/mission/controller/AcsController.cpp @@ -344,10 +344,10 @@ void AcsController::performPointingCtrl() { susDataProcessed.sunIjkModel.value, targetQuat, targetSatRotRate); guidance.comparePtg(mekfData.quatMekf.value, mekfData.satRotRateMekf.value, targetQuat, targetSatRotRate, errorQuat, errorSatRotRate, errorAngle); - ptgCtrl.ptgLaw(&acsParameters.targetModeControllerParameters, errorQuat, errorSatRotRate, + ptgCtrl.ptgLaw(&acsParameters.gsTargetModeControllerParameters, errorQuat, errorSatRotRate, *rwPseudoInv, torquePtgRws); ptgCtrl.ptgNullspace( - &acsParameters.targetModeControllerParameters, &(sensorValues.rw1Set.currSpeed.value), + &acsParameters.gsTargetModeControllerParameters, &(sensorValues.rw1Set.currSpeed.value), &(sensorValues.rw2Set.currSpeed.value), &(sensorValues.rw3Set.currSpeed.value), &(sensorValues.rw4Set.currSpeed.value), rwTrqNs); VectorOperations::add(torquePtgRws, rwTrqNs, torqueRws, 4); From 737d5ecb53b1fd02449cf5c0bc7bb85c4318c322 Mon Sep 17 00:00:00 2001 From: meggert Date: Tue, 28 Feb 2023 10:47:37 +0100 Subject: [PATCH 014/112] cleaned up ptgCtrl --- mission/controller/acs/Guidance.cpp | 1 - mission/controller/acs/control/PtgCtrl.cpp | 52 +++++++++------------- mission/controller/acs/control/PtgCtrl.h | 11 +---- 3 files changed, 23 insertions(+), 41 deletions(-) diff --git a/mission/controller/acs/Guidance.cpp b/mission/controller/acs/Guidance.cpp index 9e9c04f9..cdfc6d11 100644 --- a/mission/controller/acs/Guidance.cpp +++ b/mission/controller/acs/Guidance.cpp @@ -204,7 +204,6 @@ void Guidance::targetQuatPtgThreeAxes(timeval now, double posSatE[3], double vel void Guidance::targetQuatPtgGs(timeval now, double posSatE[3], double sunDirI[3], double targetQuat[4], double targetSatRotRate[3]) { - sif::debug << acsParameters->gsTargetModeControllerParameters.altitudeTgt << std::endl; //------------------------------------------------------------------------------------- // Calculation of target quaternion for ground station pointing //------------------------------------------------------------------------------------- diff --git a/mission/controller/acs/control/PtgCtrl.cpp b/mission/controller/acs/control/PtgCtrl.cpp index 74a32a4a..c7c8d2f0 100644 --- a/mission/controller/acs/control/PtgCtrl.cpp +++ b/mission/controller/acs/control/PtgCtrl.cpp @@ -1,10 +1,3 @@ -/* - * PtgCtrl.cpp - * - * Created on: 17 Jul 2022 - * Author: Robin Marquardt - */ - #include "PtgCtrl.h" #include @@ -16,16 +9,10 @@ #include "../util/MathOperations.h" -PtgCtrl::PtgCtrl(AcsParameters *acsParameters_) { loadAcsParameters(acsParameters_); } +PtgCtrl::PtgCtrl(AcsParameters *acsParameters_) { acsParameters = acsParameters_; } PtgCtrl::~PtgCtrl() {} -void PtgCtrl::loadAcsParameters(AcsParameters *acsParameters_) { - inertiaEIVE = &(acsParameters_->inertiaEIVE); - rwHandlingParameters = &(acsParameters_->rwHandlingParameters); - rwMatrices = &(acsParameters_->rwMatrices); -} - void PtgCtrl::ptgLaw(AcsParameters::PointingLawParameters *pointingLawParameters, const double *errorQuat, const double *deltaRate, const double *rwPseudoInv, double *torqueRws) { @@ -62,8 +49,8 @@ void PtgCtrl::ptgLaw(AcsParameters::PointingLawParameters *pointingLawParameters gainMatrixDiagonal[0][0] = gainVector[0]; gainMatrixDiagonal[1][1] = gainVector[1]; gainMatrixDiagonal[2][2] = gainVector[2]; - MatrixOperations::multiply(*gainMatrixDiagonal, *(inertiaEIVE->inertiaMatrix), - *gainMatrix, 3, 3, 3); + MatrixOperations::multiply( + *gainMatrixDiagonal, *(acsParameters->inertiaEIVE.inertiaMatrix), *gainMatrix, 3, 3, 3); // Inverse of gainMatrix double gainMatrixInverse[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; @@ -72,8 +59,8 @@ void PtgCtrl::ptgLaw(AcsParameters::PointingLawParameters *pointingLawParameters gainMatrixInverse[2][2] = 1 / gainMatrix[2][2]; double pMatrix[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; - MatrixOperations::multiply(*gainMatrixInverse, *(inertiaEIVE->inertiaMatrix), *pMatrix, 3, - 3, 3); + MatrixOperations::multiply( + *gainMatrixInverse, *(acsParameters->inertiaEIVE.inertiaMatrix), *pMatrix, 3, 3, 3); MatrixOperations::multiplyScalar(*pMatrix, kInt, *pMatrix, 3, 3); //------------------------------------------------------------------------------------------------ @@ -98,7 +85,8 @@ void PtgCtrl::ptgLaw(AcsParameters::PointingLawParameters *pointingLawParameters // Torque for rate error double torqueRate[3] = {0, 0, 0}; - MatrixOperations::multiply(*(inertiaEIVE->inertiaMatrix), deltaRate, torqueRate, 3, 3, 1); + MatrixOperations::multiply(*(acsParameters->inertiaEIVE.inertiaMatrix), deltaRate, + torqueRate, 3, 3, 1); VectorOperations::mulScalar(torqueRate, cInt, torqueRate, 3); VectorOperations::mulScalar(torqueRate, -1, torqueRate, 3); @@ -123,11 +111,13 @@ void PtgCtrl::ptgDesaturation(AcsParameters::PointingLawParameters *pointingLawP // calculating momentum of satellite and momentum of reaction wheels double speedRws[4] = {(double)*speedRw0, (double)*speedRw1, (double)*speedRw2, (double)*speedRw3}; double momentumRwU[4] = {0, 0, 0, 0}, momentumRw[3] = {0, 0, 0}; - VectorOperations::mulScalar(speedRws, rwHandlingParameters->inertiaWheel, momentumRwU, 4); - MatrixOperations::multiply(*(rwMatrices->alignmentMatrix), momentumRwU, momentumRw, 3, 4, - 1); + VectorOperations::mulScalar(speedRws, acsParameters->rwHandlingParameters.inertiaWheel, + momentumRwU, 4); + MatrixOperations::multiply(*(acsParameters->rwMatrices.alignmentMatrix), momentumRwU, + momentumRw, 3, 4, 1); double momentumSat[3] = {0, 0, 0}, momentumTotal[3] = {0, 0, 0}; - MatrixOperations::multiply(*(inertiaEIVE->inertiaMatrix), satRate, momentumSat, 3, 3, 1); + MatrixOperations::multiply(*(acsParameters->inertiaEIVE.inertiaMatrix), satRate, + momentumSat, 3, 3, 1); VectorOperations::add(momentumSat, momentumRw, momentumTotal, 3); // calculating momentum error double deltaMomentum[3] = {0, 0, 0}; @@ -152,11 +142,12 @@ void PtgCtrl::ptgNullspace(AcsParameters::PointingLawParameters *pointingLawPara VectorOperations::mulScalar(speedRws, 2 * Math::PI / 60, speedRws, 4); double diffRwSpeed[4] = {0, 0, 0, 0}; VectorOperations::subtract(speedRws, rpmOffset, diffRwSpeed, 4); - VectorOperations::mulScalar(diffRwSpeed, rwHandlingParameters->inertiaWheel, + VectorOperations::mulScalar(diffRwSpeed, acsParameters->rwHandlingParameters.inertiaWheel, wheelMomentum, 4); double gainNs = pointingLawParameters->gainNullspace; double nullSpaceMatrix[4][4] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; - MathOperations::vecTransposeVecMatrix(rwMatrices->nullspace, rwMatrices->nullspace, + MathOperations::vecTransposeVecMatrix(acsParameters->rwMatrices.nullspace, + acsParameters->rwMatrices.nullspace, *nullSpaceMatrix, 4); MatrixOperations::multiply(*nullSpaceMatrix, wheelMomentum, rwTrqNs, 4, 4, 1); VectorOperations::mulScalar(rwTrqNs, gainNs, rwTrqNs, 4); @@ -174,21 +165,22 @@ void PtgCtrl::rwAntistiction(ACS::SensorValues *sensorValues, double *torqueComm for (uint8_t i = 0; i < 4; i++) { if (rwAvailable[i]) { if (torqueMemory[i] != 0) { - if ((omegaRw[i] * torqueMemory[i]) > rwHandlingParameters->stictionReleaseSpeed) { + if ((omegaRw[i] * torqueMemory[i]) > + acsParameters->rwHandlingParameters.stictionReleaseSpeed) { torqueMemory[i] = 0; } else { - torqueCommand[i] = torqueMemory[i] * rwHandlingParameters->stictionTorque; + torqueCommand[i] = torqueMemory[i] * acsParameters->rwHandlingParameters.stictionTorque; } } else { - if ((omegaRw[i] < rwHandlingParameters->stictionSpeed) && - (omegaRw[i] > -rwHandlingParameters->stictionSpeed)) { + if ((omegaRw[i] < acsParameters->rwHandlingParameters.stictionSpeed) && + (omegaRw[i] > -acsParameters->rwHandlingParameters.stictionSpeed)) { if (omegaRw[i] < omegaMemory[i]) { torqueMemory[i] = -1; } else { torqueMemory[i] = 1; } - torqueCommand[i] = torqueMemory[i] * rwHandlingParameters->stictionTorque; + torqueCommand[i] = torqueMemory[i] * acsParameters->rwHandlingParameters.stictionTorque; } } } else { diff --git a/mission/controller/acs/control/PtgCtrl.h b/mission/controller/acs/control/PtgCtrl.h index fb27fc6d..87185612 100644 --- a/mission/controller/acs/control/PtgCtrl.h +++ b/mission/controller/acs/control/PtgCtrl.h @@ -33,13 +33,7 @@ class PtgCtrl { static const uint8_t INTERFACE_ID = CLASS_ID::ACS_PTG; static const ReturnValue_t PTGCTRL_MEKF_INPUT_INVALID = MAKE_RETURN_CODE(0x01); - /* @brief: Load AcsParameters for this class - * @param: acsParameters_ Pointer to object which defines the ACS configuration parameters - */ - void loadAcsParameters(AcsParameters *acsParameters_); - /* @brief: Calculates the needed torque for the pointing control mechanism - * @param: acsParameters_ Pointer to object which defines the ACS configuration parameters */ void ptgLaw(AcsParameters::PointingLawParameters *pointingLawParameters, const double *qError, const double *deltaRate, const double *rwPseudoInv, double *torqueRws); @@ -54,15 +48,12 @@ class PtgCtrl { const int32_t *speedRw3, double *rwTrqNs); /* @brief: Commands the stiction torque in case wheel speed is to low - * @param: sensorValues class containing all RW related values * torqueCommand modified torque after antistiction */ void rwAntistiction(ACS::SensorValues *sensorValues, double *torqueCommand); private: - AcsParameters::RwHandlingParameters *rwHandlingParameters; - AcsParameters::InertiaEIVE *inertiaEIVE; - AcsParameters::RwMatrices *rwMatrices; + const AcsParameters *acsParameters; double torqueMemory[4] = {0, 0, 0, 0}; double omegaMemory[4] = {0, 0, 0, 0}; From d59daa24857a517e4ff0e72a4828db2b558f6943 Mon Sep 17 00:00:00 2001 From: meggert Date: Tue, 28 Feb 2023 15:00:05 +0100 Subject: [PATCH 015/112] we might need this pointing law stuff ... --- mission/controller/AcsController.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/mission/controller/AcsController.cpp b/mission/controller/AcsController.cpp index 27f8eaf4..5b3eae4a 100644 --- a/mission/controller/AcsController.cpp +++ b/mission/controller/AcsController.cpp @@ -299,6 +299,8 @@ void AcsController::performPointingCtrl() { guidance.targetQuatPtgSun(susDataProcessed.sunIjkModel.value, targetQuat, targetSatRotRate); guidance.comparePtg(mekfData.quatMekf.value, mekfData.satRotRateMekf.value, targetQuat, targetSatRotRate, errorQuat, errorSatRotRate, errorAngle); + ptgCtrl.ptgLaw(&acsParameters.idleModeControllerParameters, errorQuat, errorSatRotRate, + *rwPseudoInv, torquePtgRws); ptgCtrl.ptgNullspace( &acsParameters.idleModeControllerParameters, &(sensorValues.rw1Set.currSpeed.value), &(sensorValues.rw2Set.currSpeed.value), &(sensorValues.rw3Set.currSpeed.value), From 7b0657bb55a43389c735a228fa76c0af2e66c126 Mon Sep 17 00:00:00 2001 From: meggert Date: Tue, 28 Feb 2023 15:01:07 +0100 Subject: [PATCH 016/112] fixed usage of wrong parameters --- mission/controller/AcsController.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/mission/controller/AcsController.cpp b/mission/controller/AcsController.cpp index 5b3eae4a..feb8fb6e 100644 --- a/mission/controller/AcsController.cpp +++ b/mission/controller/AcsController.cpp @@ -356,11 +356,11 @@ void AcsController::performPointingCtrl() { actuatorCmd.scalingTorqueRws(torqueRws, torqueRwsScaled, acsParameters.rwHandlingParameters.maxTrq); ptgCtrl.ptgDesaturation( - &acsParameters.targetModeControllerParameters, mgmDataProcessed.mgmVecTot.value, + &acsParameters.gsTargetModeControllerParameters, mgmDataProcessed.mgmVecTot.value, mgmDataProcessed.mgmVecTot.isValid(), mekfData.satRotRateMekf.value, &(sensorValues.rw1Set.currSpeed.value), &(sensorValues.rw2Set.currSpeed.value), &(sensorValues.rw3Set.currSpeed.value), &(sensorValues.rw4Set.currSpeed.value), mgtDpDes); - enableAntiStiction = acsParameters.targetModeControllerParameters.enableAntiStiction; + enableAntiStiction = acsParameters.gsTargetModeControllerParameters.enableAntiStiction; break; case acs::PTG_NADIR: From 2c6ea8dc9f641c0bcd707826d9e6debe460fc1b0 Mon Sep 17 00:00:00 2001 From: meggert Date: Tue, 28 Feb 2023 15:46:52 +0100 Subject: [PATCH 017/112] fixed wrong if condition --- mission/controller/acs/Guidance.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/mission/controller/acs/Guidance.cpp b/mission/controller/acs/Guidance.cpp index cdfc6d11..ed14cc48 100644 --- a/mission/controller/acs/Guidance.cpp +++ b/mission/controller/acs/Guidance.cpp @@ -540,8 +540,8 @@ ReturnValue_t Guidance::getDistributionMatrixRw(ACS::SensorValues *sensorValues, } void Guidance::getTargetParamsSafe(double sunTargetSafe[3], double satRateSafe[3]) { - if (not std::filesystem::exists(SD_0_SKEWED_PTG_FILE) or - not std::filesystem::exists(SD_1_SKEWED_PTG_FILE)) { // ToDo: if file does not exist anymore + if (not std::filesystem::exists(SD_0_SKEWED_PTG_FILE) and + not std::filesystem::exists(SD_1_SKEWED_PTG_FILE)) { std::memcpy(sunTargetSafe, acsParameters->safeModeControllerParameters.sunTargetDir, 3 * sizeof(double)); } else { From ba0e07b5c66d47ece241d6d4b61f80244cd671ab Mon Sep 17 00:00:00 2001 From: meggert Date: Tue, 7 Mar 2023 10:04:04 +0100 Subject: [PATCH 018/112] merge aftermath --- mission/controller/acs/control/SafeCtrl.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/mission/controller/acs/control/SafeCtrl.cpp b/mission/controller/acs/control/SafeCtrl.cpp index d56330bb..392e32ba 100644 --- a/mission/controller/acs/control/SafeCtrl.cpp +++ b/mission/controller/acs/control/SafeCtrl.cpp @@ -122,8 +122,8 @@ ReturnValue_t SafeCtrl::safeNoMekf(timeval now, double *susDirB, bool susDirBVal VectorOperations::subtract(estSatRate, satRateRef, diffRate, 3); // Torque Align calculation - double kRateNoMekf = acsParameters->safeModeControllerParameters->k_rate_no_mekf; - double kAlignNoMekf = acsParameters->safeModeControllerParameters->k_align_no_mekf; + double kRateNoMekf = acsParameters->safeModeControllerParameters.k_rate_no_mekf; + double kAlignNoMekf = acsParameters->safeModeControllerParameters.k_align_no_mekf; double cosAngleAlignErr = VectorOperations::dot(sunDirRef, susDirB); double crossSusSunRef[3] = {0, 0, 0}; From faf4937e7648976385cdfc450d24f20bdf5314d7 Mon Sep 17 00:00:00 2001 From: meggert Date: Tue, 7 Mar 2023 10:11:12 +0100 Subject: [PATCH 019/112] fixed detumbleCtrl magField and magRate units --- mission/controller/acs/control/Detumble.cpp | 15 ++++++++++++--- 1 file changed, 12 insertions(+), 3 deletions(-) diff --git a/mission/controller/acs/control/Detumble.cpp b/mission/controller/acs/control/Detumble.cpp index 5e69fdcc..893d6a4b 100644 --- a/mission/controller/acs/control/Detumble.cpp +++ b/mission/controller/acs/control/Detumble.cpp @@ -19,8 +19,13 @@ ReturnValue_t Detumble::bDotLaw(const double *magRate, const bool magRateValid, if (!magRateValid || !magFieldValid) { return DETUMBLE_NO_SENSORDATA; } - double factor = -gain / pow(VectorOperations::norm(magField, 3), 2); - VectorOperations::mulScalar(magRate, factor, magMom, 3); + // convert uT to T + double magFieldT[3], magRateT[3]; + VectorOperations::mulScalar(magField, 1e-6, magFieldT, 3); + VectorOperations::mulScalar(magRate, 1e-6, magRateT, 3); + // control law + double factor = -gain / pow(VectorOperations::norm(magFieldT, 3), 2); + VectorOperations::mulScalar(magRateT, factor, magMom, 3); return returnvalue::OK; } @@ -43,9 +48,13 @@ ReturnValue_t Detumble::bDotLawFull(const double *satRate, const bool *satRateVa if (!satRateValid || !magFieldValid) { return DETUMBLE_NO_SENSORDATA; } + // convert uT to T + double magFieldT[3]; + VectorOperations::mulScalar(magField, 1e-6, magFieldT, 3); + // control law double factor = gain / pow(VectorOperations::norm(magField, 3), 2); double magFieldNormed[3] = {0, 0, 0}, crossProduct[3] = {0, 0, 0}; - VectorOperations::normalize(magField, magFieldNormed, 3); + VectorOperations::normalize(magFieldT, magFieldNormed, 3); VectorOperations::cross(satRate, magFieldNormed, crossProduct); VectorOperations::mulScalar(crossProduct, factor, magMom, 3); return returnvalue::OK; From bd295d5b520cbafbc8d3a88ae6ec7ec4dd1e2c0c Mon Sep 17 00:00:00 2001 From: meggert Date: Tue, 7 Mar 2023 10:12:52 +0100 Subject: [PATCH 020/112] detumbleCounter doesnt hard reset anymore --- mission/controller/AcsController.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/mission/controller/AcsController.cpp b/mission/controller/AcsController.cpp index 3bf89d77..45ad4d91 100644 --- a/mission/controller/AcsController.cpp +++ b/mission/controller/AcsController.cpp @@ -185,8 +185,8 @@ void AcsController::performSafe() { VectorOperations::norm(gyrDataProcessed.gyrVecTot.value, 3) > acsParameters.detumbleParameter.omegaDetumbleStart) { detumbleCounter++; - } else { - detumbleCounter = 0; + } else if (detumbleCounter > 0) { + detumbleCounter -= 1; } if (detumbleCounter > acsParameters.detumbleParameter.detumblecounter) { detumbleCounter = 0; @@ -235,8 +235,8 @@ void AcsController::performDetumble() { VectorOperations::norm(gyrDataProcessed.gyrVecTot.value, 3) < acsParameters.detumbleParameter.omegaDetumbleEnd) { detumbleCounter++; - } else { - detumbleCounter = 0; + } else if (detumbleCounter > 0) { + detumbleCounter -= 1; } if (detumbleCounter > acsParameters.detumbleParameter.detumblecounter) { detumbleCounter = 0; From d8a07312f2199e7330c5e9cb88eac16b264d60e4 Mon Sep 17 00:00:00 2001 From: meggert Date: Tue, 7 Mar 2023 10:36:00 +0100 Subject: [PATCH 021/112] changelog --- CHANGELOG.md | 25 +++++++++++++++++++------ 1 file changed, 19 insertions(+), 6 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 2e3c5dc4..4ef271de 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -16,6 +16,25 @@ will consitute of a breaking change warranting a new major release: # [unreleased] +## Fixed + +- `AcsParameters` setter were previously all for scalar parameters. Now vector and matrix + parameters use their respective setters. +- Several `AcsController` components had their own implementation of `AcsParameters`. This resulted + in those parameters not being updated, while the actual ones were updated. All instances of + `AcsParameters` not belonging to `AcsController` are eiter removed or replaced by pointer + instances. +- Instead of updating the `gsTargetModeControllerParameters`, the `targetModeControllerParameters` + were updated. +- Fixed Idle Mode Controller never calling `ptgLaw` and therefore never calculating control + values. +- Fixed wrong check on wether file used for persistant boolean flag on successful still existed. + +## Changed + +- The `detumbleCounter` now does not get hard reset anymore, if the critical rate does not get + violated anymore. Instead it is incrementally reset. + # [v1.35.1] 2023-03-04 ## Fixed @@ -100,12 +119,6 @@ eive-tmtc: v2.16.2 - Linux GPS handler now checks the individual `*_SET` flags when analysing the `gpsd` struct. PR: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/400 -- Several `AcsController` components had their own implementation of `AcsParameters`. This resulted - in those parameters not being updated, while the actual ones were updated. All instances of - `AcsParameters` not belonging to `AcsController` are eiter removed or replaced by pointer - instances. -- Instead of updating the `gsTargetModeControllerParameters`, the `targetModeControllerParameters` - were updated. # [v1.32.0] 2023-02-24 From fd436dbe8b3b32ae7f1d0d82fe0493a9b96b23fb Mon Sep 17 00:00:00 2001 From: meggert Date: Tue, 7 Mar 2023 11:10:47 +0100 Subject: [PATCH 022/112] added fdir for unrealistic gps altitudes --- mission/controller/AcsController.cpp | 1 + mission/controller/AcsController.h | 1 + mission/controller/acs/AcsParameters.cpp | 9 +++++++++ mission/controller/acs/AcsParameters.h | 7 +++++-- mission/controller/acs/SensorProcessing.cpp | 15 ++++++++++++--- mission/controller/acs/SensorValues.h | 11 +++++------ .../controllerdefinitions/AcsCtrlDefinitions.h | 2 ++ 7 files changed, 35 insertions(+), 11 deletions(-) diff --git a/mission/controller/AcsController.cpp b/mission/controller/AcsController.cpp index 45ad4d91..c3149c38 100644 --- a/mission/controller/AcsController.cpp +++ b/mission/controller/AcsController.cpp @@ -588,6 +588,7 @@ ReturnValue_t AcsController::initializeLocalDataPool(localpool::DataPool &localD // GPS Processed localDataPoolMap.emplace(acsctrl::PoolIds::GC_LATITUDE, &gcLatitude); localDataPoolMap.emplace(acsctrl::PoolIds::GD_LONGITUDE, &gdLongitude); + localDataPoolMap.emplace(acsctrl::PoolIds::ALTITUDE, &altitude); localDataPoolMap.emplace(acsctrl::PoolIds::GPS_POSITION, &gpsPosition); localDataPoolMap.emplace(acsctrl::PoolIds::GPS_VELOCITY, &gpsVelocity); poolManager.subscribeForRegularPeriodicPacket({gpsDataProcessed.getSid(), false, 5.0}); diff --git a/mission/controller/AcsController.h b/mission/controller/AcsController.h index f59a4605..ae61e2a2 100644 --- a/mission/controller/AcsController.h +++ b/mission/controller/AcsController.h @@ -189,6 +189,7 @@ class AcsController : public ExtendedControllerBase, public ReceivesParameterMes acsctrl::GpsDataProcessed gpsDataProcessed; PoolEntry gcLatitude = PoolEntry(); PoolEntry gdLongitude = PoolEntry(); + PoolEntry altitude = PoolEntry(); PoolEntry gpsPosition = PoolEntry(3); PoolEntry gpsVelocity = PoolEntry(3); diff --git a/mission/controller/acs/AcsParameters.cpp b/mission/controller/acs/AcsParameters.cpp index a19571eb..0d3785cc 100644 --- a/mission/controller/acs/AcsParameters.cpp +++ b/mission/controller/acs/AcsParameters.cpp @@ -591,6 +591,15 @@ ReturnValue_t AcsParameters::getParameter(uint8_t domainId, uint8_t parameterId, case 0x0: parameterWrapper->set(gpsParameters.timeDiffVelocityMax); break; + case 0x1: + parameterWrapper->set(gpsParameters.minimumFdirAltitude); + break; + case 0x2: + parameterWrapper->set(gpsParameters.maximumFdirAltitude); + break; + case 0x3: + parameterWrapper->set(gpsParameters.fdirAltitude); + break; default: return INVALID_IDENTIFIER_ID; } diff --git a/mission/controller/acs/AcsParameters.h b/mission/controller/acs/AcsParameters.h index ea867c65..4d6aa14a 100644 --- a/mission/controller/acs/AcsParameters.h +++ b/mission/controller/acs/AcsParameters.h @@ -772,7 +772,7 @@ class AcsParameters : public HasParametersIF { double gyr2bias[3] = {0.15039212820512823, 0.7094475589743591, -0.22298363589743594}; double gyr3bias[3] = {0.0021730769230769217, -0.6655897435897435, 0.034096153846153845}; - /* var = sqrt(sigma), sigma = RND*sqrt(freq), following values are RND^2 and not var as freq is + /* var = sigma^2, sigma = RND*sqrt(freq), following values are RND^2 and not var as freq is * assumed to be equal for the same class of sensors */ float gyr02variance[3] = {pow(3.0e-3, 2), // RND_x = 3.0e-3 deg/s/sqrt(Hz) rms pow(3.0e-3, 2), // RND_y = 3.0e-3 deg/s/sqrt(Hz) rms @@ -886,7 +886,10 @@ class AcsParameters : public HasParametersIF { } strParameters; struct GpsParameters { - double timeDiffVelocityMax = 30; //[s] + double timeDiffVelocityMax = 30; // [s] + double minimumFdirAltitude = 475 * 1e3; // [m] + double maximumFdirAltitude = 575 * 1e3; // [m] + double fdirAltitude = 525 * 1e3; // [m] } gpsParameters; struct SunModelParameters { diff --git a/mission/controller/acs/SensorProcessing.cpp b/mission/controller/acs/SensorProcessing.cpp index 466d9ed5..b3423367 100644 --- a/mission/controller/acs/SensorProcessing.cpp +++ b/mission/controller/acs/SensorProcessing.cpp @@ -550,8 +550,8 @@ void SensorProcessing::processGps(const double gpsLatitude, const double gpsLong const bool validGps, const AcsParameters::GpsParameters *gpsParameters, acsctrl::GpsDataProcessed *gpsDataProcessed) { - // name to convert not process - double gdLongitude = 0, gcLatitude = 0, posSatE[3] = {0, 0, 0}, gpsVelocityE[3] = {0, 0, 0}; + double gdLongitude = 0, gcLatitude = 0, altitude = 0, posSatE[3] = {0, 0, 0}, + gpsVelocityE[3] = {0, 0, 0}; if (validGps) { // Transforming from Degree to Radians and calculation geocentric lattitude from geodetic gdLongitude = gpsLongitude * PI / 180.; @@ -560,9 +560,17 @@ void SensorProcessing::processGps(const double gpsLatitude, const double gpsLong double factor = 1 - pow(eccentricityWgs84, 2); gcLatitude = atan(factor * tan(latitudeRad)); + // Altitude FDIR + if (gpsAltitude > gpsParameters->maximumFdirAltitude || + gpsAltitude < gpsParameters->maximumFdirAltitude) { + altitude = gpsParameters->fdirAltitude; + } else { + altitude = gpsAltitude; + } + // Calculation of the satellite velocity in earth fixed frame double deltaDistance[3] = {0, 0, 0}; - MathOperations::cartesianFromLatLongAlt(latitudeRad, gdLongitude, gpsAltitude, posSatE); + MathOperations::cartesianFromLatLongAlt(latitudeRad, gdLongitude, altitude, posSatE); if (validSavedPosSatE && (gpsUnixSeconds - timeOfSavedPosSatE) < (gpsParameters->timeDiffVelocityMax)) { VectorOperations::subtract(posSatE, savedPosSatE, deltaDistance, 3); @@ -581,6 +589,7 @@ void SensorProcessing::processGps(const double gpsLatitude, const double gpsLong if (pg.getReadResult() == returnvalue::OK) { gpsDataProcessed->gdLongitude.value = gdLongitude; gpsDataProcessed->gcLatitude.value = gcLatitude; + gpsDataProcessed->altitude.value = altitude; std::memcpy(gpsDataProcessed->gpsPosition.value, posSatE, 3 * sizeof(double)); std::memcpy(gpsDataProcessed->gpsVelocity.value, gpsVelocityE, 3 * sizeof(double)); gpsDataProcessed->setValidity(validGps, true); diff --git a/mission/controller/acs/SensorValues.h b/mission/controller/acs/SensorValues.h index 79c3dfe1..25946d0b 100644 --- a/mission/controller/acs/SensorValues.h +++ b/mission/controller/acs/SensorValues.h @@ -1,17 +1,16 @@ #ifndef SENSORVALUES_H_ #define SENSORVALUES_H_ +#include +#include +#include +#include +#include #include #include #include #include -#include "fsfw_hal/devicehandlers/GyroL3GD20Handler.h" -#include "fsfw_hal/devicehandlers/MgmLIS3MDLHandler.h" -#include "fsfw_hal/devicehandlers/MgmRM3100Handler.h" -#include "linux/devices/devicedefinitions/StarTrackerDefinitions.h" -#include "mission/devices/devicedefinitions/GPSDefinitions.h" - namespace ACS { class SensorValues { diff --git a/mission/controller/controllerdefinitions/AcsCtrlDefinitions.h b/mission/controller/controllerdefinitions/AcsCtrlDefinitions.h index c3509a04..deb78152 100644 --- a/mission/controller/controllerdefinitions/AcsCtrlDefinitions.h +++ b/mission/controller/controllerdefinitions/AcsCtrlDefinitions.h @@ -86,6 +86,7 @@ enum PoolIds : lp_id_t { // GPS Processed GC_LATITUDE, GD_LONGITUDE, + ALTITUDE, GPS_POSITION, GPS_VELOCITY, // MEKF @@ -228,6 +229,7 @@ class GpsDataProcessed : public StaticLocalDataSet { lp_var_t gcLatitude = lp_var_t(sid.objectId, GC_LATITUDE, this); lp_var_t gdLongitude = lp_var_t(sid.objectId, GD_LONGITUDE, this); + lp_var_t altitude = lp_var_t(sid.objectId, ALTITUDE, this); lp_vec_t gpsPosition = lp_vec_t(sid.objectId, GPS_POSITION, this); lp_vec_t gpsVelocity = lp_vec_t(sid.objectId, GPS_VELOCITY, this); From 82966eed319c34370bf45de3e947ec4b9af97a8f Mon Sep 17 00:00:00 2001 From: meggert Date: Tue, 7 Mar 2023 11:13:00 +0100 Subject: [PATCH 023/112] changelog --- CHANGELOG.md | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/CHANGELOG.md b/CHANGELOG.md index 4ef271de..cc73f13b 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -16,6 +16,11 @@ will consitute of a breaking change warranting a new major release: # [unreleased] +## Added +- `SensorProcessing` now includes an FDIR for GPS altitude. If the measured GPS altitude is out + of bounds of the range defined in the `AcsParameters`, the altitude defaults to an altitude + set in the `AcsParameters`. + ## Fixed - `AcsParameters` setter were previously all for scalar parameters. Now vector and matrix From 903c0c82580b73e53d753b2c68b7d79d9fcc792c Mon Sep 17 00:00:00 2001 From: meggert Date: Tue, 7 Mar 2023 11:25:06 +0100 Subject: [PATCH 024/112] fixed gpsDataProcessed dataSet size --- mission/controller/controllerdefinitions/AcsCtrlDefinitions.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/mission/controller/controllerdefinitions/AcsCtrlDefinitions.h b/mission/controller/controllerdefinitions/AcsCtrlDefinitions.h index deb78152..f82e75f1 100644 --- a/mission/controller/controllerdefinitions/AcsCtrlDefinitions.h +++ b/mission/controller/controllerdefinitions/AcsCtrlDefinitions.h @@ -110,7 +110,7 @@ static constexpr uint8_t SUS_SET_RAW_ENTRIES = 12; static constexpr uint8_t SUS_SET_PROCESSED_ENTRIES = 15; static constexpr uint8_t GYR_SET_RAW_ENTRIES = 4; static constexpr uint8_t GYR_SET_PROCESSED_ENTRIES = 5; -static constexpr uint8_t GPS_SET_PROCESSED_ENTRIES = 4; +static constexpr uint8_t GPS_SET_PROCESSED_ENTRIES = 5; static constexpr uint8_t MEKF_SET_ENTRIES = 3; static constexpr uint8_t CTRL_VAL_SET_ENTRIES = 4; static constexpr uint8_t ACT_CMD_SET_ENTRIES = 3; From fd405e61a4ee9d762e382fee709d64db17e73176 Mon Sep 17 00:00:00 2001 From: meggert Date: Tue, 7 Mar 2023 13:53:46 +0100 Subject: [PATCH 025/112] fixed scaling of mtq dipole commands --- mission/controller/acs/ActuatorCmd.cpp | 13 +++++-------- 1 file changed, 5 insertions(+), 8 deletions(-) diff --git a/mission/controller/acs/ActuatorCmd.cpp b/mission/controller/acs/ActuatorCmd.cpp index cbe6b504..37212113 100644 --- a/mission/controller/acs/ActuatorCmd.cpp +++ b/mission/controller/acs/ActuatorCmd.cpp @@ -55,14 +55,11 @@ void ActuatorCmd::cmdDipolMtq(const double *dipolMoment, int16_t *dipolMomentAct MatrixOperations::multiply(inverseAlignment, dipolMoment, dipolMomentActuatorDouble, 3, 3, 1); // Scaling along largest element if dipol exceeds maximum - double maxValue = 0; - for (int i = 0; i < 3; i++) { - if (abs(dipolMomentActuator[i]) > maxDipol) { - maxValue = abs(dipolMomentActuator[i]); - } - } - if (maxValue > maxDipol) { - double scalingFactor = maxDipol / maxValue; + uint8_t maxIdx = 0; + VectorOperations::maxAbsValue(dipolMomentActuatorDouble, 3, &maxIdx); + double maxAbsValue = abs(dipolMomentActuatorDouble[maxIdx]); + if (maxAbsValue > maxDipol) { + double scalingFactor = maxDipol / maxAbsValue; VectorOperations::mulScalar(dipolMomentActuatorDouble, scalingFactor, dipolMomentActuatorDouble, 3); } From 1cc39bb6d7729ad0d75a5ca2aeed32f9cd4c454d Mon Sep 17 00:00:00 2001 From: meggert Date: Tue, 7 Mar 2023 13:57:45 +0100 Subject: [PATCH 026/112] changelog --- CHANGELOG.md | 2 ++ 1 file changed, 2 insertions(+) diff --git a/CHANGELOG.md b/CHANGELOG.md index cc73f13b..f9275219 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -34,6 +34,8 @@ will consitute of a breaking change warranting a new major release: - Fixed Idle Mode Controller never calling `ptgLaw` and therefore never calculating control values. - Fixed wrong check on wether file used for persistant boolean flag on successful still existed. +- Scaling of MTQ Cmds now scales the current values to command with the current values and not + the values of the last step, which would result in undefined behaviour. ## Changed From 72ab4b1a24c794cf334a98dacd4a79066ad69424 Mon Sep 17 00:00:00 2001 From: meggert Date: Tue, 7 Mar 2023 14:07:37 +0100 Subject: [PATCH 027/112] fixed naming collision with file for solar deployment --- mission/controller/AcsController.cpp | 2 +- mission/controller/acs/Guidance.h | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/mission/controller/AcsController.cpp b/mission/controller/AcsController.cpp index c3149c38..439fcc68 100644 --- a/mission/controller/AcsController.cpp +++ b/mission/controller/AcsController.cpp @@ -196,7 +196,7 @@ void AcsController::performSafe() { updateCtrlValData(errAng); updateActuatorCmdData(cmdDipolMtqs); - // commandActuators(cmdDipolMtqs[0], cmdDipolMtqs[1], cmdDipolMtqs[2]/*500, 500, 500*/, + // commandActuators(cmdDipolMtqs[0], cmdDipolMtqs[1], cmdDipolMtqs[2], // acsParameters.magnetorquesParameter.torqueDuration, 0, 0, 0, 0, // acsParameters.rwHandlingParameters.rampTime); } diff --git a/mission/controller/acs/Guidance.h b/mission/controller/acs/Guidance.h index c7f465f8..f3369092 100644 --- a/mission/controller/acs/Guidance.h +++ b/mission/controller/acs/Guidance.h @@ -62,8 +62,8 @@ class Guidance { double savedQuaternion[4] = {0, 0, 0, 0}; double omegaRefSaved[3] = {0, 0, 0}; - static constexpr char SD_0_SKEWED_PTG_FILE[] = "/mnt/sd0/conf/deployment"; - static constexpr char SD_1_SKEWED_PTG_FILE[] = "/mnt/sd1/conf/deployment"; + static constexpr char SD_0_SKEWED_PTG_FILE[] = "/mnt/sd0/conf/acsDeploymentConfirm"; + static constexpr char SD_1_SKEWED_PTG_FILE[] = "/mnt/sd1/conf/acsDeploymentConfirm"; }; #endif /* ACS_GUIDANCE_H_ */ From 5b0db43e0fab8c628decc2d8ca34351d0a05df99 Mon Sep 17 00:00:00 2001 From: meggert Date: Tue, 7 Mar 2023 14:15:33 +0100 Subject: [PATCH 028/112] changelog --- CHANGELOG.md | 2 ++ 1 file changed, 2 insertions(+) diff --git a/CHANGELOG.md b/CHANGELOG.md index f9275219..0f103ae4 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -36,6 +36,8 @@ will consitute of a breaking change warranting a new major release: - Fixed wrong check on wether file used for persistant boolean flag on successful still existed. - Scaling of MTQ Cmds now scales the current values to command with the current values and not the values of the last step, which would result in undefined behaviour. +- Solved naming collision between file used for solar array deployment and confirmation for + ACS for solar array deployment. ## Changed From 1154c0e887861588b9e5120a25b8718faec9cb5d Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Wed, 8 Mar 2023 18:56:27 +0100 Subject: [PATCH 029/112] move acs event handling to system --- CHANGELOG.md | 1 + mission/system/objects/AcsSubsystem.cpp | 85 +------------------------ mission/system/objects/AcsSubsystem.h | 6 -- mission/system/objects/EiveSystem.cpp | 77 +++++++++++++++++++++- mission/system/objects/EiveSystem.h | 5 ++ 5 files changed, 83 insertions(+), 91 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 24b73ff8..f163ce30 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -26,6 +26,7 @@ will consitute of a breaking change warranting a new major release: ## Changed +- Move ACS event handling to system component. - Persistent TM stores will now create new files on each reboot. - Fast ACS subsystem commanding: Command SUS board consecutively with other devices now - Star Tracker: Use ground confguration for EM and flight config for FM by default. diff --git a/mission/system/objects/AcsSubsystem.cpp b/mission/system/objects/AcsSubsystem.cpp index e4969ac1..873d88cf 100644 --- a/mission/system/objects/AcsSubsystem.cpp +++ b/mission/system/objects/AcsSubsystem.cpp @@ -8,90 +8,7 @@ AcsSubsystem::AcsSubsystem(object_id_t setObjectId, uint32_t maxNumberOfSequences, uint32_t maxNumberOfTables) - : Subsystem(setObjectId, maxNumberOfSequences, maxNumberOfTables) { - auto mqArgs = MqArgs(getObjectId(), static_cast(this)); - eventQueue = - QueueFactory::instance()->createMessageQueue(10, EventMessage::EVENT_MESSAGE_SIZE, &mqArgs); -} - -ReturnValue_t AcsSubsystem::initialize() { - EventManagerIF* manager = ObjectManager::instance()->get(objects::EVENT_MANAGER); - if (manager == nullptr) { -#if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "AcsSubsystem::initialize: Invalid event manager" << std::endl; -#endif - return ObjectManagerIF::CHILD_INIT_FAILED; - } - ReturnValue_t result = manager->registerListener(eventQueue->getId()); - if (result != returnvalue::OK) { -#if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::warning << "AcsSubsystem::registerListener: Failed to register as " - "listener" - << std::endl; -#endif - return ObjectManagerIF::CHILD_INIT_FAILED; - ; - } - result = - manager->subscribeToEvent(eventQueue->getId(), event::getEventId(acs::SAFE_RATE_VIOLATION)); - if (result != returnvalue::OK) { - sif::error << "AcsSubsystem: Subscribing for acs::SAFE_RATE_VIOLATION failed" << std::endl; - } - result = - manager->subscribeToEvent(eventQueue->getId(), event::getEventId(acs::SAFE_RATE_RECOVERY)); - if (result != returnvalue::OK) { - sif::error << "AcsSubsystem: Subscribing for acs::SAFE_RATE_RECOVERY failed" << std::endl; - } - result = - manager->subscribeToEvent(eventQueue->getId(), event::getEventId(acs::MULTIPLE_RW_INVALID)); - if (result != returnvalue::OK) { - sif::error << "AcsSubsystem: Subscribing for acs::MULTIPLE_RW_INVALID failed" << std::endl; - } - result = manager->subscribeToEvent(eventQueue->getId(), - event::getEventId(acs::MEKF_INVALID_MODE_VIOLATION)); - if (result != returnvalue::OK) { - sif::error << "AcsSubsystem: Subscribing for acs::MULTIPLE_RW_INVALID failed" << std::endl; - } - return Subsystem::initialize(); -} - -void AcsSubsystem::performChildOperation() { - handleEventMessages(); - return Subsystem::performChildOperation(); -} - -void AcsSubsystem::handleEventMessages() { - EventMessage event; - for (ReturnValue_t result = eventQueue->receiveMessage(&event); result == returnvalue::OK; - result = eventQueue->receiveMessage(&event)) { - ReturnValue_t status; - switch (event.getMessageId()) { - case EventMessage::EVENT_MESSAGE: - if (event.getEvent() == acs::SAFE_RATE_VIOLATION) { - CommandMessage msg; - ModeMessage::setCmdModeMessage(msg, acs::AcsMode::DETUMBLE, 0); - status = commandQueue->sendMessage(commandQueue->getId(), &msg); - if (result != returnvalue::OK) { - sif::error << "AcsSubsystem: sending DETUMBLE mode cmd to self has failed" << std::endl; - } - } - if (event.getEvent() == acs::SAFE_RATE_RECOVERY) { - CommandMessage msg; - ModeMessage::setCmdModeMessage(msg, acs::AcsMode::SAFE, 0); - status = commandQueue->sendMessage(commandQueue->getId(), &msg); - if (status != returnvalue::OK) { - sif::error << "AcsSubsystem: sending SAFE mode cmd to self has failed" << std::endl; - } - } - break; - default: - sif::debug << "AcsSubsystem::performChildOperation: Did not subscribe " - "to this event message" - << std::endl; - break; - } - } -} + : Subsystem(setObjectId, maxNumberOfSequences, maxNumberOfTables) {} void AcsSubsystem::announceMode(bool recursive) { const char* modeStr = acs::getModeStr(static_cast(mode)); diff --git a/mission/system/objects/AcsSubsystem.h b/mission/system/objects/AcsSubsystem.h index c6c77fef..fc6b238e 100644 --- a/mission/system/objects/AcsSubsystem.h +++ b/mission/system/objects/AcsSubsystem.h @@ -8,13 +8,7 @@ class AcsSubsystem : public Subsystem { AcsSubsystem(object_id_t setObjectId, uint32_t maxNumberOfSequences, uint32_t maxNumberOfTables); private: - ReturnValue_t initialize() override; - void performChildOperation() override; void announceMode(bool recursive) override; - - void handleEventMessages(); - - MessageQueueIF* eventQueue = nullptr; }; #endif /* MISSION_SYSTEM_ACSSUBSYSTEM_H_ */ diff --git a/mission/system/objects/EiveSystem.cpp b/mission/system/objects/EiveSystem.cpp index 26707bf1..003c5154 100644 --- a/mission/system/objects/EiveSystem.cpp +++ b/mission/system/objects/EiveSystem.cpp @@ -1,10 +1,16 @@ #include "EiveSystem.h" +#include +#include #include EiveSystem::EiveSystem(object_id_t setObjectId, uint32_t maxNumberOfSequences, uint32_t maxNumberOfTables) - : Subsystem(setObjectId, maxNumberOfSequences, maxNumberOfTables) {} + : Subsystem(setObjectId, maxNumberOfSequences, maxNumberOfTables) { + auto mqArgs = MqArgs(getObjectId(), static_cast(this)); + eventQueue = + QueueFactory::instance()->createMessageQueue(10, EventMessage::EVENT_MESSAGE_SIZE, &mqArgs); +} void EiveSystem::announceMode(bool recursive) { const char* modeStr = "UNKNOWN"; @@ -41,3 +47,72 @@ void EiveSystem::announceMode(bool recursive) { sif::info << "EIVE system is now in " << modeStr << " mode" << std::endl; return Subsystem::announceMode(recursive); } + +void EiveSystem::performChildOperation() { + handleEventMessages(); + return Subsystem::performChildOperation(); +} + +ReturnValue_t EiveSystem::initialize() { + EventManagerIF* manager = ObjectManager::instance()->get(objects::EVENT_MANAGER); + if (manager == nullptr) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::error << "AcsSubsystem::initialize: Invalid event manager" << std::endl; +#endif + return ObjectManagerIF::CHILD_INIT_FAILED; + } + ReturnValue_t result = manager->registerListener(eventQueue->getId()); + if (result != returnvalue::OK) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::warning << "AcsSubsystem::registerListener: Failed to register as " + "listener" + << std::endl; +#endif + return ObjectManagerIF::CHILD_INIT_FAILED; + ; + } + result = + manager->subscribeToEvent(eventQueue->getId(), event::getEventId(acs::MULTIPLE_RW_INVALID)); + if (result != returnvalue::OK) { + sif::error << "AcsSubsystem: Subscribing for acs::MULTIPLE_RW_INVALID failed" << std::endl; + } + result = manager->subscribeToEvent(eventQueue->getId(), + event::getEventId(acs::MEKF_INVALID_MODE_VIOLATION)); + if (result != returnvalue::OK) { + sif::error << "AcsSubsystem: Subscribing for acs::MULTIPLE_RW_INVALID failed" << std::endl; + } + return returnvalue::OK; +} + +void EiveSystem::handleEventMessages() { + EventMessage event; + for (ReturnValue_t result = eventQueue->receiveMessage(&event); result == returnvalue::OK; + result = eventQueue->receiveMessage(&event)) { + ReturnValue_t status; + switch (event.getMessageId()) { + case EventMessage::EVENT_MESSAGE: + if (event.getEvent() == acs::SAFE_RATE_VIOLATION) { + CommandMessage msg; + ModeMessage::setCmdModeMessage(msg, acs::AcsMode::DETUMBLE, 0); + status = commandQueue->sendMessage(commandQueue->getId(), &msg); + if (result != returnvalue::OK) { + sif::error << "AcsSubsystem: sending DETUMBLE mode cmd to self has failed" << std::endl; + } + } + if (event.getEvent() == acs::SAFE_RATE_RECOVERY) { + CommandMessage msg; + ModeMessage::setCmdModeMessage(msg, acs::AcsMode::SAFE, 0); + status = commandQueue->sendMessage(commandQueue->getId(), &msg); + if (status != returnvalue::OK) { + sif::error << "AcsSubsystem: sending SAFE mode cmd to self has failed" << std::endl; + } + } + break; + default: + sif::debug << "AcsSubsystem::performChildOperation: Did not subscribe " + "to this event message" + << std::endl; + break; + } + } +} diff --git a/mission/system/objects/EiveSystem.h b/mission/system/objects/EiveSystem.h index 59acf82e..0d75b31a 100644 --- a/mission/system/objects/EiveSystem.h +++ b/mission/system/objects/EiveSystem.h @@ -8,7 +8,12 @@ class EiveSystem : public Subsystem { EiveSystem(object_id_t setObjectId, uint32_t maxNumberOfSequences, uint32_t maxNumberOfTables); private: + ReturnValue_t initialize() override; + void performChildOperation() override; void announceMode(bool recursive) override; + void handleEventMessages(); + + MessageQueueIF* eventQueue = nullptr; }; #endif /* MISSION_SYSTEM_EIVESYSTEM_H_ */ From c1b43bb5049a7563b2f2e5c264c98ca742884761 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Wed, 8 Mar 2023 22:34:30 +0100 Subject: [PATCH 030/112] bump deps --- fsfw | 2 +- tmtc | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/fsfw b/fsfw index 26e44451..23d9b44b 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit 26e4445189b676eaee11840e5a9d0ede25cf3896 +Subproject commit 23d9b44b3e02bb0d35e4622d125b48e9b44fee2c diff --git a/tmtc b/tmtc index a3e03350..ffd2eb11 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit a3e03350faf3055835e65e744bc177761448ce20 +Subproject commit ffd2eb11f8ed9095ca545acbdec45b41fe874f17 From 21899d663ea9c953de4211225c18720bdc0fd77c Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 9 Mar 2023 01:32:27 +0100 Subject: [PATCH 031/112] start groundwork for new TM downlink arch --- bsp_q7s/boardconfig/busConf.h | 4 ++ bsp_q7s/core/ObjectFactory.cpp | 58 +++++++++---------- bsp_q7s/core/ObjectFactory.h | 4 +- bsp_q7s/fmObjectFactory.cpp | 7 ++- common/config/eive/objects.h | 4 ++ linux/ObjectFactory.cpp | 6 +- linux/ipcore/Ptme.h | 11 ++-- mission/core/GenericFactory.cpp | 11 ++++ mission/core/GenericFactory.h | 1 + mission/tmtc/CMakeLists.txt | 3 + mission/tmtc/CcsdsIpCoreHandler.cpp | 88 +++++++++++++---------------- mission/tmtc/CcsdsIpCoreHandler.h | 15 ++--- mission/tmtc/PersistentTmStore.cpp | 60 -------------------- mission/tmtc/PersistentTmStore.h | 16 +----- mission/tmtc/PusPacketFilter.cpp | 64 +++++++++++++++++++++ mission/tmtc/PusPacketFilter.h | 24 ++++++++ mission/tmtc/PusTmFunnel.cpp | 88 ++++++++++------------------- mission/tmtc/PusTmFunnel.h | 9 +-- mission/tmtc/TmStoreRouter.cpp | 19 +++++++ mission/tmtc/TmStoreRouter.h | 18 ++++++ mission/tmtc/VirtualChannel.cpp | 60 ++++++++++---------- mission/tmtc/VirtualChannel.h | 10 ++-- mission/tmtc/tmFilters.cpp | 51 +++++++++++++++++ mission/tmtc/tmFilters.h | 14 +++++ 24 files changed, 379 insertions(+), 266 deletions(-) create mode 100644 mission/tmtc/PusPacketFilter.cpp create mode 100644 mission/tmtc/PusPacketFilter.h create mode 100644 mission/tmtc/TmStoreRouter.cpp create mode 100644 mission/tmtc/TmStoreRouter.h create mode 100644 mission/tmtc/tmFilters.cpp create mode 100644 mission/tmtc/tmFilters.h diff --git a/bsp_q7s/boardconfig/busConf.h b/bsp_q7s/boardconfig/busConf.h index a094c029..4c142644 100644 --- a/bsp_q7s/boardconfig/busConf.h +++ b/bsp_q7s/boardconfig/busConf.h @@ -28,9 +28,13 @@ static constexpr char UIO_PDEC_IRQ[] = "/dev/uio_pdec_irq"; static constexpr int MAP_ID_PTME_CONFIG = 3; namespace uiomapids { +// Live TM static const int PTME_VC0 = 0; +// OK/NOK/MISC Store static const int PTME_VC1 = 1; +// HK store static const int PTME_VC2 = 2; +// CFDP static const int PTME_VC3 = 3; static const int PTME_CONFIG = 4; } // namespace uiomapids diff --git a/bsp_q7s/core/ObjectFactory.cpp b/bsp_q7s/core/ObjectFactory.cpp index d078916f..ee58b109 100644 --- a/bsp_q7s/core/ObjectFactory.cpp +++ b/bsp_q7s/core/ObjectFactory.cpp @@ -62,6 +62,7 @@ #include "mission/system/tree/comModeTree.h" #include "mission/system/tree/payloadModeTree.h" #include "mission/system/tree/tcsModeTree.h" +#include "mission/tmtc/tmFilters.h" #include "mission/utility/GlobalConfigHandler.h" #include "tmtc/pusIds.h" #if OBSW_TEST_LIBGPIOD == 1 @@ -715,39 +716,27 @@ void ObjectFactory::createReactionWheelComponents(LinuxLibgpioIF* gpioComIF, } ReturnValue_t ObjectFactory::createCcsdsComponents(LinuxLibgpioIF* gpioComIF, + PusTmFunnel& pusFunnel, CcsdsIpCoreHandler** ipCoreHandler) { using namespace gpio; // GPIO definitions of signals connected to the virtual channel interfaces of the PTME IP Core GpioCookie* gpioCookiePtmeIp = new GpioCookie; GpiodRegularByLineName* gpio = nullptr; - std::stringstream consumer; - consumer.str("PAPB VC0"); - gpio = new GpiodRegularByLineName(q7s::gpioNames::PAPB_BUSY_SIGNAL_VC0, consumer.str()); + gpio = new GpiodRegularByLineName(q7s::gpioNames::PAPB_BUSY_SIGNAL_VC0, "PAPB VC0"); gpioCookiePtmeIp->addGpio(gpioIds::VC0_PAPB_BUSY, gpio); - consumer.str("PAPB VC0"); - gpio = new GpiodRegularByLineName(q7s::gpioNames::PAPB_EMPTY_SIGNAL_VC0, consumer.str()); + gpio = new GpiodRegularByLineName(q7s::gpioNames::PAPB_EMPTY_SIGNAL_VC0, "PAPB VC0"); gpioCookiePtmeIp->addGpio(gpioIds::VC0_PAPB_EMPTY, gpio); - consumer.str("PAPB VC 1"); - gpio = new GpiodRegularByLineName(q7s::gpioNames::PAPB_BUSY_SIGNAL_VC1, consumer.str()); + gpio = new GpiodRegularByLineName(q7s::gpioNames::PAPB_BUSY_SIGNAL_VC1, "PAPB VC1"); gpioCookiePtmeIp->addGpio(gpioIds::VC1_PAPB_BUSY, gpio); - consumer.str(""); - consumer.str("PAPB VC 1"); + gpio = new GpiodRegularByLineName(q7s::gpioNames::PAPB_EMPTY_SIGNAL_VC1, "PAPB VC1"); gpioCookiePtmeIp->addGpio(gpioIds::VC1_PAPB_EMPTY, gpio); - consumer.str(""); - consumer.str("PAPB VC 2"); - gpio = new GpiodRegularByLineName(q7s::gpioNames::PAPB_BUSY_SIGNAL_VC2, consumer.str()); + gpio = new GpiodRegularByLineName(q7s::gpioNames::PAPB_BUSY_SIGNAL_VC2, "PAPB VC2"); gpioCookiePtmeIp->addGpio(gpioIds::VC2_PAPB_BUSY, gpio); - consumer.str(""); - consumer.str("PAPB VC 2"); - gpio = new GpiodRegularByLineName(q7s::gpioNames::PAPB_EMPTY_SIGNAL_VC2, consumer.str()); + gpio = new GpiodRegularByLineName(q7s::gpioNames::PAPB_EMPTY_SIGNAL_VC2, "PAPB VC2"); gpioCookiePtmeIp->addGpio(gpioIds::VC2_PAPB_EMPTY, gpio); - consumer.str(""); - consumer.str("PAPB VC 3"); - gpio = new GpiodRegularByLineName(q7s::gpioNames::PAPB_BUSY_SIGNAL_VC3, consumer.str()); + gpio = new GpiodRegularByLineName(q7s::gpioNames::PAPB_BUSY_SIGNAL_VC3, "PAPB VC3"); gpioCookiePtmeIp->addGpio(gpioIds::VC3_PAPB_BUSY, gpio); - consumer.str(""); - consumer.str("PAPB VC 3"); - gpio = new GpiodRegularByLineName(q7s::gpioNames::PAPB_EMPTY_SIGNAL_VC3, consumer.str()); + gpio = new GpiodRegularByLineName(q7s::gpioNames::PAPB_EMPTY_SIGNAL_VC3, "PAPB VC3"); gpioCookiePtmeIp->addGpio(gpioIds::VC3_PAPB_EMPTY, gpio); gpioChecker(gpioComIF->addGpios(gpioCookiePtmeIp), "PTME PAPB VCs"); // Creating virtual channel interfaces @@ -773,17 +762,26 @@ ReturnValue_t ObjectFactory::createCcsdsComponents(LinuxLibgpioIF* gpioComIF, new AxiPtmeConfig(objects::AXI_PTME_CONFIG, q7s::UIO_PTME, q7s::uiomapids::PTME_CONFIG); PtmeConfig* ptmeConfig = new PtmeConfig(objects::PTME_CONFIG, axiPtmeConfig); - *ipCoreHandler = new CcsdsIpCoreHandler(objects::CCSDS_HANDLER, objects::PTME, - objects::CCSDS_PACKET_DISTRIBUTOR, ptmeConfig, gpioComIF, - gpioIds::RS485_EN_TX_CLOCK, gpioIds::RS485_EN_TX_DATA); + *ipCoreHandler = new CcsdsIpCoreHandler(objects::CCSDS_HANDLER, objects::CCSDS_PACKET_DISTRIBUTOR, + *ptme, *ptmeConfig, gpioComIF, gpioIds::RS485_EN_TX_CLOCK, + gpioIds::RS485_EN_TX_DATA); VirtualChannel* vc = nullptr; - vc = new VirtualChannel(ccsds::VC0, config::VC0_QUEUE_SIZE, objects::CCSDS_HANDLER); + vc = new VirtualChannel(objects::PTME_VC0_LIVE_TM, ccsds::VC0, "PTME VC0 LIVE TM", + config::VC0_QUEUE_SIZE); (*ipCoreHandler)->addVirtualChannel(ccsds::VC0, vc); - vc = new VirtualChannel(ccsds::VC1, config::VC1_QUEUE_SIZE, objects::CCSDS_HANDLER); + vc = new VirtualChannel(objects::PTME_VC1_LOG_TM, ccsds::VC1, "PTME VC1 LOG TM", + config::VC1_QUEUE_SIZE); + pusFunnel.addPersistentTmStoreRouting(filters::okFilter(), vc->getReportReceptionQueue()); + pusFunnel.addPersistentTmStoreRouting(filters::notOkFilter(), vc->getReportReceptionQueue()); + pusFunnel.addPersistentTmStoreRouting(filters::miscFilter(), vc->getReportReceptionQueue()); (*ipCoreHandler)->addVirtualChannel(ccsds::VC1, vc); - vc = new VirtualChannel(ccsds::VC2, config::VC2_QUEUE_SIZE, objects::CCSDS_HANDLER); + vc = new VirtualChannel(objects::PTME_VC2_HK_TM, ccsds::VC2, "PTME VC2 HK TM", + config::VC2_QUEUE_SIZE); + pusFunnel.addPersistentTmStoreRouting(filters::hkFilter(), vc->getReportReceptionQueue()); (*ipCoreHandler)->addVirtualChannel(ccsds::VC2, vc); - vc = new VirtualChannel(ccsds::VC3, config::VC3_QUEUE_SIZE, objects::CCSDS_HANDLER); + vc = new VirtualChannel(objects::PTME_VC3_CFDP_TM, ccsds::VC3, "PTME VC3 CFDP TM", + config::VC3_QUEUE_SIZE); + // TODO: Set VC destination in CFDP funnel. (*ipCoreHandler)->addVirtualChannel(ccsds::VC3, vc); ReturnValue_t result = (*ipCoreHandler)->connectModeTreeParent(satsystem::com::SUBSYSTEM); @@ -794,10 +792,8 @@ ReturnValue_t ObjectFactory::createCcsdsComponents(LinuxLibgpioIF* gpioComIF, } GpioCookie* gpioCookiePdec = new GpioCookie; - consumer.str(""); - consumer << "0x" << std::hex << objects::PDEC_HANDLER; // GPIO also low after linux boot (specified by device-tree) - gpio = new GpiodRegularByLineName(q7s::gpioNames::PDEC_RESET, consumer.str(), Direction::OUT, + gpio = new GpiodRegularByLineName(q7s::gpioNames::PDEC_RESET, "PDEC Handler", Direction::OUT, Levels::LOW); gpioCookiePdec->addGpio(gpioIds::PDEC_RESET, gpio); gpioChecker(gpioComIF->addGpios(gpioCookiePdec), "PDEC"); diff --git a/bsp_q7s/core/ObjectFactory.h b/bsp_q7s/core/ObjectFactory.h index 7ec6c871..0a43b336 100644 --- a/bsp_q7s/core/ObjectFactory.h +++ b/bsp_q7s/core/ObjectFactory.h @@ -8,6 +8,7 @@ #include #include #include +#include #include @@ -43,7 +44,8 @@ void createSolarArrayDeploymentComponents(PowerSwitchIF& pwrSwitcher, GpioIF& gp void createSyrlinksComponents(PowerSwitchIF* pwrSwitcher); void createPayloadComponents(LinuxLibgpioIF* gpioComIF, PowerSwitchIF& pwrSwitcher); void createReactionWheelComponents(LinuxLibgpioIF* gpioComIF, PowerSwitchIF* pwrSwitcher); -ReturnValue_t createCcsdsComponents(LinuxLibgpioIF* gpioComIF, CcsdsIpCoreHandler** ipCoreHandler); +ReturnValue_t createCcsdsComponents(LinuxLibgpioIF* gpioComIF, PusTmFunnel& pusFunnel, + CcsdsIpCoreHandler** ipCoreHandler); void createMiscComponents(); void createTestComponents(LinuxLibgpioIF* gpioComIF); diff --git a/bsp_q7s/fmObjectFactory.cpp b/bsp_q7s/fmObjectFactory.cpp index e05e8098..c8760478 100644 --- a/bsp_q7s/fmObjectFactory.cpp +++ b/bsp_q7s/fmObjectFactory.cpp @@ -12,12 +12,14 @@ #include "linux/callbacks/gpioCallbacks.h" #include "mission/core/GenericFactory.h" #include "mission/system/tree/system.h" +#include "mission/tmtc/tmFilters.h" void ObjectFactory::produce(void* args) { ObjectFactory::setStatics(); HealthTableIF* healthTable = nullptr; PusTmFunnel* pusFunnel = nullptr; CfdpTmFunnel* cfdpFunnel = nullptr; + ObjectFactory::produceGenericObjects(&healthTable, &pusFunnel, &cfdpFunnel, *SdCardManager::instance()); @@ -72,9 +74,10 @@ void ObjectFactory::produce(void* args) { #endif /* OBSW_ADD_STAR_TRACKER == 1 */ #if OBSW_ADD_CCSDS_IP_CORES == 1 CcsdsIpCoreHandler* ipCoreHandler = nullptr; - createCcsdsComponents(gpioComIF, &ipCoreHandler); + createCcsdsComponents(gpioComIF, *pusFunnel, &ipCoreHandler); #if OBSW_TM_TO_PTME == 1 - addTmtcIpCoresToFunnels(*ipCoreHandler, *pusFunnel, *cfdpFunnel); + // TODO: Remove this if not needed anymore + // addTmtcIpCoresToFunnels(*ipCoreHandler, *pusFunnel, *cfdpFunnel); #endif #endif /* OBSW_ADD_CCSDS_IP_CORES == 1 */ diff --git a/common/config/eive/objects.h b/common/config/eive/objects.h index cb468ef2..bbab8a0a 100644 --- a/common/config/eive/objects.h +++ b/common/config/eive/objects.h @@ -66,6 +66,10 @@ enum commonObjects : uint32_t { PLOC_MPSOC_HELPER = 0x44330003, AXI_PTME_CONFIG = 0x44330004, PTME_CONFIG = 0x44330005, + PTME_VC0_LIVE_TM = 0x44330006, + PTME_VC1_LOG_TM = 0x44330007, + PTME_VC2_HK_TM = 0x44330008, + PTME_VC3_CFDP_TM = 0x44330009, PLOC_MPSOC_HANDLER = 0x44330015, PLOC_SUPERVISOR_HANDLER = 0x44330016, PLOC_SUPERVISOR_HELPER = 0x44330017, diff --git a/linux/ObjectFactory.cpp b/linux/ObjectFactory.cpp index e9154ba1..43ea9e70 100644 --- a/linux/ObjectFactory.cpp +++ b/linux/ObjectFactory.cpp @@ -344,6 +344,8 @@ void ObjectFactory::gpioChecker(ReturnValue_t result, std::string output) { void ObjectFactory::addTmtcIpCoresToFunnels(CcsdsIpCoreHandler& ipCoreHandler, PusTmFunnel& pusFunnel, CfdpTmFunnel& cfdpFunnel) { - cfdpFunnel.addDestination("PTME IP Core", ipCoreHandler, config::LIVE_TM); - pusFunnel.addDestination("PTME IP Core", ipCoreHandler, config::LIVE_TM); + // TODO: Consider removing this, the only additional object in the dest list will + // be the live VC + // cfdpFunnel.addDestination("PTME IP Core", ipCoreHandler, config::LIVE_TM); + // pusFunnel.addDestination("PTME IP Core", ipCoreHandler, config::LIVE_TM); } diff --git a/linux/ipcore/Ptme.h b/linux/ipcore/Ptme.h index 2de85a38..d826ac57 100644 --- a/linux/ipcore/Ptme.h +++ b/linux/ipcore/Ptme.h @@ -13,10 +13,13 @@ #include "linux/ipcore/VcInterfaceIF.h" /** - * @brief This class handles the interfacing to the telemetry (PTME) IP core responsible for the - * encoding of telemetry packets according to the CCSDS standards CCSDS 131.0-B-3 (TM - * Synchro- nization and channel coding) and CCSDS 132.0-B-2 (TM Space Data Link Protocoll). The IP - * cores are implemented on the programmable logic and are accessible through the linux UIO driver. + * @brief This class handles the interfacing to the telemetry (PTME) IP core. + * + * @details + * This module is responsible for the encoding of telemetry packets according to the CCSDS + * standards CCSDS 131.0-B-3 (TM Synchronization and channel coding) and CCSDS 132.0-B-2 + * (TM Space Data Link Protocoll). The IP cores are implemented on the programmable logic and are + * accessible through the linux UIO driver. */ class Ptme : public PtmeIF, public SystemObject { public: diff --git a/mission/core/GenericFactory.cpp b/mission/core/GenericFactory.cpp index b6119eda..01871ff2 100644 --- a/mission/core/GenericFactory.cpp +++ b/mission/core/GenericFactory.cpp @@ -33,8 +33,11 @@ #include #include #include +#include +#include #include #include +#include #include "OBSWConfig.h" #include "devices/gpioIds.h" @@ -144,6 +147,14 @@ void ObjectFactory::produceGenericObjects(HealthTableIF** healthTable_, PusTmFun PusTmFunnel::FunnelCfg cfdpFunnelCfg(objects::CFDP_TM_FUNNEL, "CfdpTmFunnel", *tmStore, *ipcStore, 50); *cfdpFunnel = new CfdpTmFunnel(cfdpFunnelCfg, config::EIVE_CFDP_APID); + auto* miscStore = new PersistentTmStore(objects::MISC_TM_STORE, "tm", "misc", + RolloverInterval::HOURLY, 2, *tmStore, sdcMan); + auto* okStore = new PersistentTmStore(objects::OK_TM_STORE, "tm", "ok", + RolloverInterval::MINUTELY, 30, *tmStore, sdcMan); + auto* notOkStore = new PersistentTmStore(objects::NOT_OK_TM_STORE, "tm", "nok", + RolloverInterval::MINUTELY, 30, *tmStore, sdcMan); + auto* hkStore = new PersistentTmStore(objects::HK_TM_STORE, "tm", "hk", + RolloverInterval::MINUTELY, 15, *tmStore, sdcMan); PusTmFunnel::FunnelCfg pusFunnelCfg(objects::PUS_TM_FUNNEL, "PusTmFunnel", *tmStore, *ipcStore, config::MAX_PUS_FUNNEL_QUEUE_DEPTH); *pusFunnel = new PusTmFunnel(pusFunnelCfg, *timeStamper, sdcMan); diff --git a/mission/core/GenericFactory.h b/mission/core/GenericFactory.h index 5902ff7b..8663d696 100644 --- a/mission/core/GenericFactory.h +++ b/mission/core/GenericFactory.h @@ -3,6 +3,7 @@ #include #include +#include #include "fsfw/objectmanager/SystemObjectIF.h" #include "fsfw/power/PowerSwitchIF.h" diff --git a/mission/tmtc/CMakeLists.txt b/mission/tmtc/CMakeLists.txt index c4c93ab6..ef97002c 100644 --- a/mission/tmtc/CMakeLists.txt +++ b/mission/tmtc/CMakeLists.txt @@ -5,6 +5,9 @@ target_sources( TmFunnelHandler.cpp TmFunnelBase.cpp CfdpTmFunnel.cpp + tmFilters.cpp + PusPacketFilter.cpp + TmStoreRouter.cpp Service15TmStorage.cpp PersistentTmStore.cpp PusTmFunnel.cpp) diff --git a/mission/tmtc/CcsdsIpCoreHandler.cpp b/mission/tmtc/CcsdsIpCoreHandler.cpp index b462f236..a0cb8d28 100644 --- a/mission/tmtc/CcsdsIpCoreHandler.cpp +++ b/mission/tmtc/CcsdsIpCoreHandler.cpp @@ -12,11 +12,11 @@ #include "fsfw/serviceinterface/serviceInterfaceDefintions.h" #include "mission/devices/devicedefinitions/SyrlinksDefinitions.h" -CcsdsIpCoreHandler::CcsdsIpCoreHandler(object_id_t objectId, object_id_t ptmeId, - object_id_t tcDestination, PtmeConfig* ptmeConfig, - GpioIF* gpioIF, gpioId_t enTxClock, gpioId_t enTxData) +CcsdsIpCoreHandler::CcsdsIpCoreHandler(object_id_t objectId, object_id_t tcDestination, + PtmeIF& ptme, PtmeConfig& ptmeConfig, GpioIF* gpioIF, + gpioId_t enTxClock, gpioId_t enTxData) : SystemObject(objectId), - ptmeId(ptmeId), + ptme(ptme), tcDestination(tcDestination), parameterHelper(this), actionHelper(this, nullptr), @@ -35,28 +35,20 @@ CcsdsIpCoreHandler::~CcsdsIpCoreHandler() {} ReturnValue_t CcsdsIpCoreHandler::performOperation(uint8_t operationCode) { readCommandQueue(); - handleTelemetry(); - handleTelecommands(); + // handleTelemetry(); return returnvalue::OK; } -void CcsdsIpCoreHandler::handleTelemetry() { - VirtualChannelMapIter iter; - for (iter = virtualChannelMap.begin(); iter != virtualChannelMap.end(); iter++) { - iter->second->performOperation(); - } -} - -void CcsdsIpCoreHandler::handleTelecommands() {} +// TODO: TM is sent to the respective VCs directly. +// void CcsdsIpCoreHandler::handleTelemetry() { +// VirtualChannelMapIter iter; +// for (iter = virtualChannelMap.begin(); iter != virtualChannelMap.end(); iter++) { +// iter->second->performOperation(); +// } +//} ReturnValue_t CcsdsIpCoreHandler::initialize() { ReturnValue_t result = returnvalue::OK; - PtmeIF* ptme = ObjectManager::instance()->get(ptmeId); - if (ptme == nullptr) { - sif::warning << "Invalid PTME object" << std::endl; - return ObjectManagerIF::CHILD_INIT_FAILED; - } - AcceptsTelecommandsIF* tcDistributor = ObjectManager::instance()->get(tcDestination); if (tcDistributor == nullptr) { @@ -89,10 +81,10 @@ ReturnValue_t CcsdsIpCoreHandler::initialize() { if (result != returnvalue::OK) { return result; } - iter->second->setPtmeObject(ptme); + iter->second->setPtmeObject(&ptme); } - result = ptmeConfig->initialize(); + result = ptmeConfig.initialize(); if (result != returnvalue::OK) { return ObjectManagerIF::CHILD_INIT_FAILED; } @@ -155,22 +147,22 @@ void CcsdsIpCoreHandler::addVirtualChannel(VcId_t vcId, VirtualChannel* virtualC } } -MessageQueueId_t CcsdsIpCoreHandler::getReportReceptionQueue(uint8_t virtualChannel) const { - if (virtualChannel < config::NUMBER_OF_VIRTUAL_CHANNELS) { - auto iter = virtualChannelMap.find(virtualChannel); - if (iter != virtualChannelMap.end()) { - return iter->second->getReportReceptionQueue(); - } else { - sif::warning << "CcsdsHandler::getReportReceptionQueue: Virtual channel with ID " - << static_cast(virtualChannel) << " not in virtual channel map" - << std::endl; - return MessageQueueIF::NO_QUEUE; - } - } else { - sif::debug << "CcsdsHandler::getReportReceptionQueue: Invalid virtual channel requested"; - } - return MessageQueueIF::NO_QUEUE; -} +// MessageQueueId_t CcsdsIpCoreHandler::getReportReceptionQueue(uint8_t virtualChannel) const { +// if (virtualChannel < config::NUMBER_OF_VIRTUAL_CHANNELS) { +// auto iter = virtualChannelMap.find(virtualChannel); +// if (iter != virtualChannelMap.end()) { +// return iter->second->getReportReceptionQueue(); +// } else { +// sif::warning << "CcsdsHandler::getReportReceptionQueue: Virtual channel with ID " +// << static_cast(virtualChannel) << " not in virtual channel map" +// << std::endl; +// return MessageQueueIF::NO_QUEUE; +// } +// } else { +// sif::debug << "CcsdsHandler::getReportReceptionQueue: Invalid virtual channel requested"; +// } +// return MessageQueueIF::NO_QUEUE; +// } ReturnValue_t CcsdsIpCoreHandler::getParameter(uint8_t domainId, uint8_t uniqueIdentifier, ParameterWrapper* parameterWrapper, @@ -182,7 +174,7 @@ ReturnValue_t CcsdsIpCoreHandler::getParameter(uint8_t domainId, uint8_t uniqueI uint32_t CcsdsIpCoreHandler::getIdentifier() const { return 0; } MessageQueueId_t CcsdsIpCoreHandler::getRequestQueue() const { - // Forward packets directly to TC distributor + // Forward packets directly to the CCSDS TC distributor return tcDistributorQueueId; } @@ -192,18 +184,18 @@ ReturnValue_t CcsdsIpCoreHandler::executeAction(ActionId_t actionId, MessageQueu switch (actionId) { case SET_LOW_RATE: { submode = static_cast(com::CcsdsSubmode::DATARATE_LOW); - result = ptmeConfig->setRate(RATE_100KBPS); + result = ptmeConfig.setRate(RATE_100KBPS); break; } case SET_HIGH_RATE: { submode = static_cast(com::CcsdsSubmode::DATARATE_HIGH); - result = ptmeConfig->setRate(RATE_500KBPS); + result = ptmeConfig.setRate(RATE_500KBPS); break; } case ARBITRARY_RATE: { uint32_t bitrate = 0; SerializeAdapter::deSerialize(&bitrate, &data, &size, SerializeIF::Endianness::BIG); - result = ptmeConfig->setRate(bitrate); + result = ptmeConfig.setRate(bitrate); break; } case EN_TRANSMITTER: { @@ -221,19 +213,19 @@ ReturnValue_t CcsdsIpCoreHandler::executeAction(ActionId_t actionId, MessageQueu return EXECUTION_FINISHED; } case ENABLE_TX_CLK_MANIPULATOR: { - result = ptmeConfig->configTxManipulator(true); + result = ptmeConfig.configTxManipulator(true); break; } case DISABLE_TX_CLK_MANIPULATOR: { - result = ptmeConfig->configTxManipulator(false); + result = ptmeConfig.configTxManipulator(false); break; } case UPDATE_ON_RISING_EDGE: { - result = ptmeConfig->invertTxClock(false); + result = ptmeConfig.invertTxClock(false); break; } case UPDATE_ON_FALLING_EDGE: { - result = ptmeConfig->invertTxClock(true); + result = ptmeConfig.invertTxClock(true); break; } default: @@ -283,13 +275,13 @@ ReturnValue_t CcsdsIpCoreHandler::checkModeCommand(Mode_t mode, Submode_t submod void CcsdsIpCoreHandler::startTransition(Mode_t mode, Submode_t submode) { auto rateHigh = [&]() { - ReturnValue_t result = ptmeConfig->setRate(RATE_500KBPS); + ReturnValue_t result = ptmeConfig.setRate(RATE_500KBPS); if (result == returnvalue::OK) { this->mode = HasModesIF::MODE_ON; } }; auto rateLow = [&]() { - ReturnValue_t result = ptmeConfig->setRate(RATE_100KBPS); + ReturnValue_t result = ptmeConfig.setRate(RATE_100KBPS); if (result == returnvalue::OK) { this->mode = HasModesIF::MODE_ON; } diff --git a/mission/tmtc/CcsdsIpCoreHandler.h b/mission/tmtc/CcsdsIpCoreHandler.h index 356c2f8d..f82e28fd 100644 --- a/mission/tmtc/CcsdsIpCoreHandler.h +++ b/mission/tmtc/CcsdsIpCoreHandler.h @@ -39,7 +39,7 @@ class CcsdsIpCoreHandler : public SystemObject, public ModeTreeChildIF, public ModeTreeConnectionIF, public HasModesIF, - public AcceptsTelemetryIF, + // public AcceptsTelemetryIF, public AcceptsTelecommandsIF, public ReceivesParameterMessagesIF, public HasActionsIF { @@ -58,8 +58,8 @@ class CcsdsIpCoreHandler : public SystemObject, * @param enTxClock GPIO ID of RS485 tx clock enable * @param enTxData GPIO ID of RS485 tx data enable */ - CcsdsIpCoreHandler(object_id_t objectId, object_id_t ptmeId, object_id_t tcDestination, - PtmeConfig* ptmeConfig, GpioIF* gpioIF, gpioId_t enTxClock, gpioId_t enTxData); + CcsdsIpCoreHandler(object_id_t objectId, object_id_t tcDestination, PtmeIF& ptme, + PtmeConfig& ptmeConfig, GpioIF* gpioIF, gpioId_t enTxClock, gpioId_t enTxData); ~CcsdsIpCoreHandler(); @@ -82,7 +82,7 @@ class CcsdsIpCoreHandler : public SystemObject, */ void addVirtualChannel(VcId_t virtualChannelId, VirtualChannel* virtualChannel); - MessageQueueId_t getReportReceptionQueue(uint8_t virtualChannel = 0) const override; + // MessageQueueId_t getReportReceptionQueue(uint8_t virtualChannel = 0) const override; ReturnValue_t getParameter(uint8_t domainId, uint8_t uniqueIdentifier, ParameterWrapper* parameterWrapper, const ParameterWrapper* newValues, uint16_t startAtIndex); @@ -132,11 +132,9 @@ class CcsdsIpCoreHandler : public SystemObject, using VirtualChannelMap = std::unordered_map; using VirtualChannelMapIter = VirtualChannelMap::iterator; + PtmeIF& ptme; VirtualChannelMap virtualChannelMap; - // Object ID of PTME object - object_id_t ptmeId; - object_id_t tcDestination; MessageQueueIF* commandQueue = nullptr; @@ -150,7 +148,7 @@ class CcsdsIpCoreHandler : public SystemObject, MessageQueueId_t tcDistributorQueueId = MessageQueueIF::NO_QUEUE; - PtmeConfig* ptmeConfig = nullptr; + PtmeConfig& ptmeConfig; GpioIF* gpioIF = nullptr; // GPIO to enable RS485 transceiver for TX clock @@ -162,7 +160,6 @@ class CcsdsIpCoreHandler : public SystemObject, void readCommandQueue(void); void handleTelemetry(); - void handleTelecommands(); /** * @brief Forward link state to virtual channels. diff --git a/mission/tmtc/PersistentTmStore.cpp b/mission/tmtc/PersistentTmStore.cpp index 7b29e06f..694a50b7 100644 --- a/mission/tmtc/PersistentTmStore.cpp +++ b/mission/tmtc/PersistentTmStore.cpp @@ -75,41 +75,6 @@ ReturnValue_t PersistentTmStore::handleCommandQueue(StorageManagerIF& ipcStore, return returnvalue::OK; } -ReturnValue_t PersistentTmStore::passPacket(PusTmReader& reader) { - bool inApidList = false; - if (filter.apid) { - auto& apidFilter = filter.apid.value(); - if (std::find(apidFilter.begin(), apidFilter.end(), reader.getApid()) != apidFilter.end()) { - if (not filter.serviceSubservices and not filter.services) { - return storePacket(reader); - } - inApidList = true; - } - } - std::pair serviceSubservice; - serviceSubservice.first = reader.getService(); - serviceSubservice.second = reader.getSubService(); - if (filter.services) { - auto& serviceFilter = filter.services.value(); - if (std::find(serviceFilter.begin(), serviceFilter.end(), serviceSubservice.first) != - serviceFilter.end()) { - if (filter.apid and inApidList) { - return storePacket(reader); - } - } - } - if (filter.serviceSubservices) { - auto& serviceSubserviceFilter = filter.serviceSubservices.value(); - if (std::find(serviceSubserviceFilter.begin(), serviceSubserviceFilter.end(), - serviceSubservice) != serviceSubserviceFilter.end()) { - if (filter.apid and inApidList) { - return storePacket(reader); - } - } - } - return returnvalue::OK; -} - void PersistentTmStore::dumpFrom(uint32_t fromUnixSeconds, TmFunnelBase& tmFunnel) { return dumpFromUpTo(fromUnixSeconds, currentTv.tv_sec, tmFunnel); } @@ -182,31 +147,6 @@ bool PersistentTmStore::updateBaseDir() { return true; } -void PersistentTmStore::addApid(uint16_t apid) { - if (not filter.apid) { - filter.apid = std::vector({apid}); - return; - } - filter.apid.value().push_back(apid); -} - -void PersistentTmStore::addService(uint8_t service) { - if (not filter.services) { - filter.services = std::vector({service}); - return; - } - filter.services.value().push_back(service); -} - -void PersistentTmStore::addServiceSubservice(uint8_t service, uint8_t subservice) { - if (not filter.serviceSubservices) { - filter.serviceSubservices = - std::vector>({std::pair(service, subservice)}); - return; - } - filter.serviceSubservices.value().emplace_back(service, subservice); -} - void PersistentTmStore::deleteUpTo(uint32_t unixSeconds) { using namespace std::filesystem; for (auto const& file : directory_iterator(basePath)) { diff --git a/mission/tmtc/PersistentTmStore.h b/mission/tmtc/PersistentTmStore.h index d8bc9acf..280fa4ac 100644 --- a/mission/tmtc/PersistentTmStore.h +++ b/mission/tmtc/PersistentTmStore.h @@ -13,12 +13,6 @@ #include "TmFunnelBase.h" #include "eive/eventSubsystemIds.h" -struct PacketFilter { - std::optional> apid; - std::optional> services; - std::optional>> serviceSubservices; -}; - enum class RolloverInterval { MINUTELY, HOURLY, DAILY }; class PersistentTmStore : public TmStoreFrontendSimpleIF, public SystemObject { @@ -37,15 +31,12 @@ class PersistentTmStore : public TmStoreFrontendSimpleIF, public SystemObject { ReturnValue_t initializeTmStore(); ReturnValue_t handleCommandQueue(StorageManagerIF& ipcStore, TmFunnelBase& tmFunnel); - void addApid(uint16_t apid); - void addService(uint8_t service); - void addServiceSubservice(uint8_t service, uint8_t subservice); - void deleteUpTo(uint32_t unixSeconds); void dumpFrom(uint32_t fromUnixSeconds, TmFunnelBase& tmFunnel); void dumpFromUpTo(uint32_t fromUnixSeconds, uint32_t upToUnixSeconds, TmFunnelBase& tmFunnel); - ReturnValue_t passPacket(PusTmReader& reader); + // ReturnValue_t passPacket(PusTmReader& reader); + ReturnValue_t storePacket(PusTmReader& reader); private: static constexpr uint8_t MAX_FILES_IN_ONE_SECOND = 10; @@ -54,7 +45,7 @@ class PersistentTmStore : public TmStoreFrontendSimpleIF, public SystemObject { static constexpr char FILE_DATE_FORMAT[] = "%FT%H%M%SZ"; MessageQueueIF* tcQueue; - PacketFilter filter; + // PacketFilter filter; CdsShortTimeStamper timeReader; bool baseDirUninitialized = true; const char* baseDir; @@ -81,7 +72,6 @@ class PersistentTmStore : public TmStoreFrontendSimpleIF, public SystemObject { void fileToPackets(const std::filesystem::path& path, uint32_t unixStamp, TmFunnelBase& funnel); bool updateBaseDir(); ReturnValue_t assignAndOrCreateMostRecentFile(); - ReturnValue_t storePacket(PusTmReader& reader); }; #endif /* MISSION_TMTC_TMSTOREBACKEND_H_ */ diff --git a/mission/tmtc/PusPacketFilter.cpp b/mission/tmtc/PusPacketFilter.cpp new file mode 100644 index 00000000..51abc02b --- /dev/null +++ b/mission/tmtc/PusPacketFilter.cpp @@ -0,0 +1,64 @@ +#include + +#include + +PusPacketFilter::PusPacketFilter() {} + +void PusPacketFilter::addApid(uint16_t apid) { + if (not this->apid) { + this->apid = std::vector({apid}); + return; + } + this->apid.value().push_back(apid); +} + +void PusPacketFilter::addService(uint8_t service) { + if (not this->services) { + this->services = std::vector({service}); + return; + } + this->services.value().push_back(service); +} + +void PusPacketFilter::addServiceSubservice(uint8_t service, uint8_t subservice) { + if (not serviceSubservices) { + serviceSubservices = std::vector>({std::pair(service, subservice)}); + return; + } + serviceSubservices.value().emplace_back(service, subservice); +} + +bool PusPacketFilter::packetMatches(PusTmReader& reader) const { + bool inApidList = false; + if (apid) { + auto& apidFilter = apid.value(); + if (std::find(apidFilter.begin(), apidFilter.end(), reader.getApid()) != apidFilter.end()) { + if (not serviceSubservices and not services) { + return true; + } + inApidList = true; + } + } + std::pair serviceSubservice; + serviceSubservice.first = reader.getService(); + serviceSubservice.second = reader.getSubService(); + if (services) { + auto& serviceFilter = services.value(); + if (std::find(serviceFilter.begin(), serviceFilter.end(), serviceSubservice.first) != + serviceFilter.end()) { + if (apid and inApidList) { + return true; + } + } + } + if (serviceSubservices) { + auto& serviceSubserviceFilter = serviceSubservices.value(); + if (std::find(serviceSubserviceFilter.begin(), serviceSubserviceFilter.end(), + serviceSubservice) != serviceSubserviceFilter.end()) { + if (apid and inApidList) { + return true; + } + } + } + return false; +} diff --git a/mission/tmtc/PusPacketFilter.h b/mission/tmtc/PusPacketFilter.h new file mode 100644 index 00000000..78d9cc18 --- /dev/null +++ b/mission/tmtc/PusPacketFilter.h @@ -0,0 +1,24 @@ +#ifndef MISSION_TMTC_PUSPACKETFILTER_H_ +#define MISSION_TMTC_PUSPACKETFILTER_H_ + +#include + +#include +#include + +class PusPacketFilter { + public: + PusPacketFilter(); + + bool packetMatches(PusTmReader& reader) const; + void addApid(uint16_t apid); + void addService(uint8_t service); + void addServiceSubservice(uint8_t service, uint8_t subservice); + + private: + std::optional> apid; + std::optional> services; + std::optional>> serviceSubservices; +}; + +#endif /* MISSION_TMTC_PUSPACKETFILTER_H_ */ diff --git a/mission/tmtc/PusTmFunnel.cpp b/mission/tmtc/PusTmFunnel.cpp index 08a047a0..ad763ff5 100644 --- a/mission/tmtc/PusTmFunnel.cpp +++ b/mission/tmtc/PusTmFunnel.cpp @@ -12,48 +12,14 @@ PusTmFunnel::PusTmFunnel(TmFunnelBase::FunnelCfg cfg, TimeReaderIF &timeReader, SdCardMountedIF &sdcMan) - : TmFunnelBase(cfg), - timeReader(timeReader), - miscStore(objects::MISC_TM_STORE, "tm", "misc", RolloverInterval::HOURLY, 2, tmStore, sdcMan), - okStore(objects::OK_TM_STORE, "tm", "ok", RolloverInterval::MINUTELY, 30, tmStore, sdcMan), - notOkStore(objects::NOT_OK_TM_STORE, "tm", "nok", RolloverInterval::MINUTELY, 30, tmStore, - sdcMan), - hkStore(objects::HK_TM_STORE, "tm", "hk", RolloverInterval::MINUTELY, 15, tmStore, sdcMan), - sdcMan(sdcMan) { - Clock::getClock_timeval(¤tTv); - Clock::getUptime(&lastTvUpdate); - hkStore.addApid(config::EIVE_PUS_APID); - hkStore.addService(pus::PUS_SERVICE_3); - miscStore.addApid(config::EIVE_PUS_APID); - miscStore.addService(pus::PUS_SERVICE_17); - miscStore.addService(pus::PUS_SERVICE_2); - miscStore.addService(pus::PUS_SERVICE_200); - miscStore.addService(pus::PUS_SERVICE_201); - miscStore.addService(pus::PUS_SERVICE_9); - miscStore.addService(pus::PUS_SERVICE_20); - okStore.addApid(config::EIVE_PUS_APID); - okStore.addServiceSubservice(pus::PUS_SERVICE_5, - Service5EventReporting::Subservice::NORMAL_REPORT); - okStore.addService(pus::PUS_SERVICE_8); - okStore.addServiceSubservice(pus::PUS_SERVICE_1, 1); - okStore.addServiceSubservice(pus::PUS_SERVICE_1, 3); - okStore.addServiceSubservice(pus::PUS_SERVICE_1, 5); - okStore.addServiceSubservice(pus::PUS_SERVICE_1, 7); - notOkStore.addApid(config::EIVE_PUS_APID); - notOkStore.addServiceSubservice(pus::PUS_SERVICE_5, 2); - notOkStore.addServiceSubservice(pus::PUS_SERVICE_5, 3); - notOkStore.addServiceSubservice(pus::PUS_SERVICE_5, 4); - notOkStore.addServiceSubservice(pus::PUS_SERVICE_1, 2); - notOkStore.addServiceSubservice(pus::PUS_SERVICE_1, 4); - notOkStore.addServiceSubservice(pus::PUS_SERVICE_1, 6); - notOkStore.addServiceSubservice(pus::PUS_SERVICE_1, 8); -} + : TmFunnelBase(cfg), timeReader(timeReader), sdcMan(sdcMan) {} PusTmFunnel::~PusTmFunnel() = default; ReturnValue_t PusTmFunnel::performOperation(uint8_t) { CommandMessage cmdMessage; ReturnValue_t result; + /* try { result = okStore.handleCommandQueue(ipcStore, *this); if (result != returnvalue::OK) { @@ -75,6 +41,7 @@ ReturnValue_t PusTmFunnel::performOperation(uint8_t) { } catch (const std::bad_optional_access &e) { sif::error << e.what() << "when handling TM store command" << std::endl; } + */ TmTcMessage currentMessage; unsigned int count = 0; @@ -119,38 +86,45 @@ ReturnValue_t PusTmFunnel::handleTmPacket(TmTcMessage &message) { sourceSequenceCount = sourceSequenceCount % ccsds::LIMIT_SEQUENCE_COUNT; packet.updateErrorControl(); - timeval currentUptime{}; - Clock::getUptime(¤tUptime); - if (currentUptime.tv_sec - lastTvUpdate.tv_sec > - static_cast(TV_UPDATE_INTERVAL_SECS)) { - Clock::getClock_timeval(¤tTv); - lastTvUpdate = currentUptime; - } - - bool sdcUsable = sdcMan.isSdCardUsable(std::nullopt); - initStoresIfPossible(sdcUsable); - if (sdcUsable) { - miscStore.passPacket(packet); - okStore.passPacket(packet); - notOkStore.passPacket(packet); - hkStore.passPacket(packet); - } + // TODO: 1. Send packet to persistent TM store when applicable. + // 2. Send packet to live TM VC + // 3. Send packet to TCP/IP destination return sendPacketToDestinations(origStoreId, message, packetData, size); + // timeval currentUptime{}; + // Clock::getUptime(¤tUptime); + // if (currentUptime.tv_sec - lastTvUpdate.tv_sec > + // static_cast(TV_UPDATE_INTERVAL_SECS)) { + // Clock::getClock_timeval(¤tTv); + // lastTvUpdate = currentUptime; + // } + + // bool sdcUsable = sdcMan.isSdCardUsable(std::nullopt); + // initStoresIfPossible(sdcUsable); + // if (sdcUsable) { + // miscStore.passPacket(packet); + // okStore.passPacket(packet); + // notOkStore.passPacket(packet); + // hkStore.passPacket(packet); + // } } const char *PusTmFunnel::getName() const { return "PUS TM Funnel"; } void PusTmFunnel::initStoresIfPossible(bool sdCardUsable) { if (not storesInitialized and sdCardUsable and sdcMan.getCurrentMountPrefix() != nullptr) { - miscStore.initializeTmStore(); - okStore.initializeTmStore(); - hkStore.initializeTmStore(); - notOkStore.initializeTmStore(); + // miscStore.initializeTmStore(); + // okStore.initializeTmStore(); + // hkStore.initializeTmStore(); + // notOkStore.initializeTmStore(); storesInitialized = true; } } ReturnValue_t PusTmFunnel::initialize() { - initStoresIfPossible(sdcMan.isSdCardUsable(std::nullopt)); + // initStoresIfPossible(sdcMan.isSdCardUsable(std::nullopt)); return returnvalue::OK; } + +void PusTmFunnel::addPersistentTmStoreRouting(PusPacketFilter filter, MessageQueueId_t dest) { + router.addRouting(filter, dest); +} diff --git a/mission/tmtc/PusTmFunnel.h b/mission/tmtc/PusTmFunnel.h index ab6a9480..774737dc 100644 --- a/mission/tmtc/PusTmFunnel.h +++ b/mission/tmtc/PusTmFunnel.h @@ -7,6 +7,7 @@ #include #include #include +#include #include @@ -28,6 +29,7 @@ class PusTmFunnel : public TmFunnelBase { ~PusTmFunnel() override; ReturnValue_t performOperation(uint8_t operationCode); + void addPersistentTmStoreRouting(PusPacketFilter filter, MessageQueueId_t dest); private: // Update TV stamp every 5 minutes @@ -36,13 +38,8 @@ class PusTmFunnel : public TmFunnelBase { uint16_t sourceSequenceCount = 0; TimeReaderIF &timeReader; bool storesInitialized = false; - timeval currentTv{}; - timeval lastTvUpdate{}; - PersistentTmStore miscStore; - PersistentTmStore okStore; - PersistentTmStore notOkStore; - PersistentTmStore hkStore; SdCardMountedIF &sdcMan; + PersistentTmStoreRouter router; ReturnValue_t handleTmPacket(TmTcMessage &message); void initStoresIfPossible(bool sdCardUsable); diff --git a/mission/tmtc/TmStoreRouter.cpp b/mission/tmtc/TmStoreRouter.cpp new file mode 100644 index 00000000..d958574e --- /dev/null +++ b/mission/tmtc/TmStoreRouter.cpp @@ -0,0 +1,19 @@ +#include "TmStoreRouter.h" + +#include + +PersistentTmStoreRouter::PersistentTmStoreRouter() = default; + +bool PersistentTmStoreRouter::packetMatches(PusTmReader& reader, MessageQueueId_t& destination) { + for (const auto filterAndDest : routerMap) { + if (filterAndDest.first.packetMatches(reader)) { + destination = filterAndDest.second; + return true; + } + } + return false; +} + +void PersistentTmStoreRouter::addRouting(PusPacketFilter filter, MessageQueueId_t destination) { + routerMap.emplace_back(std::move(filter), destination); +} diff --git a/mission/tmtc/TmStoreRouter.h b/mission/tmtc/TmStoreRouter.h new file mode 100644 index 00000000..9daa4889 --- /dev/null +++ b/mission/tmtc/TmStoreRouter.h @@ -0,0 +1,18 @@ +#ifndef MISSION_TMTC_PUSTMROUTER_H_ +#define MISSION_TMTC_PUSTMROUTER_H_ + +#include +#include + +class PersistentTmStoreRouter { + public: + PersistentTmStoreRouter(); + + bool packetMatches(PusTmReader& reader, MessageQueueId_t& destination); + void addRouting(PusPacketFilter filter, MessageQueueId_t destination); + + private: + std::vector> routerMap; +}; + +#endif /* MISSION_TMTC_PUSTMROUTER_H_ */ diff --git a/mission/tmtc/VirtualChannel.cpp b/mission/tmtc/VirtualChannel.cpp index 6a24cc09..a6e7732c 100644 --- a/mission/tmtc/VirtualChannel.cpp +++ b/mission/tmtc/VirtualChannel.cpp @@ -7,12 +7,12 @@ #include "fsfw/serviceinterface/ServiceInterfaceStream.h" #include "fsfw/tmtcservices/TmTcMessage.h" -VirtualChannel::VirtualChannel(uint8_t vcId, uint32_t tmQueueDepth, object_id_t ownerId) - : vcId(vcId) { - auto mqArgs = MqArgs(ownerId, reinterpret_cast(vcId)); +VirtualChannel::VirtualChannel(object_id_t objectId, uint8_t vcId, const char* vcName, + uint32_t tmQueueDepth) + : SystemObject(objectId), vcId(vcId), vcName(vcName) { + auto mqArgs = MqArgs(objectId, reinterpret_cast(vcId)); tmQueue = QueueFactory::instance()->createMessageQueue( tmQueueDepth, MessageQueueMessage::MAX_MESSAGE_SIZE, &mqArgs); - vcName = "VC " + vcId; } ReturnValue_t VirtualChannel::initialize() { @@ -24,38 +24,40 @@ ReturnValue_t VirtualChannel::initialize() { return returnvalue::OK; } -ReturnValue_t VirtualChannel::performOperation() { +ReturnValue_t VirtualChannel::performOperation(uint8_t opCode) { ReturnValue_t result = returnvalue::OK; TmTcMessage message; + // To be able to push high datarates, we use a custom permanent loop. + while (true) { + unsigned int count = 0; + while (tmQueue->receiveMessage(&message) == returnvalue::OK) { + store_address_t storeId = message.getStorageId(); + const uint8_t* data = nullptr; + size_t size = 0; + result = tmStore->getData(storeId, &data, &size); + if (result != returnvalue::OK) { + sif::warning << "VirtualChannel::performOperation: Failed to read data from TM store" + << std::endl; + tmStore->deleteData(storeId); + return result; + } - unsigned int count = 0; - while (tmQueue->receiveMessage(&message) == returnvalue::OK) { - store_address_t storeId = message.getStorageId(); - const uint8_t* data = nullptr; - size_t size = 0; - result = tmStore->getData(storeId, &data, &size); - if (result != returnvalue::OK) { - sif::warning << "VirtualChannel::performOperation: Failed to read data from TM store" - << std::endl; + if (linkIsUp) { + result = ptme->writeToVc(vcId, data, size); + } tmStore->deleteData(storeId); - return result; - } + if (result != returnvalue::OK) { + return result; + } - if (linkIsUp) { - result = ptme->writeToVc(vcId, data, size); - } - tmStore->deleteData(storeId); - if (result != returnvalue::OK) { - return result; - } - - count++; - if (count == 500) { - sif::error << "VirtualChannel: Possible message storm detected" << std::endl; - break; + count++; + if (count == 500) { + sif::error << "VirtualChannel: Possible message storm detected" << std::endl; + break; + } } } - return result; + return returnvalue::FAILED; } MessageQueueId_t VirtualChannel::getReportReceptionQueue(uint8_t virtualChannel) const { diff --git a/mission/tmtc/VirtualChannel.h b/mission/tmtc/VirtualChannel.h index 96d7ba9d..98caa004 100644 --- a/mission/tmtc/VirtualChannel.h +++ b/mission/tmtc/VirtualChannel.h @@ -2,6 +2,8 @@ #define VIRTUALCHANNEL_H_ #include +#include +#include #include #include "OBSWConfig.h" @@ -16,7 +18,7 @@ class StorageManagerIF; * * @author J. Meier */ -class VirtualChannel : public AcceptsTelemetryIF { +class VirtualChannel : public SystemObject, public ExecutableObjectIF, public AcceptsTelemetryIF { public: /** * @brief Constructor @@ -24,11 +26,11 @@ class VirtualChannel : public AcceptsTelemetryIF { * @param vcId The virtual channel id assigned to this object * @param tmQueueDepth Queue depth of queue receiving telemetry from other objects */ - VirtualChannel(uint8_t vcId, uint32_t tmQueueDepth, object_id_t ownerId); + VirtualChannel(object_id_t objectId, uint8_t vcId, const char* vcName, uint32_t tmQueueDepth); - ReturnValue_t initialize(); + ReturnValue_t initialize() override; MessageQueueId_t getReportReceptionQueue(uint8_t virtualChannel = 0) const override; - ReturnValue_t performOperation(); + ReturnValue_t performOperation(uint8_t opCode) override; /** * @brief Sets the PTME object which handles access to the PTME IP Core. diff --git a/mission/tmtc/tmFilters.cpp b/mission/tmtc/tmFilters.cpp new file mode 100644 index 00000000..540df3de --- /dev/null +++ b/mission/tmtc/tmFilters.cpp @@ -0,0 +1,51 @@ +#include "tmFilters.h" + +#include +#include + +#include "eive/definitions.h" + +PusPacketFilter filters::hkFilter() { + PusPacketFilter hkFilter; + hkFilter.addApid(config::EIVE_PUS_APID); + hkFilter.addService(pus::PUS_SERVICE_3); + return hkFilter; +} + +PusPacketFilter filters::miscFilter() { + PusPacketFilter miscFilter; + miscFilter.addApid(config::EIVE_PUS_APID); + miscFilter.addService(pus::PUS_SERVICE_17); + miscFilter.addService(pus::PUS_SERVICE_2); + miscFilter.addService(pus::PUS_SERVICE_200); + miscFilter.addService(pus::PUS_SERVICE_201); + miscFilter.addService(pus::PUS_SERVICE_9); + miscFilter.addService(pus::PUS_SERVICE_20); + return miscFilter; +} + +PusPacketFilter filters::okFilter() { + PusPacketFilter okFilter; + okFilter.addApid(config::EIVE_PUS_APID); + okFilter.addServiceSubservice(pus::PUS_SERVICE_5, + Service5EventReporting::Subservice::NORMAL_REPORT); + okFilter.addService(pus::PUS_SERVICE_8); + okFilter.addServiceSubservice(pus::PUS_SERVICE_1, 1); + okFilter.addServiceSubservice(pus::PUS_SERVICE_1, 3); + okFilter.addServiceSubservice(pus::PUS_SERVICE_1, 5); + okFilter.addServiceSubservice(pus::PUS_SERVICE_1, 7); + return okFilter; +} + +PusPacketFilter filters::notOkFilter() { + PusPacketFilter notOkFilter; + notOkFilter.addApid(config::EIVE_PUS_APID); + notOkFilter.addServiceSubservice(pus::PUS_SERVICE_5, 2); + notOkFilter.addServiceSubservice(pus::PUS_SERVICE_5, 3); + notOkFilter.addServiceSubservice(pus::PUS_SERVICE_5, 4); + notOkFilter.addServiceSubservice(pus::PUS_SERVICE_1, 2); + notOkFilter.addServiceSubservice(pus::PUS_SERVICE_1, 4); + notOkFilter.addServiceSubservice(pus::PUS_SERVICE_1, 6); + notOkFilter.addServiceSubservice(pus::PUS_SERVICE_1, 8); + return notOkFilter; +} diff --git a/mission/tmtc/tmFilters.h b/mission/tmtc/tmFilters.h new file mode 100644 index 00000000..fc5318f9 --- /dev/null +++ b/mission/tmtc/tmFilters.h @@ -0,0 +1,14 @@ +#ifndef MISSION_TMTC_FILTERS_H_ +#define MISSION_TMTC_FILTERS_H_ +#include + +namespace filters { + +PusPacketFilter hkFilter(); +PusPacketFilter miscFilter(); +PusPacketFilter okFilter(); +PusPacketFilter notOkFilter(); + +} // namespace filters + +#endif /* MISSION_TMTC_FILTERS_H_ */ From e5636f0b6c6217f19be3d50b0c84aa59d5065367 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 9 Mar 2023 11:46:13 +0100 Subject: [PATCH 032/112] continue rework --- bsp_q7s/core/ObjectFactory.h | 1 - mission/core/GenericFactory.cpp | 10 ++-- mission/core/GenericFactory.h | 1 - mission/tmtc/CMakeLists.txt | 3 +- mission/tmtc/CfdpTmFunnel.cpp | 34 +----------- mission/tmtc/PersistentTmStore.cpp | 27 +++++----- mission/tmtc/PersistentTmStore.h | 6 +-- mission/tmtc/PusLiveDemux.cpp | 48 +++++++++++++++++ mission/tmtc/PusLiveDemux.h | 34 ++++++++++++ mission/tmtc/PusTmFunnel.cpp | 28 +++++----- mission/tmtc/PusTmFunnel.h | 4 +- mission/tmtc/PusTmRouteByFilterHelper.cpp | 19 +++++++ ...oreRouter.h => PusTmRouteByFilterHelper.h} | 15 +++++- mission/tmtc/TmFunnelBase.cpp | 54 +++++-------------- mission/tmtc/TmFunnelBase.h | 21 +++----- mission/tmtc/TmStoreRouter.cpp | 19 ------- 16 files changed, 176 insertions(+), 148 deletions(-) create mode 100644 mission/tmtc/PusLiveDemux.cpp create mode 100644 mission/tmtc/PusLiveDemux.h create mode 100644 mission/tmtc/PusTmRouteByFilterHelper.cpp rename mission/tmtc/{TmStoreRouter.h => PusTmRouteByFilterHelper.h} (53%) delete mode 100644 mission/tmtc/TmStoreRouter.cpp diff --git a/bsp_q7s/core/ObjectFactory.h b/bsp_q7s/core/ObjectFactory.h index 0a43b336..d71ed359 100644 --- a/bsp_q7s/core/ObjectFactory.h +++ b/bsp_q7s/core/ObjectFactory.h @@ -8,7 +8,6 @@ #include #include #include -#include #include diff --git a/mission/core/GenericFactory.cpp b/mission/core/GenericFactory.cpp index 01871ff2..e2e5c0c7 100644 --- a/mission/core/GenericFactory.cpp +++ b/mission/core/GenericFactory.cpp @@ -36,8 +36,8 @@ #include #include #include +#include #include -#include #include "OBSWConfig.h" #include "devices/gpioIds.h" @@ -160,12 +160,12 @@ void ObjectFactory::produceGenericObjects(HealthTableIF** healthTable_, PusTmFun *pusFunnel = new PusTmFunnel(pusFunnelCfg, *timeStamper, sdcMan); #if OBSW_ADD_TCPIP_SERVERS == 1 #if OBSW_ADD_TMTC_UDP_SERVER == 1 - (*cfdpFunnel)->addDestination("UDP Server", *udpBridge, 0); - (*pusFunnel)->addDestination("UDP Server", *udpBridge, 0); + (*cfdpFunnel)->addLiveDestination("UDP Server", *udpBridge, 0); + (*pusFunnel)->addLiveDestination("UDP Server", *udpBridge, 0); #endif #if OBSW_ADD_TMTC_TCP_SERVER == 1 - (*cfdpFunnel)->addDestination("TCP Server", *tcpBridge, 0); - (*pusFunnel)->addDestination("TCP Server", *tcpBridge, 0); + (*cfdpFunnel)->addLiveDestination("TCP Server", *tcpBridge, 0); + (*pusFunnel)->addLiveDestination("TCP Server", *tcpBridge, 0); #endif #endif // Every TM packet goes through this funnel diff --git a/mission/core/GenericFactory.h b/mission/core/GenericFactory.h index 8663d696..5902ff7b 100644 --- a/mission/core/GenericFactory.h +++ b/mission/core/GenericFactory.h @@ -3,7 +3,6 @@ #include #include -#include #include "fsfw/objectmanager/SystemObjectIF.h" #include "fsfw/power/PowerSwitchIF.h" diff --git a/mission/tmtc/CMakeLists.txt b/mission/tmtc/CMakeLists.txt index ef97002c..213f4ef0 100644 --- a/mission/tmtc/CMakeLists.txt +++ b/mission/tmtc/CMakeLists.txt @@ -6,8 +6,9 @@ target_sources( TmFunnelBase.cpp CfdpTmFunnel.cpp tmFilters.cpp + PusLiveDemux.cpp PusPacketFilter.cpp - TmStoreRouter.cpp + PusTmRouteByFilterHelper.cpp Service15TmStorage.cpp PersistentTmStore.cpp PusTmFunnel.cpp) diff --git a/mission/tmtc/CfdpTmFunnel.cpp b/mission/tmtc/CfdpTmFunnel.cpp index 89d7c105..26b308da 100644 --- a/mission/tmtc/CfdpTmFunnel.cpp +++ b/mission/tmtc/CfdpTmFunnel.cpp @@ -75,36 +75,6 @@ ReturnValue_t CfdpTmFunnel::handlePacket(TmTcMessage& msg) { tmStore.deleteData(msg.getStorageId()); msg.setStorageId(newStoreId); store_address_t origStoreId = newStoreId; - for (unsigned int idx = 0; idx < destinations.size(); idx++) { - const auto& dest = destinations[idx]; - if (destinations.size() > 1) { - if (idx < destinations.size() - 1) { - // Create copy of data to ensure each TM recipient has its own copy. That way, we don't need - // to bother with send order and where the data is deleted. - store_address_t storeId; - result = tmStore.addData(&storeId, newPacketData, packetLen); - if (result == returnvalue::OK) { - msg.setStorageId(storeId); - } else { -#if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "PusTmFunnel::handlePacket: Store too full to create data copy or store " - "error" - << std::endl; -#endif - break; - } - } else { - msg.setStorageId(origStoreId); - } - } - result = tmQueue->sendMessage(dest.queueId, &msg); - if (result != returnvalue::OK) { -#if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << "PusTmFunnel::handlePacket: Error sending TM to downlink handler " << dest.name - << " failed" << std::endl; -#endif - tmStore.deleteData(msg.getStorageId()); - } - } - return result; + // TODO: Also route to persistent TM store + return demultiplexLivePackets(origStoreId, newPacketData, packetLen); } diff --git a/mission/tmtc/PersistentTmStore.cpp b/mission/tmtc/PersistentTmStore.cpp index 694a50b7..0324a649 100644 --- a/mission/tmtc/PersistentTmStore.cpp +++ b/mission/tmtc/PersistentTmStore.cpp @@ -69,14 +69,14 @@ ReturnValue_t PersistentTmStore::handleCommandQueue(StorageManagerIF& ipcStore, SerializeIF::Endianness::NETWORK); SerializeAdapter::deSerialize(&dumpUntilUnixSeconds, accessor.second.data() + 4, &size, SerializeIF::Endianness::NETWORK); - dumpFromUpTo(dumpFromUnixSeconds, dumpUntilUnixSeconds, tmFunnel); + dumpFromUpTo(dumpFromUnixSeconds, dumpUntilUnixSeconds); } } return returnvalue::OK; } -void PersistentTmStore::dumpFrom(uint32_t fromUnixSeconds, TmFunnelBase& tmFunnel) { - return dumpFromUpTo(fromUnixSeconds, currentTv.tv_sec, tmFunnel); +void PersistentTmStore::dumpFrom(uint32_t fromUnixSeconds) { + return dumpFromUpTo(fromUnixSeconds, currentTv.tv_sec); } ReturnValue_t PersistentTmStore::storePacket(PusTmReader& reader) { @@ -166,8 +166,7 @@ void PersistentTmStore::deleteUpTo(uint32_t unixSeconds) { } } -void PersistentTmStore::dumpFromUpTo(uint32_t fromUnixSeconds, uint32_t upToUnixSeconds, - TmFunnelBase& funnel) { +void PersistentTmStore::dumpFromUpTo(uint32_t fromUnixSeconds, uint32_t upToUnixSeconds) { using namespace std::filesystem; for (auto const& file : directory_iterator(basePath)) { if (file.is_directory()) { @@ -180,7 +179,7 @@ void PersistentTmStore::dumpFromUpTo(uint32_t fromUnixSeconds, uint32_t upToUnix } auto fileEpoch = static_cast(timegm(&fileTime)); if ((fileEpoch > fromUnixSeconds) and (fileEpoch + rolloverDiffSeconds <= upToUnixSeconds)) { - fileToPackets(file, fileEpoch, funnel); + fileToPackets(file, fileEpoch); } } } @@ -195,8 +194,7 @@ ReturnValue_t PersistentTmStore::pathToTm(const std::filesystem::path& path, str return returnvalue::OK; } -void PersistentTmStore::fileToPackets(const std::filesystem::path& path, uint32_t unixStamp, - TmFunnelBase& funnel) { +void PersistentTmStore::fileToPackets(const std::filesystem::path& path, uint32_t unixStamp) { store_address_t storeId; TmTcMessage message; size_t size = std::filesystem::file_size(path); @@ -212,12 +210,13 @@ void PersistentTmStore::fileToPackets(const std::filesystem::path& path, uint32_ // CRC check to fully ensure this is a valid TM ReturnValue_t result = reader.parseDataWithCrcCheck(); if (result == returnvalue::OK) { - result = tmStore.addData(&storeId, fileBuf.data() + currentIdx, reader.getFullPacketLen()); - if (result != returnvalue::OK) { - continue; - } - funnel.sendPacketToDestinations(storeId, message, fileBuf.data() + currentIdx, - reader.getFullPacketLen()); + // TODO: Blow the data out to the VC directly. Use IF function to do this. + // result = tmStore.addData(&storeId, fileBuf.data() + currentIdx, + // reader.getFullPacketLen()); if (result != returnvalue::OK) { + // continue; + // } + // funnel.sendPacketToLiveDestinations(storeId, message, fileBuf.data() + currentIdx, + // reader.getFullPacketLen()); currentIdx += reader.getFullPacketLen(); } else { sif::error << "Parsing of PUS TM failed with code " << result << std::endl; diff --git a/mission/tmtc/PersistentTmStore.h b/mission/tmtc/PersistentTmStore.h index 280fa4ac..3b72cb2d 100644 --- a/mission/tmtc/PersistentTmStore.h +++ b/mission/tmtc/PersistentTmStore.h @@ -32,8 +32,8 @@ class PersistentTmStore : public TmStoreFrontendSimpleIF, public SystemObject { ReturnValue_t handleCommandQueue(StorageManagerIF& ipcStore, TmFunnelBase& tmFunnel); void deleteUpTo(uint32_t unixSeconds); - void dumpFrom(uint32_t fromUnixSeconds, TmFunnelBase& tmFunnel); - void dumpFromUpTo(uint32_t fromUnixSeconds, uint32_t upToUnixSeconds, TmFunnelBase& tmFunnel); + void dumpFrom(uint32_t fromUnixSeconds); + void dumpFromUpTo(uint32_t fromUnixSeconds, uint32_t upToUnixSeconds); // ReturnValue_t passPacket(PusTmReader& reader); ReturnValue_t storePacket(PusTmReader& reader); @@ -69,7 +69,7 @@ class PersistentTmStore : public TmStoreFrontendSimpleIF, public SystemObject { void calcDiffSeconds(RolloverInterval intervalUnit, uint32_t intervalCount); ReturnValue_t createMostRecentFile(std::optional suffix); static ReturnValue_t pathToTm(const std::filesystem::path& path, struct tm& time); - void fileToPackets(const std::filesystem::path& path, uint32_t unixStamp, TmFunnelBase& funnel); + void fileToPackets(const std::filesystem::path& path, uint32_t unixStamp); bool updateBaseDir(); ReturnValue_t assignAndOrCreateMostRecentFile(); }; diff --git a/mission/tmtc/PusLiveDemux.cpp b/mission/tmtc/PusLiveDemux.cpp new file mode 100644 index 00000000..d8ae1126 --- /dev/null +++ b/mission/tmtc/PusLiveDemux.cpp @@ -0,0 +1,48 @@ +#include "PusLiveDemux.h" + +#include +#include + +PusLiveDemux::PusLiveDemux(MessageQueueIF& ownerQueue) : ownerQueue(ownerQueue) {} + +ReturnValue_t PusLiveDemux::demultiplexPackets(StorageManagerIF& tmStore, + store_address_t origStoreId, const uint8_t* tmData, + size_t tmSize) { + ReturnValue_t result = returnvalue::OK; + for (unsigned int idx = 0; idx < destinations.size(); idx++) { + const auto& dest = destinations[idx]; + if (destinations.size() > 1) { + if (idx < destinations.size() - 1) { + // Create copy of data to ensure each TM recipient has its own copy. That way, we don't need + // to bother with send order and where the data is deleted. + store_address_t storeId; + result = tmStore.addData(&storeId, tmData, tmSize); + if (result == returnvalue::OK) { + message.setStorageId(storeId); + } else { +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::error << "PusLiveDemux::handlePacket: Store too full to create data copy" + << std::endl; +#endif + } + } else { + message.setStorageId(origStoreId); + } + } + result = ownerQueue.sendMessage(dest.queueId, &message); + if (result != returnvalue::OK) { +#if FSFW_CPP_OSTREAM_ENABLED == 1 + sif::error << "PusLiveDemux::handlePacket: Error sending TM to downlink handler " << dest.name + << std::endl; +#endif + tmStore.deleteData(message.getStorageId()); + } + } + return result; +} + +void PusLiveDemux::addDestination(const char* name, const AcceptsTelemetryIF& downlinkDestination, + uint8_t vcid) { + auto queueId = downlinkDestination.getReportReceptionQueue(vcid); + destinations.emplace_back(name, queueId, vcid); +} diff --git a/mission/tmtc/PusLiveDemux.h b/mission/tmtc/PusLiveDemux.h new file mode 100644 index 00000000..1288b173 --- /dev/null +++ b/mission/tmtc/PusLiveDemux.h @@ -0,0 +1,34 @@ +#ifndef MISSION_TMTC_PUSLIVEDEMUX_H_ +#define MISSION_TMTC_PUSLIVEDEMUX_H_ + +#include +#include +#include + +#include + +class PusLiveDemux { + public: + PusLiveDemux(MessageQueueIF& ownerQueue); + ReturnValue_t demultiplexPackets(StorageManagerIF& tmStore, store_address_t origStoreId, + const uint8_t* tmData, size_t tmSize); + + void addDestination(const char* name, const AcceptsTelemetryIF& downlinkDestination, + uint8_t vcid = 0); + + private: + struct Destination { + Destination(const char* name, MessageQueueId_t queueId, uint8_t virtualChannel) + : name(name), queueId(queueId), virtualChannel(virtualChannel) {} + + const char* name; + MessageQueueId_t queueId; + uint8_t virtualChannel = 0; + }; + + MessageQueueIF& ownerQueue; + TmTcMessage message; + std::vector destinations; +}; + +#endif /* MISSION_TMTC_PUSLIVEDEMUX_H_ */ diff --git a/mission/tmtc/PusTmFunnel.cpp b/mission/tmtc/PusTmFunnel.cpp index ad763ff5..691ccd46 100644 --- a/mission/tmtc/PusTmFunnel.cpp +++ b/mission/tmtc/PusTmFunnel.cpp @@ -86,18 +86,21 @@ ReturnValue_t PusTmFunnel::handleTmPacket(TmTcMessage &message) { sourceSequenceCount = sourceSequenceCount % ccsds::LIMIT_SEQUENCE_COUNT; packet.updateErrorControl(); - // TODO: 1. Send packet to persistent TM store when applicable. - // 2. Send packet to live TM VC - // 3. Send packet to TCP/IP destination - return sendPacketToDestinations(origStoreId, message, packetData, size); - // timeval currentUptime{}; - // Clock::getUptime(¤tUptime); - // if (currentUptime.tv_sec - lastTvUpdate.tv_sec > - // static_cast(TV_UPDATE_INTERVAL_SECS)) { - // Clock::getClock_timeval(¤tTv); - // lastTvUpdate = currentUptime; - // } + // Send to persistent TM store if the packet matches some filter. + MessageQueueId_t destination; + if (persistentTmMap.packetMatches(packet, destination)) { + store_address_t storageId; + TmTcMessage msg(storageId); + result = tmStore.addData(&storageId, packetData, size); + if (result != returnvalue::OK) { + sif::error << "PusLiveDemux::handlePacket: Store too full to create data copy" << std::endl; + } else { + tmQueue->sendMessage(destination, &msg); + } + } + return demultiplexLivePackets(origStoreId, packetData, size); + // TODO: Will be moved to own thread. // bool sdcUsable = sdcMan.isSdCardUsable(std::nullopt); // initStoresIfPossible(sdcUsable); // if (sdcUsable) { @@ -111,6 +114,7 @@ ReturnValue_t PusTmFunnel::handleTmPacket(TmTcMessage &message) { const char *PusTmFunnel::getName() const { return "PUS TM Funnel"; } void PusTmFunnel::initStoresIfPossible(bool sdCardUsable) { + // TODO: Those will be moved to own thread. if (not storesInitialized and sdCardUsable and sdcMan.getCurrentMountPrefix() != nullptr) { // miscStore.initializeTmStore(); // okStore.initializeTmStore(); @@ -126,5 +130,5 @@ ReturnValue_t PusTmFunnel::initialize() { } void PusTmFunnel::addPersistentTmStoreRouting(PusPacketFilter filter, MessageQueueId_t dest) { - router.addRouting(filter, dest); + persistentTmMap.addRouting(filter, dest); } diff --git a/mission/tmtc/PusTmFunnel.h b/mission/tmtc/PusTmFunnel.h index 774737dc..3c22afa2 100644 --- a/mission/tmtc/PusTmFunnel.h +++ b/mission/tmtc/PusTmFunnel.h @@ -6,8 +6,8 @@ #include #include #include +#include #include -#include #include @@ -39,7 +39,7 @@ class PusTmFunnel : public TmFunnelBase { TimeReaderIF &timeReader; bool storesInitialized = false; SdCardMountedIF &sdcMan; - PersistentTmStoreRouter router; + PusTmRouteByFilterHelper persistentTmMap; ReturnValue_t handleTmPacket(TmTcMessage &message); void initStoresIfPossible(bool sdCardUsable); diff --git a/mission/tmtc/PusTmRouteByFilterHelper.cpp b/mission/tmtc/PusTmRouteByFilterHelper.cpp new file mode 100644 index 00000000..63b95733 --- /dev/null +++ b/mission/tmtc/PusTmRouteByFilterHelper.cpp @@ -0,0 +1,19 @@ +#include "PusTmRouteByFilterHelper.h" + +#include + +PusTmRouteByFilterHelper::PusTmRouteByFilterHelper() = default; + +bool PusTmRouteByFilterHelper::packetMatches(PusTmReader& reader, MessageQueueId_t& destination) { + for (const auto filterAndDest : routerMap) { + if (filterAndDest.first.packetMatches(reader)) { + destination = filterAndDest.second; + return true; + } + } + return false; +} + +void PusTmRouteByFilterHelper::addRouting(PusPacketFilter filter, MessageQueueId_t destination) { + routerMap.emplace_back(std::move(filter), destination); +} diff --git a/mission/tmtc/TmStoreRouter.h b/mission/tmtc/PusTmRouteByFilterHelper.h similarity index 53% rename from mission/tmtc/TmStoreRouter.h rename to mission/tmtc/PusTmRouteByFilterHelper.h index 9daa4889..92bb0f6f 100644 --- a/mission/tmtc/TmStoreRouter.h +++ b/mission/tmtc/PusTmRouteByFilterHelper.h @@ -4,10 +4,21 @@ #include #include -class PersistentTmStoreRouter { +/** + * Simple composition of concrecte @PusPacketFilters which also maps them to + * a destination ID. + */ +class PusTmRouteByFilterHelper { public: - PersistentTmStoreRouter(); + PusTmRouteByFilterHelper(); + /** + * Checks whether the packet matches any of the inserted filters and returns + * the destination if it does. Currently only supports one destination. + * @param reader + * @param destination + * @return + */ bool packetMatches(PusTmReader& reader, MessageQueueId_t& destination); void addRouting(PusPacketFilter filter, MessageQueueId_t destination); diff --git a/mission/tmtc/TmFunnelBase.cpp b/mission/tmtc/TmFunnelBase.cpp index 78a13fab..eb480b03 100644 --- a/mission/tmtc/TmFunnelBase.cpp +++ b/mission/tmtc/TmFunnelBase.cpp @@ -5,8 +5,16 @@ #include "fsfw/ipc/QueueFactory.h" TmFunnelBase::TmFunnelBase(FunnelCfg cfg) - : SystemObject(cfg.objectId), name(cfg.name), tmStore(cfg.tmStore), ipcStore(cfg.ipcStore) { - tmQueue = QueueFactory::instance()->createMessageQueue(cfg.tmMsgDepth); + : SystemObject(cfg.objectId), + name(cfg.name), + tmStore(cfg.tmStore), + ipcStore(cfg.ipcStore), + tmQueue(QueueFactory::instance()->createMessageQueue(cfg.tmMsgDepth)), + liveDemux(*tmQueue) {} + +ReturnValue_t TmFunnelBase::demultiplexLivePackets(store_address_t origStoreId, + const uint8_t *tmData, size_t tmSize) { + return liveDemux.demultiplexPackets(tmStore, origStoreId, tmData, tmSize); } TmFunnelBase::~TmFunnelBase() { QueueFactory::instance()->deleteMessageQueue(tmQueue); } @@ -15,43 +23,7 @@ MessageQueueId_t TmFunnelBase::getReportReceptionQueue(uint8_t virtualChannel) c return tmQueue->getId(); } -void TmFunnelBase::addDestination(const char *name, const AcceptsTelemetryIF &downlinkDestination, - uint8_t vcid) { - auto queueId = downlinkDestination.getReportReceptionQueue(vcid); - destinations.emplace_back(name, queueId, vcid); -} - -ReturnValue_t TmFunnelBase::sendPacketToDestinations(store_address_t origStoreId, - TmTcMessage &message, - const uint8_t *packetData, size_t size) { - ReturnValue_t result = returnvalue::OK; - for (unsigned int idx = 0; idx < destinations.size(); idx++) { - const auto &dest = destinations[idx]; - if (destinations.size() > 1) { - if (idx < destinations.size() - 1) { - // Create copy of data to ensure each TM recipient has its own copy. That way, we don't need - // to bother with send order and where the data is deleted. - store_address_t storeId; - result = tmStore.addData(&storeId, packetData, size); - if (result == returnvalue::OK) { - message.setStorageId(storeId); - } else { -#if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << name << "::handlePacket: Store too full to create data copy" << std::endl; -#endif - } - } else { - message.setStorageId(origStoreId); - } - } - result = tmQueue->sendMessage(dest.queueId, &message); - if (result != returnvalue::OK) { -#if FSFW_CPP_OSTREAM_ENABLED == 1 - sif::error << name << "::handlePacket: Error sending TM to downlink handler " << dest.name - << std::endl; -#endif - tmStore.deleteData(message.getStorageId()); - } - } - return result; +void TmFunnelBase::addLiveDestination(const char *name, + const AcceptsTelemetryIF &downlinkDestination, uint8_t vcid) { + liveDemux.addDestination(name, downlinkDestination, vcid); } diff --git a/mission/tmtc/TmFunnelBase.h b/mission/tmtc/TmFunnelBase.h index ef3c6c6a..51d16626 100644 --- a/mission/tmtc/TmFunnelBase.h +++ b/mission/tmtc/TmFunnelBase.h @@ -6,6 +6,7 @@ #include #include #include +#include #include @@ -26,11 +27,11 @@ class TmFunnelBase : public AcceptsTelemetryIF, public SystemObject { uint32_t tmMsgDepth; }; explicit TmFunnelBase(FunnelCfg cfg); - void addDestination(const char* name, const AcceptsTelemetryIF& downlinkDestination, - uint8_t vcid = 0); - ReturnValue_t sendPacketToDestinations(store_address_t origStoreId, TmTcMessage& message, - const uint8_t* packetData, size_t size); [[nodiscard]] MessageQueueId_t getReportReceptionQueue(uint8_t virtualChannel) const override; + void addLiveDestination(const char* name, const AcceptsTelemetryIF& downlinkDestination, + uint8_t vcid = 0); + ReturnValue_t demultiplexLivePackets(store_address_t origStoreId, const uint8_t* tmData, + size_t tmSize); ~TmFunnelBase() override; @@ -38,18 +39,8 @@ class TmFunnelBase : public AcceptsTelemetryIF, public SystemObject { const char* name; StorageManagerIF& tmStore; StorageManagerIF& ipcStore; - - struct Destination { - Destination(const char* name, MessageQueueId_t queueId, uint8_t virtualChannel) - : name(name), queueId(queueId), virtualChannel(virtualChannel) {} - - const char* name; - MessageQueueId_t queueId; - uint8_t virtualChannel = 0; - }; - - std::vector destinations; MessageQueueIF* tmQueue = nullptr; + PusLiveDemux liveDemux; }; #endif /* MISSION_TMTC_TMFUNNELBASE_H_ */ diff --git a/mission/tmtc/TmStoreRouter.cpp b/mission/tmtc/TmStoreRouter.cpp deleted file mode 100644 index d958574e..00000000 --- a/mission/tmtc/TmStoreRouter.cpp +++ /dev/null @@ -1,19 +0,0 @@ -#include "TmStoreRouter.h" - -#include - -PersistentTmStoreRouter::PersistentTmStoreRouter() = default; - -bool PersistentTmStoreRouter::packetMatches(PusTmReader& reader, MessageQueueId_t& destination) { - for (const auto filterAndDest : routerMap) { - if (filterAndDest.first.packetMatches(reader)) { - destination = filterAndDest.second; - return true; - } - } - return false; -} - -void PersistentTmStoreRouter::addRouting(PusPacketFilter filter, MessageQueueId_t destination) { - routerMap.emplace_back(std::move(filter), destination); -} From 49e3002abcd0af55397898e900a3568229e03b05 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 9 Mar 2023 12:20:13 +0100 Subject: [PATCH 033/112] what is the IDE doing.. --- linux/ipcore/VcInterfaceIF.h | 15 ++------ mission/tmtc/DirectTmSinkIF.h | 21 ++++++++++ mission/tmtc/PersistentTmStore.cpp | 62 +++++++++++++++++------------- mission/tmtc/PersistentTmStore.h | 13 +++++-- mission/tmtc/PusLiveDemux.h | 1 + 5 files changed, 72 insertions(+), 40 deletions(-) create mode 100644 mission/tmtc/DirectTmSinkIF.h diff --git a/linux/ipcore/VcInterfaceIF.h b/linux/ipcore/VcInterfaceIF.h index de1bb61e..3b2b7c6c 100644 --- a/linux/ipcore/VcInterfaceIF.h +++ b/linux/ipcore/VcInterfaceIF.h @@ -1,6 +1,7 @@ #ifndef LINUX_OBC_VCINTERFACEIF_H_ #define LINUX_OBC_VCINTERFACEIF_H_ +#include #include #include "fsfw/returnvalues/returnvalue.h" @@ -8,22 +9,14 @@ /** * @brief Interface class for managing different virtual channels of the PTME IP core implemented * in the programmable logic. - * + * @details + * Also implements @DirectTmSinkIF to allow wiriting to the VC directly. * @author J. Meier */ -class VcInterfaceIF { +class VcInterfaceIF : public DirectTmSinkIF { public: virtual ~VcInterfaceIF(){}; - /** - * @brief Implememts the functionality to write data in the virtual channel of the PTME IP - * Core. - * - * @param data Pointer to buffer holding the data to write - * @param size Number of bytes to write - */ - virtual ReturnValue_t write(const uint8_t* data, size_t size) = 0; - virtual ReturnValue_t initialize() = 0; }; diff --git a/mission/tmtc/DirectTmSinkIF.h b/mission/tmtc/DirectTmSinkIF.h new file mode 100644 index 00000000..ca055ea9 --- /dev/null +++ b/mission/tmtc/DirectTmSinkIF.h @@ -0,0 +1,21 @@ +#ifndef MISSION_TMTC_DIRECTTMSINKIF_H_ +#define MISSION_TMTC_DIRECTTMSINKIF_H_ + +#include + +#include "fsfw/retval.h" + +class DirectTmSinkIF { + public: + virtual ~DirectTmSinkIF() = default; + + /** + * @brief Implememts the functionality to write to a TM sink directly + * + * @param data Pointer to buffer holding the data to write + * @param size Number of bytes to write + */ + virtual ReturnValue_t write(const uint8_t* data, size_t size) = 0; +}; + +#endif /* MISSION_TMTC_DIRECTTMSINKIF_H_ */ diff --git a/mission/tmtc/PersistentTmStore.cpp b/mission/tmtc/PersistentTmStore.cpp index 0324a649..ea1b6c6f 100644 --- a/mission/tmtc/PersistentTmStore.cpp +++ b/mission/tmtc/PersistentTmStore.cpp @@ -69,14 +69,14 @@ ReturnValue_t PersistentTmStore::handleCommandQueue(StorageManagerIF& ipcStore, SerializeIF::Endianness::NETWORK); SerializeAdapter::deSerialize(&dumpUntilUnixSeconds, accessor.second.data() + 4, &size, SerializeIF::Endianness::NETWORK); - dumpFromUpTo(dumpFromUnixSeconds, dumpUntilUnixSeconds); + startDumpFromUpTo(dumpFromUnixSeconds, dumpUntilUnixSeconds); } } return returnvalue::OK; } -void PersistentTmStore::dumpFrom(uint32_t fromUnixSeconds) { - return dumpFromUpTo(fromUnixSeconds, currentTv.tv_sec); +ReturnValue_t PersistentTmStore::startDumpFrom(uint32_t fromUnixSeconds) { + return startDumpFromUpTo(fromUnixSeconds, currentTv.tv_sec); } ReturnValue_t PersistentTmStore::storePacket(PusTmReader& reader) { @@ -155,7 +155,7 @@ void PersistentTmStore::deleteUpTo(uint32_t unixSeconds) { } // Convert file time to the UNIX epoch struct tm fileTime {}; - if (pathToTm(file.path(), fileTime) != returnvalue::OK) { + if (pathToTime(file.path(), fileTime) != returnvalue::OK) { sif::error << "Time extraction for " << file << "failed" << std::endl; continue; } @@ -166,32 +166,30 @@ void PersistentTmStore::deleteUpTo(uint32_t unixSeconds) { } } -void PersistentTmStore::dumpFromUpTo(uint32_t fromUnixSeconds, uint32_t upToUnixSeconds) { +ReturnValue_t PersistentTmStore::startDumpFromUpTo(uint32_t fromUnixSeconds, + uint32_t upToUnixSeconds) { using namespace std::filesystem; - for (auto const& file : directory_iterator(basePath)) { - if (file.is_directory()) { - continue; - } - struct tm fileTime {}; - if (pathToTm(file.path(), fileTime) != returnvalue::OK) { - sif::error << "Time extraction for file " << file << "failed" << std::endl; - continue; - } - auto fileEpoch = static_cast(timegm(&fileTime)); - if ((fileEpoch > fromUnixSeconds) and (fileEpoch + rolloverDiffSeconds <= upToUnixSeconds)) { - fileToPackets(file, fileEpoch); - } - } -} - -ReturnValue_t PersistentTmStore::pathToTm(const std::filesystem::path& path, struct tm& time) { - auto pathStr = path.string(); - size_t splitChar = pathStr.find('_'); - auto timeOnlyStr = pathStr.substr(splitChar + 1); - if (nullptr == strptime(timeOnlyStr.c_str(), FILE_DATE_FORMAT, &time)) { + if (state == State::DUMPING) { return returnvalue::FAILED; } + activeDumpDirIter = directory_iterator(basePath); + state = State::DUMPING; return returnvalue::OK; + // for (auto const& file : directory_iterator(basePath)) { + // if (file.is_directory()) { + // continue; + // } + // struct tm fileTime {}; + // if (pathToTm(file.path(), fileTime) != returnvalue::OK) { + // sif::error << "Time extraction for file " << file << "failed" << std::endl; + // continue; + // } + // auto fileEpoch = static_cast(timegm(&fileTime)); + // if ((fileEpoch > fromUnixSeconds) and (fileEpoch + rolloverDiffSeconds <= upToUnixSeconds)) + // { + // fileToPackets(file, fileEpoch); + // } + // } } void PersistentTmStore::fileToPackets(const std::filesystem::path& path, uint32_t unixStamp) { @@ -227,6 +225,18 @@ void PersistentTmStore::fileToPackets(const std::filesystem::path& path, uint32_ } } +ReturnValue_t PersistentTmStore::dumpNextPacket(size_t& dumpedLen) {} + +ReturnValue_t PersistentTmStore::pathToTime(const std::filesystem::path& path, struct tm& time) { + auto pathStr = path.string(); + size_t splitChar = pathStr.find('_'); + auto timeOnlyStr = pathStr.substr(splitChar + 1); + if (nullptr == strptime(timeOnlyStr.c_str(), FILE_DATE_FORMAT, &time)) { + return returnvalue::FAILED; + } + return returnvalue::OK; +} + ReturnValue_t PersistentTmStore::createMostRecentFile(std::optional suffix) { using namespace std::filesystem; unsigned currentIdx = 0; diff --git a/mission/tmtc/PersistentTmStore.h b/mission/tmtc/PersistentTmStore.h index 3b72cb2d..ad7ff4e0 100644 --- a/mission/tmtc/PersistentTmStore.h +++ b/mission/tmtc/PersistentTmStore.h @@ -17,6 +17,7 @@ enum class RolloverInterval { MINUTELY, HOURLY, DAILY }; class PersistentTmStore : public TmStoreFrontendSimpleIF, public SystemObject { public: + enum class State { IDLE, DUMPING }; static constexpr uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::PERSISTENT_TM_STORE; //! [EXPORT] : [COMMENT] @@ -32,8 +33,9 @@ class PersistentTmStore : public TmStoreFrontendSimpleIF, public SystemObject { ReturnValue_t handleCommandQueue(StorageManagerIF& ipcStore, TmFunnelBase& tmFunnel); void deleteUpTo(uint32_t unixSeconds); - void dumpFrom(uint32_t fromUnixSeconds); - void dumpFromUpTo(uint32_t fromUnixSeconds, uint32_t upToUnixSeconds); + ReturnValue_t startDumpFrom(uint32_t fromUnixSeconds); + ReturnValue_t startDumpFromUpTo(uint32_t fromUnixSeconds, uint32_t upToUnixSeconds); + ReturnValue_t dumpNextPacket(size_t& dumpedLen); // ReturnValue_t passPacket(PusTmReader& reader); ReturnValue_t storePacket(PusTmReader& reader); @@ -45,6 +47,7 @@ class PersistentTmStore : public TmStoreFrontendSimpleIF, public SystemObject { static constexpr char FILE_DATE_FORMAT[] = "%FT%H%M%SZ"; MessageQueueIF* tcQueue; + State state = State::IDLE; // PacketFilter filter; CdsShortTimeStamper timeReader; bool baseDirUninitialized = true; @@ -56,6 +59,10 @@ class PersistentTmStore : public TmStoreFrontendSimpleIF, public SystemObject { std::array fileBuf{}; timeval currentTv; timeval activeFileTv{}; + std::filesystem::directory_iterator activeDumpDirIter; + std::filesystem::path activeDumpFile; + size_t activeDumpFileSize = 0; + size_t activeDumpCurrentSize = 0; std::optional activeFile; SdCardMountedIF& sdcMan; StorageManagerIF& tmStore; @@ -68,7 +75,7 @@ class PersistentTmStore : public TmStoreFrontendSimpleIF, public SystemObject { void calcDiffSeconds(RolloverInterval intervalUnit, uint32_t intervalCount); ReturnValue_t createMostRecentFile(std::optional suffix); - static ReturnValue_t pathToTm(const std::filesystem::path& path, struct tm& time); + static ReturnValue_t pathToTime(const std::filesystem::path& path, struct tm& time); void fileToPackets(const std::filesystem::path& path, uint32_t unixStamp); bool updateBaseDir(); ReturnValue_t assignAndOrCreateMostRecentFile(); diff --git a/mission/tmtc/PusLiveDemux.h b/mission/tmtc/PusLiveDemux.h index 1288b173..b9af04ff 100644 --- a/mission/tmtc/PusLiveDemux.h +++ b/mission/tmtc/PusLiveDemux.h @@ -4,6 +4,7 @@ #include #include #include +#include #include From eb61996f91c44091be029ce6cda4e4c82d9835f7 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 9 Mar 2023 13:15:42 +0100 Subject: [PATCH 034/112] Persistent Tm Store now has dump state --- common/config/eive/resultClassIds.h | 1 + mission/tmtc/PersistentTmStore.cpp | 153 ++++++++++++++++++++-------- mission/tmtc/PersistentTmStore.h | 29 +++++- 3 files changed, 133 insertions(+), 50 deletions(-) diff --git a/common/config/eive/resultClassIds.h b/common/config/eive/resultClassIds.h index df47d935..125dd79a 100644 --- a/common/config/eive/resultClassIds.h +++ b/common/config/eive/resultClassIds.h @@ -42,6 +42,7 @@ enum commonClassIds : uint8_t { ACS_DETUMBLE, // ACSDTB SD_CARD_MANAGER, // SDMA LOCAL_PARAM_HANDLER, // LPH + PERSISTENT_TM_STORE, // PTM COMMON_CLASS_ID_END // [EXPORT] : [END] }; } diff --git a/mission/tmtc/PersistentTmStore.cpp b/mission/tmtc/PersistentTmStore.cpp index ea1b6c6f..5784fdba 100644 --- a/mission/tmtc/PersistentTmStore.cpp +++ b/mission/tmtc/PersistentTmStore.cpp @@ -1,6 +1,7 @@ #include "PersistentTmStore.h" #include +#include #include #include @@ -172,60 +173,122 @@ ReturnValue_t PersistentTmStore::startDumpFromUpTo(uint32_t fromUnixSeconds, if (state == State::DUMPING) { return returnvalue::FAILED; } - activeDumpDirIter = directory_iterator(basePath); + dumpParams.dirIter = directory_iterator(basePath); + dumpParams.fromUnixTime = fromUnixSeconds; + dumpParams.untilUnixTime = upToUnixSeconds; state = State::DUMPING; + if (loadNextDumpFile() == DUMP_DONE) { + // State will be set inside the function loading the next file. + return DUMP_DONE; + } return returnvalue::OK; - // for (auto const& file : directory_iterator(basePath)) { - // if (file.is_directory()) { - // continue; - // } - // struct tm fileTime {}; - // if (pathToTm(file.path(), fileTime) != returnvalue::OK) { - // sif::error << "Time extraction for file " << file << "failed" << std::endl; - // continue; - // } - // auto fileEpoch = static_cast(timegm(&fileTime)); - // if ((fileEpoch > fromUnixSeconds) and (fileEpoch + rolloverDiffSeconds <= upToUnixSeconds)) - // { - // fileToPackets(file, fileEpoch); - // } - // } } -void PersistentTmStore::fileToPackets(const std::filesystem::path& path, uint32_t unixStamp) { - store_address_t storeId; - TmTcMessage message; - size_t size = std::filesystem::file_size(path); - if (size < 6) { - // Can't even read the CCSDS header - return; - } - std::ifstream ifile(path, std::ios::binary); - ifile.read(reinterpret_cast(fileBuf.data()), static_cast(size)); - size_t currentIdx = 0; - while (currentIdx < size) { - PusTmReader reader(&timeReader, fileBuf.data(), fileBuf.size()); - // CRC check to fully ensure this is a valid TM - ReturnValue_t result = reader.parseDataWithCrcCheck(); - if (result == returnvalue::OK) { - // TODO: Blow the data out to the VC directly. Use IF function to do this. - // result = tmStore.addData(&storeId, fileBuf.data() + currentIdx, - // reader.getFullPacketLen()); if (result != returnvalue::OK) { - // continue; - // } - // funnel.sendPacketToLiveDestinations(storeId, message, fileBuf.data() + currentIdx, - // reader.getFullPacketLen()); - currentIdx += reader.getFullPacketLen(); - } else { - sif::error << "Parsing of PUS TM failed with code " << result << std::endl; - triggerEvent(POSSIBLE_FILE_CORRUPTION, result, unixStamp); - // Stop for now, do not really know where to continue and we do not trust the file anymore. +ReturnValue_t PersistentTmStore::loadNextDumpFile() { + using namespace std::filesystem; + std::error_code e; + for (; dumpParams.dirIter != directory_iterator(); dumpParams.dirIter++) { + if (dumpParams.dirEntry.is_directory(e)) { + continue; + } + dumpParams.fileSize = std::filesystem::file_size(dumpParams.dirEntry.path()); + // Can't even read CCSDS header. + if (dumpParams.fileSize <= 6) { + continue; + } + if (dumpParams.fileSize > fileBuf.size()) { + sif::error << "PersistentTmStore: File too large, is deleted" << std::endl; + triggerEvent(FILE_TOO_LARGE, dumpParams.fileSize, fileBuf.size()); + std::remove(dumpParams.dirEntry.path().c_str()); + continue; + } + const path& file = dumpParams.dirEntry.path(); + struct tm fileTime {}; + if (pathToTime(file, fileTime) != returnvalue::OK) { + sif::error << "Time extraction for file " << file << "failed" << std::endl; + continue; + } + auto fileEpoch = static_cast(timegm(&fileTime)); + if ((fileEpoch > dumpParams.fromUnixTime) and + (fileEpoch + rolloverDiffSeconds <= dumpParams.untilUnixTime)) { + dumpParams.currentSize = 0; + dumpParams.currentFileUnixStamp = fileEpoch; + std::ifstream ifile(file, std::ios::binary); + ifile.read(reinterpret_cast(fileBuf.data()), + static_cast(dumpParams.fileSize)); break; } } + if (dumpParams.dirIter == directory_iterator()) { + state = State::IDLE; + return DUMP_DONE; + } + return returnvalue::OK; } -ReturnValue_t PersistentTmStore::dumpNextPacket(size_t& dumpedLen) {} +// void PersistentTmStore::fileToPackets(const std::filesystem::path& path, uint32_t unixStamp) { +// store_address_t storeId; +// TmTcMessage message; +// size_t size = std::filesystem::file_size(path); +// if (size < 6) { +// // Can't even read the CCSDS header +// return; +// } +// std::ifstream ifile(path, std::ios::binary); +// ifile.read(reinterpret_cast(fileBuf.data()), static_cast(size)); +// size_t currentIdx = 0; +// while (currentIdx < size) { +// PusTmReader reader(&timeReader, fileBuf.data(), fileBuf.size()); +// // CRC check to fully ensure this is a valid TM +// ReturnValue_t result = reader.parseDataWithCrcCheck(); +// if (result == returnvalue::OK) { +// // TODO: Blow the data out to the VC directly. Use IF function to do this. +// // result = tmStore.addData(&storeId, fileBuf.data() + currentIdx, +// // reader.getFullPacketLen()); if (result != returnvalue::OK) { +// // continue; +// // } +// // funnel.sendPacketToLiveDestinations(storeId, message, fileBuf.data() + currentIdx, +// // reader.getFullPacketLen()); +// currentIdx += reader.getFullPacketLen(); +// } else { +// sif::error << "Parsing of PUS TM failed with code " << result << std::endl; +// triggerEvent(POSSIBLE_FILE_CORRUPTION, result, unixStamp); +// // Stop for now, do not really know where to continue and we do not trust the file anymore. +// break; +// } +// } +// } + +ReturnValue_t PersistentTmStore::dumpNextPacket(DirectTmSinkIF& tmSink, size_t& dumpedLen) { + if (state == State::IDLE) { + return returnvalue::FAILED; + } + PusTmReader reader(&timeReader, fileBuf.data() + dumpParams.currentSize, + fileBuf.size() - dumpParams.currentSize); + // CRC check to fully ensure this is a valid TM + ReturnValue_t result = reader.parseDataWithCrcCheck(); + if (result == returnvalue::OK) { + result = tmSink.write(fileBuf.data() + dumpParams.currentSize, reader.getFullPacketLen()); + if (result != returnvalue::OK) { + // TODO: Event? + sif::error << "PersistentTmStore: Writing to TM sink failed" << std::endl; + } + dumpParams.currentSize += reader.getFullPacketLen(); + dumpedLen = reader.getFullPacketLen(); + if (dumpParams.currentSize >= dumpParams.fileSize) { + return loadNextDumpFile(); + } + } else { + sif::error << "Parsing of PUS TM failed with code " << result << std::endl; + triggerEvent(POSSIBLE_FILE_CORRUPTION, result, dumpParams.currentFileUnixStamp); + // Delete the file and load next. Could use better algorithm to partially + // restore the file dump, but for now do not trust the file. + dumpedLen = 0; + std::remove(dumpParams.dirEntry.path().c_str()); + return loadNextDumpFile(); + } + return returnvalue::OK; +} ReturnValue_t PersistentTmStore::pathToTime(const std::filesystem::path& path, struct tm& time) { auto pathStr = path.string(); diff --git a/mission/tmtc/PersistentTmStore.h b/mission/tmtc/PersistentTmStore.h index ad7ff4e0..88c79443 100644 --- a/mission/tmtc/PersistentTmStore.h +++ b/mission/tmtc/PersistentTmStore.h @@ -7,17 +7,22 @@ #include #include #include +#include #include #include "TmFunnelBase.h" #include "eive/eventSubsystemIds.h" +#include "eive/resultClassIds.h" enum class RolloverInterval { MINUTELY, HOURLY, DAILY }; class PersistentTmStore : public TmStoreFrontendSimpleIF, public SystemObject { public: enum class State { IDLE, DUMPING }; + static constexpr uint8_t INTERFACE_ID = CLASS_ID::PERSISTENT_TM_STORE; + static constexpr ReturnValue_t DUMP_DONE = returnvalue::makeCode(INTERFACE_ID, 0); + static constexpr uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::PERSISTENT_TM_STORE; //! [EXPORT] : [COMMENT] @@ -25,6 +30,9 @@ class PersistentTmStore : public TmStoreFrontendSimpleIF, public SystemObject { //! P2: Timestamp of possibly corrupt file as a unix timestamp. static constexpr Event POSSIBLE_FILE_CORRUPTION = event::makeEvent(SUBSYSTEM_ID, 0, severity::LOW); + //! [EXPORT] : [COMMENT] File in store too large. P1: Detected file size + //! P2: Allowed file size + static constexpr Event FILE_TOO_LARGE = event::makeEvent(SUBSYSTEM_ID, 1, severity::LOW); PersistentTmStore(object_id_t objectId, const char* baseDir, std::string baseName, RolloverInterval intervalUnit, uint32_t intervalCount, StorageManagerIF& tmStore, SdCardMountedIF& sdcMan); @@ -35,7 +43,7 @@ class PersistentTmStore : public TmStoreFrontendSimpleIF, public SystemObject { void deleteUpTo(uint32_t unixSeconds); ReturnValue_t startDumpFrom(uint32_t fromUnixSeconds); ReturnValue_t startDumpFromUpTo(uint32_t fromUnixSeconds, uint32_t upToUnixSeconds); - ReturnValue_t dumpNextPacket(size_t& dumpedLen); + ReturnValue_t dumpNextPacket(DirectTmSinkIF& tmSink, size_t& dumpedLen); // ReturnValue_t passPacket(PusTmReader& reader); ReturnValue_t storePacket(PusTmReader& reader); @@ -46,6 +54,9 @@ class PersistentTmStore : public TmStoreFrontendSimpleIF, public SystemObject { // ISO8601 timestamp. static constexpr char FILE_DATE_FORMAT[] = "%FT%H%M%SZ"; + //! [EXPORT] : [SKIP] + static constexpr ReturnValue_t INVALID_FILE_DETECTED_AND_DELETED = returnvalue::makeCode(2, 1); + MessageQueueIF* tcQueue; State state = State::IDLE; // PacketFilter filter; @@ -59,10 +70,17 @@ class PersistentTmStore : public TmStoreFrontendSimpleIF, public SystemObject { std::array fileBuf{}; timeval currentTv; timeval activeFileTv{}; - std::filesystem::directory_iterator activeDumpDirIter; - std::filesystem::path activeDumpFile; - size_t activeDumpFileSize = 0; - size_t activeDumpCurrentSize = 0; + + struct ActiveDumpParams { + uint32_t fromUnixTime = 0; + uint32_t untilUnixTime = 0; + uint32_t currentFileUnixStamp = 0; + std::filesystem::directory_iterator dirIter; + std::filesystem::directory_entry dirEntry; + size_t fileSize = 0; + size_t currentSize = 0; + }; + ActiveDumpParams dumpParams; std::optional activeFile; SdCardMountedIF& sdcMan; StorageManagerIF& tmStore; @@ -77,6 +95,7 @@ class PersistentTmStore : public TmStoreFrontendSimpleIF, public SystemObject { ReturnValue_t createMostRecentFile(std::optional suffix); static ReturnValue_t pathToTime(const std::filesystem::path& path, struct tm& time); void fileToPackets(const std::filesystem::path& path, uint32_t unixStamp); + ReturnValue_t loadNextDumpFile(); bool updateBaseDir(); ReturnValue_t assignAndOrCreateMostRecentFile(); }; From ac2c4c7abcb76786d0d6a0da1160a9198ecbbd2b Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 9 Mar 2023 16:43:35 +0100 Subject: [PATCH 035/112] heater name bugfix --- common/config/eive/objects.h | 2 +- fsfw | 2 +- mission/core/GenericFactory.cpp | 2 +- tmtc | 2 +- 4 files changed, 4 insertions(+), 4 deletions(-) diff --git a/common/config/eive/objects.h b/common/config/eive/objects.h index cb468ef2..31d1862d 100644 --- a/common/config/eive/objects.h +++ b/common/config/eive/objects.h @@ -136,7 +136,7 @@ enum commonObjects : uint32_t { HEATER_4_CAMERA = 0x60000004, HEATER_5_STR = 0x60000005, HEATER_6_DRO = 0x60000006, - HEATER_7_HPA = 0x60000007, + HEATER_7_SYRLINKS = 0x60000007, // 0x73 ('s') for assemblies and system/subsystem components ACS_BOARD_ASS = 0x73000001, diff --git a/fsfw b/fsfw index 26e44451..23d9b44b 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit 26e4445189b676eaee11840e5a9d0ede25cf3896 +Subproject commit 23d9b44b3e02bb0d35e4622d125b48e9b44fee2c diff --git a/mission/core/GenericFactory.cpp b/mission/core/GenericFactory.cpp index b6119eda..c6a3e216 100644 --- a/mission/core/GenericFactory.cpp +++ b/mission/core/GenericFactory.cpp @@ -224,7 +224,7 @@ void ObjectFactory::createGenericHeaterComponents(GpioIF& gpioIF, PowerSwitchIF& {new HealthDevice(objects::HEATER_4_CAMERA, MessageQueueIF::NO_QUEUE), gpioIds::HEATER_4}, {new HealthDevice(objects::HEATER_5_STR, MessageQueueIF::NO_QUEUE), gpioIds::HEATER_5}, {new HealthDevice(objects::HEATER_6_DRO, MessageQueueIF::NO_QUEUE), gpioIds::HEATER_6}, - {new HealthDevice(objects::HEATER_7_HPA, MessageQueueIF::NO_QUEUE), gpioIds::HEATER_7}, + {new HealthDevice(objects::HEATER_7_SYRLINKS, MessageQueueIF::NO_QUEUE), gpioIds::HEATER_7}, }}); heaterHandler = new HeaterHandler(objects::HEATER_HANDLER, &gpioIF, helper, &pwrSwitcher, pcdu::Switches::PDU2_CH3_TCS_BOARD_HEATER_IN_8V); diff --git a/tmtc b/tmtc index a3e03350..bf158bee 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit a3e03350faf3055835e65e744bc177761448ce20 +Subproject commit bf158bee2d79c95de3ac2e38f4e7d977699711b1 From 9f9b1e440ab3f02de3783cfb7aee691ac1a6c5a9 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 9 Mar 2023 16:52:47 +0100 Subject: [PATCH 036/112] changelog --- CHANGELOG.md | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/CHANGELOG.md b/CHANGELOG.md index 8ab39c23..4d2e2cbb 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -16,6 +16,10 @@ will consitute of a breaking change warranting a new major release: # [unreleased] +## Fixed + +- Fix for heater names: HPA heater (index 7) is now the Syrlinks heater. + # [v1.36.0] 2023-03-08 eive-tmtc: v2.17.2 From 96865c1dd2990370ebe331d54c790223d9c70d3b Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 9 Mar 2023 17:44:05 +0100 Subject: [PATCH 037/112] continue TM handling refactoring --- bsp_q7s/core/ObjectFactory.cpp | 49 ++++----- linux/ipcore/PapbVcInterface.h | 4 +- linux/ipcore/Ptme.cpp | 2 +- linux/ipcore/Ptme.h | 6 +- .../{VcInterfaceIF.h => VirtualChannelIF.h} | 4 +- mission/tmtc/CMakeLists.txt | 5 + mission/tmtc/CcsdsIpCoreHandler.cpp | 102 +++++++----------- mission/tmtc/CcsdsIpCoreHandler.h | 34 +++--- mission/tmtc/LiveTmTask.cpp | 16 +++ mission/tmtc/LiveTmTask.h | 18 ++++ mission/tmtc/PersistentLogTmStoreTask.cpp | 1 + mission/tmtc/PersistentLogTmStoreTask.h | 26 +++++ mission/tmtc/PersistentSingleTmStoreTask.cpp | 37 +++++++ mission/tmtc/PersistentSingleTmStoreTask.h | 23 ++++ mission/tmtc/PersistentTmStore.cpp | 13 +-- mission/tmtc/PersistentTmStore.h | 8 +- mission/tmtc/PersistentTmStoreWithTmQueue.cpp | 28 +++++ mission/tmtc/PersistentTmStoreWithTmQueue.h | 19 ++++ mission/tmtc/VirtualChannel.cpp | 81 +++----------- mission/tmtc/VirtualChannel.h | 47 +++----- mission/tmtc/VirtualChannelWithQueue.cpp | 48 +++++++++ mission/tmtc/VirtualChannelWithQueue.h | 45 ++++++++ 22 files changed, 396 insertions(+), 220 deletions(-) rename linux/ipcore/{VcInterfaceIF.h => VirtualChannelIF.h} (86%) create mode 100644 mission/tmtc/LiveTmTask.cpp create mode 100644 mission/tmtc/LiveTmTask.h create mode 100644 mission/tmtc/PersistentLogTmStoreTask.cpp create mode 100644 mission/tmtc/PersistentLogTmStoreTask.h create mode 100644 mission/tmtc/PersistentSingleTmStoreTask.cpp create mode 100644 mission/tmtc/PersistentSingleTmStoreTask.h create mode 100644 mission/tmtc/PersistentTmStoreWithTmQueue.cpp create mode 100644 mission/tmtc/PersistentTmStoreWithTmQueue.h create mode 100644 mission/tmtc/VirtualChannelWithQueue.cpp create mode 100644 mission/tmtc/VirtualChannelWithQueue.h diff --git a/bsp_q7s/core/ObjectFactory.cpp b/bsp_q7s/core/ObjectFactory.cpp index ee58b109..62aecde4 100644 --- a/bsp_q7s/core/ObjectFactory.cpp +++ b/bsp_q7s/core/ObjectFactory.cpp @@ -73,6 +73,7 @@ #include #include #include +#include #include @@ -113,9 +114,9 @@ #include "mission/system/objects/AcsBoardAssembly.h" #include "mission/tmtc/CcsdsIpCoreHandler.h" #include "mission/tmtc/TmFunnelHandler.h" -#include "mission/tmtc/VirtualChannel.h" ResetArgs RESET_ARGS_GNSS; +std::atomic_bool LINK_STATE = CcsdsIpCoreHandler::LINK_DOWN; void Factory::setStaticFrameworkObjectIds() { PusServiceBase::PUS_DISTRIBUTOR = objects::PUS_PACKET_DISTRIBUTOR; @@ -740,16 +741,16 @@ ReturnValue_t ObjectFactory::createCcsdsComponents(LinuxLibgpioIF* gpioComIF, gpioCookiePtmeIp->addGpio(gpioIds::VC3_PAPB_EMPTY, gpio); gpioChecker(gpioComIF->addGpios(gpioCookiePtmeIp), "PTME PAPB VCs"); // Creating virtual channel interfaces - VcInterfaceIF* vc0 = + VirtualChannelIF* vc0 = new PapbVcInterface(gpioComIF, gpioIds::VC0_PAPB_BUSY, gpioIds::VC0_PAPB_EMPTY, q7s::UIO_PTME, q7s::uiomapids::PTME_VC0); - VcInterfaceIF* vc1 = + VirtualChannelIF* vc1 = new PapbVcInterface(gpioComIF, gpioIds::VC1_PAPB_BUSY, gpioIds::VC1_PAPB_EMPTY, q7s::UIO_PTME, q7s::uiomapids::PTME_VC1); - VcInterfaceIF* vc2 = + VirtualChannelIF* vc2 = new PapbVcInterface(gpioComIF, gpioIds::VC2_PAPB_BUSY, gpioIds::VC2_PAPB_EMPTY, q7s::UIO_PTME, q7s::uiomapids::PTME_VC2); - VcInterfaceIF* vc3 = + VirtualChannelIF* vc3 = new PapbVcInterface(gpioComIF, gpioIds::VC3_PAPB_BUSY, gpioIds::VC3_PAPB_EMPTY, q7s::UIO_PTME, q7s::uiomapids::PTME_VC3); // Creating ptme object and adding virtual channel interfaces @@ -763,26 +764,26 @@ ReturnValue_t ObjectFactory::createCcsdsComponents(LinuxLibgpioIF* gpioComIF, PtmeConfig* ptmeConfig = new PtmeConfig(objects::PTME_CONFIG, axiPtmeConfig); *ipCoreHandler = new CcsdsIpCoreHandler(objects::CCSDS_HANDLER, objects::CCSDS_PACKET_DISTRIBUTOR, - *ptme, *ptmeConfig, gpioComIF, gpioIds::RS485_EN_TX_CLOCK, - gpioIds::RS485_EN_TX_DATA); - VirtualChannel* vc = nullptr; - vc = new VirtualChannel(objects::PTME_VC0_LIVE_TM, ccsds::VC0, "PTME VC0 LIVE TM", - config::VC0_QUEUE_SIZE); - (*ipCoreHandler)->addVirtualChannel(ccsds::VC0, vc); - vc = new VirtualChannel(objects::PTME_VC1_LOG_TM, ccsds::VC1, "PTME VC1 LOG TM", - config::VC1_QUEUE_SIZE); - pusFunnel.addPersistentTmStoreRouting(filters::okFilter(), vc->getReportReceptionQueue()); - pusFunnel.addPersistentTmStoreRouting(filters::notOkFilter(), vc->getReportReceptionQueue()); - pusFunnel.addPersistentTmStoreRouting(filters::miscFilter(), vc->getReportReceptionQueue()); - (*ipCoreHandler)->addVirtualChannel(ccsds::VC1, vc); - vc = new VirtualChannel(objects::PTME_VC2_HK_TM, ccsds::VC2, "PTME VC2 HK TM", - config::VC2_QUEUE_SIZE); - pusFunnel.addPersistentTmStoreRouting(filters::hkFilter(), vc->getReportReceptionQueue()); - (*ipCoreHandler)->addVirtualChannel(ccsds::VC2, vc); - vc = new VirtualChannel(objects::PTME_VC3_CFDP_TM, ccsds::VC3, "PTME VC3 CFDP TM", - config::VC3_QUEUE_SIZE); + *ptmeConfig, LINK_STATE, gpioComIF, + gpioIds::RS485_EN_TX_CLOCK, gpioIds::RS485_EN_TX_DATA); + VirtualChannel* vc = new VirtualChannel(objects::PTME_VC0_LIVE_TM, ccsds::VC0, "PTME VC0 LIVE TM", + *ptme, LINK_STATE); + //(*ipCoreHandler)->addVirtualChannel(ccsds::VC0, vc); + vc = new VirtualChannel(objects::PTME_VC1_LOG_TM, ccsds::VC1, "PTME VC1 LOG TM", *ptme, + LINK_STATE); + + // pusFunnel.addPersistentTmStoreRouting(filters::okFilter(), vc->getReportReceptionQueue()); + // pusFunnel.addPersistentTmStoreRouting(filters::notOkFilter(), vc->getReportReceptionQueue()); + // pusFunnel.addPersistentTmStoreRouting(filters::miscFilter(), vc->getReportReceptionQueue()); + //(*ipCoreHandler)->addVirtualChannel(ccsds::VC1, vc); + vc = new VirtualChannel(objects::PTME_VC2_HK_TM, ccsds::VC2, "PTME VC2 HK TM", *ptme, LINK_STATE); + // auto hkTmStoreTask = new PersistentSingleTmStoreTask(); + // pusFunnel.addPersistentTmStoreRouting(filters::hkFilter(), vc->getReportReceptionQueue()); + //(*ipCoreHandler)->addVirtualChannel(ccsds::VC2, vc); + vc = new VirtualChannel(objects::PTME_VC3_CFDP_TM, ccsds::VC3, "PTME VC3 CFDP TM", *ptme, + LINK_STATE); // TODO: Set VC destination in CFDP funnel. - (*ipCoreHandler)->addVirtualChannel(ccsds::VC3, vc); + //(*ipCoreHandler)->addVirtualChannel(ccsds::VC3, vc); ReturnValue_t result = (*ipCoreHandler)->connectModeTreeParent(satsystem::com::SUBSYSTEM); if (result != returnvalue::OK) { diff --git a/linux/ipcore/PapbVcInterface.h b/linux/ipcore/PapbVcInterface.h index 83081d9d..5fb71340 100644 --- a/linux/ipcore/PapbVcInterface.h +++ b/linux/ipcore/PapbVcInterface.h @@ -3,10 +3,10 @@ #include #include +#include #include "OBSWConfig.h" #include "fsfw/returnvalues/returnvalue.h" -#include "linux/ipcore/VcInterfaceIF.h" /** * @brief This class handles the transmission of data to a virtual channel of the PTME IP Core @@ -14,7 +14,7 @@ * * @author J. Meier */ -class PapbVcInterface : public VcInterfaceIF { +class PapbVcInterface : public VirtualChannelIF { public: /** * @brief Constructor diff --git a/linux/ipcore/Ptme.cpp b/linux/ipcore/Ptme.cpp index 50b1a37c..714c71be 100644 --- a/linux/ipcore/Ptme.cpp +++ b/linux/ipcore/Ptme.cpp @@ -32,7 +32,7 @@ ReturnValue_t Ptme::writeToVc(uint8_t vcId, const uint8_t* data, size_t size) { return result; } -void Ptme::addVcInterface(VcId_t vcId, VcInterfaceIF* vc) { +void Ptme::addVcInterface(VcId_t vcId, VirtualChannelIF* vc) { if (vcId > config::NUMBER_OF_VIRTUAL_CHANNELS) { sif::warning << "Ptme::addVcInterface: Invalid virtual channel ID" << std::endl; return; diff --git a/linux/ipcore/Ptme.h b/linux/ipcore/Ptme.h index d826ac57..aec7bcb4 100644 --- a/linux/ipcore/Ptme.h +++ b/linux/ipcore/Ptme.h @@ -3,6 +3,7 @@ #include #include +#include #include #include @@ -10,7 +11,6 @@ #include "OBSWConfig.h" #include "fsfw/returnvalues/returnvalue.h" #include "linux/ipcore/PtmeIF.h" -#include "linux/ipcore/VcInterfaceIF.h" /** * @brief This class handles the interfacing to the telemetry (PTME) IP core. @@ -40,7 +40,7 @@ class Ptme : public PtmeIF, public SystemObject { * @brief This function adds the reference to a virtual channel interface to the vcInterface * map. */ - void addVcInterface(VcId_t vcId, VcInterfaceIF* vc); + void addVcInterface(VcId_t vcId, VirtualChannelIF* vc); private: static const uint8_t INTERFACE_ID = CLASS_ID::PTME; @@ -73,7 +73,7 @@ class Ptme : public PtmeIF, public SystemObject { uint32_t* ptmeBaseAddress = nullptr; - using VcInterfaceMap = std::unordered_map; + using VcInterfaceMap = std::unordered_map; using VcInterfaceMapIter = VcInterfaceMap::iterator; VcInterfaceMap vcInterfaceMap; diff --git a/linux/ipcore/VcInterfaceIF.h b/linux/ipcore/VirtualChannelIF.h similarity index 86% rename from linux/ipcore/VcInterfaceIF.h rename to linux/ipcore/VirtualChannelIF.h index 3b2b7c6c..266a56c3 100644 --- a/linux/ipcore/VcInterfaceIF.h +++ b/linux/ipcore/VirtualChannelIF.h @@ -13,9 +13,9 @@ * Also implements @DirectTmSinkIF to allow wiriting to the VC directly. * @author J. Meier */ -class VcInterfaceIF : public DirectTmSinkIF { +class VirtualChannelIF : public DirectTmSinkIF { public: - virtual ~VcInterfaceIF(){}; + virtual ~VirtualChannelIF(){}; virtual ReturnValue_t initialize() = 0; }; diff --git a/mission/tmtc/CMakeLists.txt b/mission/tmtc/CMakeLists.txt index 213f4ef0..ab5cf85d 100644 --- a/mission/tmtc/CMakeLists.txt +++ b/mission/tmtc/CMakeLists.txt @@ -1,12 +1,17 @@ target_sources( ${LIB_EIVE_MISSION} PRIVATE CcsdsIpCoreHandler.cpp + VirtualChannelWithQueue.cpp + PersistentTmStoreWithTmQueue.cpp + LiveTmTask.cpp VirtualChannel.cpp TmFunnelHandler.cpp TmFunnelBase.cpp CfdpTmFunnel.cpp tmFilters.cpp PusLiveDemux.cpp + PersistentSingleTmStoreTask.cpp + PersistentLogTmStoreTask.cpp PusPacketFilter.cpp PusTmRouteByFilterHelper.cpp Service15TmStorage.cpp diff --git a/mission/tmtc/CcsdsIpCoreHandler.cpp b/mission/tmtc/CcsdsIpCoreHandler.cpp index a0cb8d28..9a892977 100644 --- a/mission/tmtc/CcsdsIpCoreHandler.cpp +++ b/mission/tmtc/CcsdsIpCoreHandler.cpp @@ -13,10 +13,10 @@ #include "mission/devices/devicedefinitions/SyrlinksDefinitions.h" CcsdsIpCoreHandler::CcsdsIpCoreHandler(object_id_t objectId, object_id_t tcDestination, - PtmeIF& ptme, PtmeConfig& ptmeConfig, GpioIF* gpioIF, - gpioId_t enTxClock, gpioId_t enTxData) + PtmeConfig& ptmeConfig, std::atomic_bool& linkState, + GpioIF* gpioIF, gpioId_t enTxClock, gpioId_t enTxData) : SystemObject(objectId), - ptme(ptme), + linkState(linkState), tcDestination(tcDestination), parameterHelper(this), actionHelper(this, nullptr), @@ -31,22 +31,13 @@ CcsdsIpCoreHandler::CcsdsIpCoreHandler(object_id_t objectId, object_id_t tcDesti QueueFactory::instance()->createMessageQueue(10, EventMessage::EVENT_MESSAGE_SIZE, &mqArgs); } -CcsdsIpCoreHandler::~CcsdsIpCoreHandler() {} +CcsdsIpCoreHandler::~CcsdsIpCoreHandler() = default; ReturnValue_t CcsdsIpCoreHandler::performOperation(uint8_t operationCode) { readCommandQueue(); - // handleTelemetry(); return returnvalue::OK; } -// TODO: TM is sent to the respective VCs directly. -// void CcsdsIpCoreHandler::handleTelemetry() { -// VirtualChannelMapIter iter; -// for (iter = virtualChannelMap.begin(); iter != virtualChannelMap.end(); iter++) { -// iter->second->performOperation(); -// } -//} - ReturnValue_t CcsdsIpCoreHandler::initialize() { ReturnValue_t result = returnvalue::OK; AcceptsTelecommandsIF* tcDistributor = @@ -75,15 +66,6 @@ ReturnValue_t CcsdsIpCoreHandler::initialize() { return result; } - VirtualChannelMapIter iter; - for (iter = virtualChannelMap.begin(); iter != virtualChannelMap.end(); iter++) { - result = iter->second->initialize(); - if (result != returnvalue::OK) { - return result; - } - iter->second->setPtmeObject(&ptme); - } - result = ptmeConfig.initialize(); if (result != returnvalue::OK) { return ObjectManagerIF::CHILD_INIT_FAILED; @@ -92,7 +74,7 @@ ReturnValue_t CcsdsIpCoreHandler::initialize() { #if OBSW_SYRLINKS_SIMULATED == 1 // Update data on rising edge ptmeConfig->invertTxClock(false); - linkState = UP; + linkState = LINK_UP; forwardLinkstate(); #endif /* OBSW_SYRLINKS_SIMULATED == 1*/ @@ -126,41 +108,40 @@ void CcsdsIpCoreHandler::readCommandQueue(void) { MessageQueueId_t CcsdsIpCoreHandler::getCommandQueue() const { return commandQueue->getId(); } -void CcsdsIpCoreHandler::addVirtualChannel(VcId_t vcId, VirtualChannel* virtualChannel) { - if (vcId > config::NUMBER_OF_VIRTUAL_CHANNELS) { - sif::warning << "CcsdsHandler::addVirtualChannel: Invalid virtual channel ID" << std::endl; - return; - } - - if (virtualChannel == nullptr) { - sif::warning << "CcsdsHandler::addVirtualChannel: Invalid virtual channel interface" - << std::endl; - return; - } - - auto status = virtualChannelMap.emplace(vcId, virtualChannel); - if (status.second == false) { - sif::warning << "CcsdsHandler::addVirtualChannel: Failed to add virtual channel to " - "virtual channel map" - << std::endl; - return; - } -} +// void CcsdsIpCoreHandler::addVirtualChannel(VcId_t vcId, VirtualChannelWithQueue* virtualChannel) +// { +// if (vcId > config::NUMBER_OF_VIRTUAL_CHANNELS) { +// sif::warning << "CcsdsHandler::addVirtualChannel: Invalid virtual channel ID" << std::endl; +// return; +// } +// +// if (virtualChannel == nullptr) { +// sif::warning << "CcsdsHandler::addVirtualChannel: Invalid virtual channel interface" +// << std::endl; +// return; +// } +// +// auto status = virtualChannelMap.emplace(vcId, virtualChannel); +// if (status.second == false) { +// sif::warning << "CcsdsHandler::addVirtualChannel: Failed to add virtual channel to " +// "virtual channel map" +// << std::endl; +// return; +// } +// } // MessageQueueId_t CcsdsIpCoreHandler::getReportReceptionQueue(uint8_t virtualChannel) const { -// if (virtualChannel < config::NUMBER_OF_VIRTUAL_CHANNELS) { -// auto iter = virtualChannelMap.find(virtualChannel); -// if (iter != virtualChannelMap.end()) { -// return iter->second->getReportReceptionQueue(); -// } else { -// sif::warning << "CcsdsHandler::getReportReceptionQueue: Virtual channel with ID " -// << static_cast(virtualChannel) << " not in virtual channel map" -// << std::endl; -// return MessageQueueIF::NO_QUEUE; -// } -// } else { +// if (virtualChannel > config::NUMBER_OF_VIRTUAL_CHANNELS) { // sif::debug << "CcsdsHandler::getReportReceptionQueue: Invalid virtual channel requested"; +// return MessageQueueIF::NO_QUEUE; // } +// auto iter = virtualChannelMap.find(virtualChannel); +// if (iter != virtualChannelMap.end()) { +// return iter->second->getReportReceptionQueue(); +// } +// sif::warning << "CcsdsHandler::getReportReceptionQueue: Virtual channel with ID " +// << static_cast(virtualChannel) << " not in virtual channel map" +// << std::endl; // return MessageQueueIF::NO_QUEUE; // } @@ -237,20 +218,14 @@ ReturnValue_t CcsdsIpCoreHandler::executeAction(ActionId_t actionId, MessageQueu return EXECUTION_FINISHED; } -void CcsdsIpCoreHandler::forwardLinkstate() { - VirtualChannelMapIter iter; - for (iter = virtualChannelMap.begin(); iter != virtualChannelMap.end(); iter++) { - iter->second->setLinkState(linkState); - } -} +void CcsdsIpCoreHandler::updateLinkState() { linkState = LINK_UP; } void CcsdsIpCoreHandler::enableTransmit() { #ifndef TE0720_1CFA gpioIF->pullHigh(enTxClock); gpioIF->pullHigh(enTxData); #endif - linkState = UP; - forwardLinkstate(); + linkState = LINK_UP; } void CcsdsIpCoreHandler::getMode(Mode_t* mode, Submode_t* submode) { @@ -317,8 +292,7 @@ void CcsdsIpCoreHandler::disableTransmit() { gpioIF->pullLow(enTxClock); gpioIF->pullLow(enTxData); #endif - linkState = DOWN; - forwardLinkstate(); + linkState = LINK_DOWN; } const char* CcsdsIpCoreHandler::getName() const { return "CCSDS Handler"; } diff --git a/mission/tmtc/CcsdsIpCoreHandler.h b/mission/tmtc/CcsdsIpCoreHandler.h index f82e28fd..4a501ab5 100644 --- a/mission/tmtc/CcsdsIpCoreHandler.h +++ b/mission/tmtc/CcsdsIpCoreHandler.h @@ -2,12 +2,12 @@ #define CCSDSHANDLER_H_ #include +#include #include #include #include "OBSWConfig.h" -#include "VirtualChannel.h" #include "eive/definitions.h" #include "fsfw/action/ActionHelper.h" #include "fsfw/action/HasActionsIF.h" @@ -44,6 +44,8 @@ class CcsdsIpCoreHandler : public SystemObject, public ReceivesParameterMessagesIF, public HasActionsIF { public: + static const bool LINK_UP = true; + static const bool LINK_DOWN = false; using VcId_t = uint8_t; /** @@ -58,14 +60,22 @@ class CcsdsIpCoreHandler : public SystemObject, * @param enTxClock GPIO ID of RS485 tx clock enable * @param enTxData GPIO ID of RS485 tx data enable */ - CcsdsIpCoreHandler(object_id_t objectId, object_id_t tcDestination, PtmeIF& ptme, - PtmeConfig& ptmeConfig, GpioIF* gpioIF, gpioId_t enTxClock, gpioId_t enTxData); + CcsdsIpCoreHandler(object_id_t objectId, object_id_t tcDestination, PtmeConfig& ptmeConfig, + std::atomic_bool& linkState, GpioIF* gpioIF, gpioId_t enTxClock, + gpioId_t enTxData); ~CcsdsIpCoreHandler(); ReturnValue_t performOperation(uint8_t operationCode = 0) override; ReturnValue_t initialize(); MessageQueueId_t getCommandQueue() const override; + /** + * Currently directly forwards requests to the virtual channels which might live + * in different threads. + * @param virtualChannel + * @return + */ + // MessageQueueId_t getReportReceptionQueue(uint8_t virtualChannel) const override; // ModesIF void getMode(Mode_t* mode, Submode_t* submode) override; @@ -80,9 +90,8 @@ class CcsdsIpCoreHandler : public SystemObject, * @param virtualChannelId ID of the virtual channel to add * @param virtualChannel Pointer to virtual channel object */ - void addVirtualChannel(VcId_t virtualChannelId, VirtualChannel* virtualChannel); + // void addVirtualChannel(VcId_t virtualChannelId, VirtualChannelWithQueue* virtualChannel); - // MessageQueueId_t getReportReceptionQueue(uint8_t virtualChannel = 0) const override; ReturnValue_t getParameter(uint8_t domainId, uint8_t uniqueIdentifier, ParameterWrapper* parameterWrapper, const ParameterWrapper* newValues, uint16_t startAtIndex); @@ -126,14 +135,9 @@ class CcsdsIpCoreHandler : public SystemObject, //! [EXPORT] : [COMMENT] Received action message with unknown action id static const ReturnValue_t COMMAND_NOT_IMPLEMENTED = MAKE_RETURN_CODE(0xA0); - static const bool UP = true; - static const bool DOWN = false; - - using VirtualChannelMap = std::unordered_map; - using VirtualChannelMapIter = VirtualChannelMap::iterator; - - PtmeIF& ptme; - VirtualChannelMap virtualChannelMap; + // using VirtualChannelMap = std::unordered_map; + // VirtualChannelMap virtualChannelMap; + std::atomic_bool& linkState; object_id_t tcDestination; @@ -156,15 +160,13 @@ class CcsdsIpCoreHandler : public SystemObject, // GPIO to enable RS485 transceiver for TX data signal gpioId_t enTxData = gpio::NO_GPIO; - bool linkState = DOWN; - void readCommandQueue(void); void handleTelemetry(); /** * @brief Forward link state to virtual channels. */ - void forwardLinkstate(); + void updateLinkState(); /** * @brief Starts transmit timer and enables transmitter. diff --git a/mission/tmtc/LiveTmTask.cpp b/mission/tmtc/LiveTmTask.cpp new file mode 100644 index 00000000..723ed26d --- /dev/null +++ b/mission/tmtc/LiveTmTask.cpp @@ -0,0 +1,16 @@ +#include "LiveTmTask.h" + +#include + +LiveTmTask::LiveTmTask(object_id_t objectId, VirtualChannelWithQueue& channel) + : SystemObject(objectId), channel(channel) {} + +ReturnValue_t LiveTmTask::performOperation(uint8_t opCode) { + while (true) { + ReturnValue_t result = channel.sendNextTm(); + if (result == MessageQueueIF::EMPTY) { + // 5 ms IDLE delay. Might tweak this in the future. + TaskFactory::delayTask(5); + } + } +} diff --git a/mission/tmtc/LiveTmTask.h b/mission/tmtc/LiveTmTask.h new file mode 100644 index 00000000..598b1379 --- /dev/null +++ b/mission/tmtc/LiveTmTask.h @@ -0,0 +1,18 @@ +#ifndef MISSION_TMTC_LIVETMTASK_H_ +#define MISSION_TMTC_LIVETMTASK_H_ + +#include +#include +#include + +class LiveTmTask : public SystemObject, public ExecutableObjectIF { + public: + LiveTmTask(object_id_t objectId, VirtualChannelWithQueue& channel); + + ReturnValue_t performOperation(uint8_t opCode) override; + + private: + VirtualChannelWithQueue& channel; +}; + +#endif /* MISSION_TMTC_LIVETMTASK_H_ */ diff --git a/mission/tmtc/PersistentLogTmStoreTask.cpp b/mission/tmtc/PersistentLogTmStoreTask.cpp new file mode 100644 index 00000000..2102bcb7 --- /dev/null +++ b/mission/tmtc/PersistentLogTmStoreTask.cpp @@ -0,0 +1 @@ +#include "PersistentLogTmStoreTask.h" diff --git a/mission/tmtc/PersistentLogTmStoreTask.h b/mission/tmtc/PersistentLogTmStoreTask.h new file mode 100644 index 00000000..d119fd33 --- /dev/null +++ b/mission/tmtc/PersistentLogTmStoreTask.h @@ -0,0 +1,26 @@ +#ifndef MISSION_TMTC_PERSISTENTLOGTMSTORETASK_H_ +#define MISSION_TMTC_PERSISTENTLOGTMSTORETASK_H_ + +#include +#include +#include +#include +#include +#include +#include + +struct LogStores { + PersistentTmStoreWithTmQueue& okStore; + PersistentTmStoreWithTmQueue& notOkStore; + PersistentTmStoreWithTmQueue& miscStore; +}; + +class PersistentLogTmStoreTask : public SystemObject, public ExecutableObjectIF { + public: + PersistentLogTmStoreTask(object_id_t objectId, StorageManagerIF& ipcStore, LogStores tmStore, + VirtualChannelWithQueue& channel); + + private: +}; + +#endif /* MISSION_TMTC_PERSISTENTLOGTMSTORETASK_H_ */ diff --git a/mission/tmtc/PersistentSingleTmStoreTask.cpp b/mission/tmtc/PersistentSingleTmStoreTask.cpp new file mode 100644 index 00000000..3b7f919c --- /dev/null +++ b/mission/tmtc/PersistentSingleTmStoreTask.cpp @@ -0,0 +1,37 @@ +#include +#include + +PersistentSingleTmStoreTask::PersistentSingleTmStoreTask(object_id_t objectId, + StorageManagerIF& ipcStore, + PersistentTmStoreWithTmQueue& tmStore, + VirtualChannel& channel) + : SystemObject(objectId), ipcStore(ipcStore), storeWithQueue(tmStore), channel(channel) {} + +ReturnValue_t PersistentSingleTmStoreTask::performOperation(uint8_t opCode) { + ReturnValue_t result; + auto& store = storeWithQueue.getTmStore(); + bool noTmToStoreReceived = false; + bool noTcRequestReceived = false; + while (true) { + // Store TM persistently + result = storeWithQueue.handleNextTm(); + if (result == MessageQueueIF::NO_QUEUE) { + noTmToStoreReceived = true; + } + // Handle TC requests, for example deletion or retrieval requests. + result = store.handleCommandQueue(ipcStore); + if (result == MessageQueueIF::NO_QUEUE) { + noTcRequestReceived = true; + } + // Dump TMs when applicable + if (store.getState() == PersistentTmStore::State::DUMPING) { + size_t dumpedLen; + // TODO: Maybe do a bit of a delay every 100-200 packets? + // TODO: handle returnvalue? + store.dumpNextPacket(channel, dumpedLen); + } else if (noTcRequestReceived and noTmToStoreReceived) { + // Nothng to do, so sleep for a bit. + TaskFactory::delayTask(5); + } + } +} diff --git a/mission/tmtc/PersistentSingleTmStoreTask.h b/mission/tmtc/PersistentSingleTmStoreTask.h new file mode 100644 index 00000000..4ec9f03f --- /dev/null +++ b/mission/tmtc/PersistentSingleTmStoreTask.h @@ -0,0 +1,23 @@ +#ifndef MISSION_TMTC_PERSISTENTSINGLETMSTORETASK_H_ +#define MISSION_TMTC_PERSISTENTSINGLETMSTORETASK_H_ + +#include +#include +#include +#include + +class PersistentSingleTmStoreTask : public SystemObject, public ExecutableObjectIF { + public: + PersistentSingleTmStoreTask(object_id_t objectId, StorageManagerIF& ipcStore, + PersistentTmStoreWithTmQueue& storeWithQueue, + VirtualChannel& channel); + + ReturnValue_t performOperation(uint8_t opCode) override; + + private: + StorageManagerIF& ipcStore; + PersistentTmStoreWithTmQueue& storeWithQueue; + VirtualChannel& channel; +}; + +#endif /* MISSION_TMTC_PERSISTENTSINGLETMSTORETASK_H_ */ diff --git a/mission/tmtc/PersistentTmStore.cpp b/mission/tmtc/PersistentTmStore.cpp index 5784fdba..8bcf59bd 100644 --- a/mission/tmtc/PersistentTmStore.cpp +++ b/mission/tmtc/PersistentTmStore.cpp @@ -35,13 +35,9 @@ ReturnValue_t PersistentTmStore::assignAndOrCreateMostRecentFile() { return returnvalue::OK; } -ReturnValue_t PersistentTmStore::handleCommandQueue(StorageManagerIF& ipcStore, - TmFunnelBase& tmFunnel) { +ReturnValue_t PersistentTmStore::handleCommandQueue(StorageManagerIF& ipcStore) { CommandMessage cmdMessage; ReturnValue_t result = tcQueue->receiveMessage(&cmdMessage); - if (result == MessageQueueIF::EMPTY) { - return returnvalue::OK; - } if (result != returnvalue::OK) { return result; } @@ -70,7 +66,10 @@ ReturnValue_t PersistentTmStore::handleCommandQueue(StorageManagerIF& ipcStore, SerializeIF::Endianness::NETWORK); SerializeAdapter::deSerialize(&dumpUntilUnixSeconds, accessor.second.data() + 4, &size, SerializeIF::Endianness::NETWORK); - startDumpFromUpTo(dumpFromUnixSeconds, dumpUntilUnixSeconds); + result = startDumpFromUpTo(dumpFromUnixSeconds, dumpUntilUnixSeconds); + if (result != returnvalue::OK and result == BUSY_DUMPING) { + triggerEvent(BUSY_DUMPING_EVENT); + } } } return returnvalue::OK; @@ -344,3 +343,5 @@ ReturnValue_t PersistentTmStore::initializeTmStore() { updateBaseDir(); return assignAndOrCreateMostRecentFile(); } + +PersistentTmStore::State PersistentTmStore::getState() const { return state; } diff --git a/mission/tmtc/PersistentTmStore.h b/mission/tmtc/PersistentTmStore.h index 88c79443..795c1fcd 100644 --- a/mission/tmtc/PersistentTmStore.h +++ b/mission/tmtc/PersistentTmStore.h @@ -2,6 +2,7 @@ #define MISSION_TMTC_TMSTOREBACKEND_H_ #include +#include #include #include #include @@ -11,7 +12,6 @@ #include -#include "TmFunnelBase.h" #include "eive/eventSubsystemIds.h" #include "eive/resultClassIds.h" @@ -22,6 +22,7 @@ class PersistentTmStore : public TmStoreFrontendSimpleIF, public SystemObject { enum class State { IDLE, DUMPING }; static constexpr uint8_t INTERFACE_ID = CLASS_ID::PERSISTENT_TM_STORE; static constexpr ReturnValue_t DUMP_DONE = returnvalue::makeCode(INTERFACE_ID, 0); + static constexpr ReturnValue_t BUSY_DUMPING = returnvalue::makeCode(INTERFACE_ID, 1); static constexpr uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::PERSISTENT_TM_STORE; @@ -33,12 +34,15 @@ class PersistentTmStore : public TmStoreFrontendSimpleIF, public SystemObject { //! [EXPORT] : [COMMENT] File in store too large. P1: Detected file size //! P2: Allowed file size static constexpr Event FILE_TOO_LARGE = event::makeEvent(SUBSYSTEM_ID, 1, severity::LOW); + static constexpr Event BUSY_DUMPING_EVENT = event::makeEvent(SUBSYSTEM_ID, 2, severity::INFO); + PersistentTmStore(object_id_t objectId, const char* baseDir, std::string baseName, RolloverInterval intervalUnit, uint32_t intervalCount, StorageManagerIF& tmStore, SdCardMountedIF& sdcMan); ReturnValue_t initializeTmStore(); - ReturnValue_t handleCommandQueue(StorageManagerIF& ipcStore, TmFunnelBase& tmFunnel); + State getState() const; + ReturnValue_t handleCommandQueue(StorageManagerIF& ipcStore); void deleteUpTo(uint32_t unixSeconds); ReturnValue_t startDumpFrom(uint32_t fromUnixSeconds); diff --git a/mission/tmtc/PersistentTmStoreWithTmQueue.cpp b/mission/tmtc/PersistentTmStoreWithTmQueue.cpp new file mode 100644 index 00000000..b8d40adf --- /dev/null +++ b/mission/tmtc/PersistentTmStoreWithTmQueue.cpp @@ -0,0 +1,28 @@ +#include "PersistentTmStoreWithTmQueue.h" + +#include +#include + +PersistentTmStoreWithTmQueue::PersistentTmStoreWithTmQueue(StorageManagerIF& tmStore, + PersistentTmStore& persistentTmStore, + uint32_t tmQueueDepth) + : tmStore(tmStore), persistentTmStore(persistentTmStore) { + tmQueue = QueueFactory::instance()->createMessageQueue(tmQueueDepth); +} + +ReturnValue_t PersistentTmStoreWithTmQueue::handleNextTm() { + TmTcMessage msg; + ReturnValue_t result = tmQueue->receiveMessage(&msg); + if (result == MessageQueueIF::EMPTY) { + return result; + } + auto accessor = tmStore.getData(msg.getStorageId()); + if (accessor.first != returnvalue::OK) { + return result; + } + PusTmReader reader(accessor.second.data(), accessor.second.size()); + persistentTmStore.storePacket(reader); + return returnvalue::OK; +} + +PersistentTmStore& PersistentTmStoreWithTmQueue::getTmStore() { return persistentTmStore; } diff --git a/mission/tmtc/PersistentTmStoreWithTmQueue.h b/mission/tmtc/PersistentTmStoreWithTmQueue.h new file mode 100644 index 00000000..05cc4d2d --- /dev/null +++ b/mission/tmtc/PersistentTmStoreWithTmQueue.h @@ -0,0 +1,19 @@ +#ifndef MISSION_TMTC_PERSISTENTTMSTOREWITHTMQUEUE_H_ +#define MISSION_TMTC_PERSISTENTTMSTOREWITHTMQUEUE_H_ +#include + +class PersistentTmStoreWithTmQueue : public AcceptsTelemetryIF { + public: + PersistentTmStoreWithTmQueue(StorageManagerIF& tmStore, PersistentTmStore& persistentTmStore, + uint32_t tmQueueDepth); + + ReturnValue_t handleNextTm(); + PersistentTmStore& getTmStore(); + + private: + StorageManagerIF& tmStore; + MessageQueueIF* tmQueue; + PersistentTmStore& persistentTmStore; +}; + +#endif /* MISSION_TMTC_PERSISTENTTMSTOREWITHTMQUEUE_H_ */ diff --git a/mission/tmtc/VirtualChannel.cpp b/mission/tmtc/VirtualChannel.cpp index a6e7732c..fba64049 100644 --- a/mission/tmtc/VirtualChannel.cpp +++ b/mission/tmtc/VirtualChannel.cpp @@ -1,77 +1,26 @@ #include "VirtualChannel.h" -#include "CcsdsIpCoreHandler.h" -#include "OBSWConfig.h" -#include "fsfw/ipc/QueueFactory.h" -#include "fsfw/objectmanager/ObjectManager.h" -#include "fsfw/serviceinterface/ServiceInterfaceStream.h" -#include "fsfw/tmtcservices/TmTcMessage.h" +VirtualChannel::VirtualChannel(object_id_t objectId, uint8_t vcId, const char* vcName, PtmeIF& ptme, + const std::atomic_bool& linkStateProvider) + : SystemObject(objectId), + vcId(vcId), + vcName(vcName), + ptme(ptme), + linkStateProvider(linkStateProvider) {} -VirtualChannel::VirtualChannel(object_id_t objectId, uint8_t vcId, const char* vcName, - uint32_t tmQueueDepth) - : SystemObject(objectId), vcId(vcId), vcName(vcName) { - auto mqArgs = MqArgs(objectId, reinterpret_cast(vcId)); - tmQueue = QueueFactory::instance()->createMessageQueue( - tmQueueDepth, MessageQueueMessage::MAX_MESSAGE_SIZE, &mqArgs); +ReturnValue_t VirtualChannel::initialize() { return returnvalue::OK; } + +ReturnValue_t VirtualChannel::sendNextTm(const uint8_t* data, size_t size) { + return write(data, size); } -ReturnValue_t VirtualChannel::initialize() { - tmStore = ObjectManager::instance()->get(objects::TM_STORE); - if (tmStore == nullptr) { - sif::error << "VirtualChannel::initialize: Failed to get tm store" << std::endl; - return returnvalue::FAILED; +ReturnValue_t VirtualChannel::write(const uint8_t* data, size_t size) { + if (linkStateProvider.load()) { + return ptme.writeToVc(vcId, data, size); } return returnvalue::OK; } -ReturnValue_t VirtualChannel::performOperation(uint8_t opCode) { - ReturnValue_t result = returnvalue::OK; - TmTcMessage message; - // To be able to push high datarates, we use a custom permanent loop. - while (true) { - unsigned int count = 0; - while (tmQueue->receiveMessage(&message) == returnvalue::OK) { - store_address_t storeId = message.getStorageId(); - const uint8_t* data = nullptr; - size_t size = 0; - result = tmStore->getData(storeId, &data, &size); - if (result != returnvalue::OK) { - sif::warning << "VirtualChannel::performOperation: Failed to read data from TM store" - << std::endl; - tmStore->deleteData(storeId); - return result; - } - - if (linkIsUp) { - result = ptme->writeToVc(vcId, data, size); - } - tmStore->deleteData(storeId); - if (result != returnvalue::OK) { - return result; - } - - count++; - if (count == 500) { - sif::error << "VirtualChannel: Possible message storm detected" << std::endl; - break; - } - } - } - return returnvalue::FAILED; -} - -MessageQueueId_t VirtualChannel::getReportReceptionQueue(uint8_t virtualChannel) const { - return tmQueue->getId(); -} - -void VirtualChannel::setPtmeObject(PtmeIF* ptme_) { - if (ptme_ == nullptr) { - sif::warning << "VirtualChannel::setPtmeObject: Invalid ptme object" << std::endl; - return; - } - ptme = ptme_; -} - -void VirtualChannel::setLinkState(bool linkIsUp_) { linkIsUp = linkIsUp_; } +uint8_t VirtualChannel::getVcid() const { return vcId; } const char* VirtualChannel::getName() const { return vcName.c_str(); } diff --git a/mission/tmtc/VirtualChannel.h b/mission/tmtc/VirtualChannel.h index 98caa004..b46c099e 100644 --- a/mission/tmtc/VirtualChannel.h +++ b/mission/tmtc/VirtualChannel.h @@ -1,16 +1,11 @@ -#ifndef VIRTUALCHANNEL_H_ -#define VIRTUALCHANNEL_H_ +#pragma once -#include #include -#include #include +#include -#include "OBSWConfig.h" -#include "fsfw/returnvalues/returnvalue.h" -#include "fsfw/tmtcservices/AcceptsTelemetryIF.h" - -class StorageManagerIF; +#include +#include /** * @brief This class represents a virtual channel. Sending a tm message to an object of this class @@ -18,7 +13,7 @@ class StorageManagerIF; * * @author J. Meier */ -class VirtualChannel : public SystemObject, public ExecutableObjectIF, public AcceptsTelemetryIF { +class VirtualChannel : public SystemObject, public VirtualChannelIF { public: /** * @brief Constructor @@ -26,35 +21,19 @@ class VirtualChannel : public SystemObject, public ExecutableObjectIF, public Ac * @param vcId The virtual channel id assigned to this object * @param tmQueueDepth Queue depth of queue receiving telemetry from other objects */ - VirtualChannel(object_id_t objectId, uint8_t vcId, const char* vcName, uint32_t tmQueueDepth); + VirtualChannel(object_id_t objectId, uint8_t vcId, const char* vcName, PtmeIF& ptme, + const std::atomic_bool& linkStateProvider); ReturnValue_t initialize() override; - MessageQueueId_t getReportReceptionQueue(uint8_t virtualChannel = 0) const override; - ReturnValue_t performOperation(uint8_t opCode) override; + ReturnValue_t sendNextTm(const uint8_t* data, size_t size); + ReturnValue_t write(const uint8_t* data, size_t size) override; + uint8_t getVcid() const; - /** - * @brief Sets the PTME object which handles access to the PTME IP Core. - * - * @param ptme Pointer to ptme object - */ - void setPtmeObject(PtmeIF* ptme_); - - /** - * @brief Can be used by the owner to set the link state. Packets will be discarded if link - * to ground station is down. - */ - void setLinkState(bool linkIsUp_); - const char* getName() const override; + const char* getName() const; private: - PtmeIF* ptme = nullptr; - MessageQueueIF* tmQueue = nullptr; + PtmeIF& ptme; uint8_t vcId = 0; std::string vcName; - - bool linkIsUp = false; - - StorageManagerIF* tmStore = nullptr; + const std::atomic_bool& linkStateProvider; }; - -#endif /* VIRTUALCHANNEL_H_ */ diff --git a/mission/tmtc/VirtualChannelWithQueue.cpp b/mission/tmtc/VirtualChannelWithQueue.cpp new file mode 100644 index 00000000..62557973 --- /dev/null +++ b/mission/tmtc/VirtualChannelWithQueue.cpp @@ -0,0 +1,48 @@ +#include + +#include "CcsdsIpCoreHandler.h" +#include "OBSWConfig.h" +#include "fsfw/ipc/QueueFactory.h" +#include "fsfw/objectmanager/ObjectManager.h" +#include "fsfw/serviceinterface/ServiceInterfaceStream.h" +#include "fsfw/tmtcservices/TmTcMessage.h" + +VirtualChannelWithQueue::VirtualChannelWithQueue(VirtualChannel& channel, StorageManagerIF& tmStore, + uint32_t tmQueueDepth, + const std::atomic_bool& linkStateProvider) + : channel(channel) { + auto mqArgs = MqArgs(channel.getObjectId(), reinterpret_cast(channel.getVcid())); + tmQueue = QueueFactory::instance()->createMessageQueue( + tmQueueDepth, MessageQueueMessage::MAX_MESSAGE_SIZE, &mqArgs); +} + +ReturnValue_t VirtualChannelWithQueue::sendNextTm() { + TmTcMessage message; + ReturnValue_t result = tmQueue->receiveMessage(&message); + if (result == MessageQueueIF::EMPTY) { + return result; + } + store_address_t storeId = message.getStorageId(); + const uint8_t* data = nullptr; + size_t size = 0; + result = tmStore->getData(storeId, &data, &size); + if (result != returnvalue::OK) { + sif::warning << "VirtualChannel::performOperation: Failed to read data from TM store" + << std::endl; + tmStore->deleteData(storeId); + return result; + } + + channel.write(data, size); + tmStore->deleteData(storeId); + if (result != returnvalue::OK) { + return result; + } + return returnvalue::OK; +} + +MessageQueueId_t VirtualChannelWithQueue::getReportReceptionQueue(uint8_t virtualChannel) const { + return tmQueue->getId(); +} + +VirtualChannel& VirtualChannelWithQueue::vc() { return channel; } diff --git a/mission/tmtc/VirtualChannelWithQueue.h b/mission/tmtc/VirtualChannelWithQueue.h new file mode 100644 index 00000000..f7a2bef9 --- /dev/null +++ b/mission/tmtc/VirtualChannelWithQueue.h @@ -0,0 +1,45 @@ +#pragma once + +#include +#include +#include +#include +#include + +#include + +#include "OBSWConfig.h" +#include "fsfw/returnvalues/returnvalue.h" +#include "fsfw/tmtcservices/AcceptsTelemetryIF.h" + +class StorageManagerIF; + +/** + * @brief This class represents a virtual channel. Sending a tm message to an object of this class + * will forward the tm packet to the respective virtual channel of the PTME IP Core. + * + * @author J. Meier + */ +class VirtualChannelWithQueue : public AcceptsTelemetryIF { + public: + /** + * @brief Constructor + * + * @param vcId The virtual channel id assigned to this object + * @param tmQueueDepth Queue depth of queue receiving telemetry from other objects + */ + VirtualChannelWithQueue(VirtualChannel& channel, StorageManagerIF& tmStore, uint32_t tmQueueDepth, + const std::atomic_bool& linkStateProvider); + + MessageQueueId_t getReportReceptionQueue(uint8_t virtualChannel = 0) const override; + ReturnValue_t sendNextTm(); + + VirtualChannel& vc(); + + const char* getName() const override; + + private: + VirtualChannel& channel; + MessageQueueIF* tmQueue = nullptr; + StorageManagerIF* tmStore = nullptr; +}; From b2fd2f5d83fcccb1c8e22c372c03b37f96da056c Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 9 Mar 2023 19:42:20 +0100 Subject: [PATCH 038/112] now only scheduling is left --- CHANGELOG.md | 8 ++ bsp_q7s/core/ObjectFactory.cpp | 73 ++++++++-------- bsp_q7s/core/ObjectFactory.h | 23 ++++- bsp_q7s/fmObjectFactory.cpp | 8 +- common/config/eive/objects.h | 5 ++ mission/core/GenericFactory.cpp | 87 +++++++++++++++---- mission/core/GenericFactory.h | 13 ++- mission/tmtc/CMakeLists.txt | 1 + mission/tmtc/PersistentLogTmStoreTask.cpp | 27 ++++++ mission/tmtc/PersistentLogTmStoreTask.h | 11 ++- mission/tmtc/PersistentSingleTmStoreTask.cpp | 26 +----- mission/tmtc/PersistentSingleTmStoreTask.h | 5 +- mission/tmtc/PersistentTmStore.cpp | 17 ++-- mission/tmtc/PersistentTmStore.h | 29 ++++++- mission/tmtc/PersistentTmStoreWithTmQueue.cpp | 15 ++-- mission/tmtc/PersistentTmStoreWithTmQueue.h | 11 +-- mission/tmtc/TmStoreTaskBase.cpp | 35 ++++++++ mission/tmtc/TmStoreTaskBase.h | 22 +++++ mission/tmtc/VirtualChannel.cpp | 2 +- mission/tmtc/VirtualChannelWithQueue.cpp | 17 ++-- mission/tmtc/VirtualChannelWithQueue.h | 13 ++- mission/tmtc/tmFilters.cpp | 6 ++ mission/tmtc/tmFilters.h | 1 + 23 files changed, 330 insertions(+), 125 deletions(-) create mode 100644 mission/tmtc/TmStoreTaskBase.cpp create mode 100644 mission/tmtc/TmStoreTaskBase.h diff --git a/CHANGELOG.md b/CHANGELOG.md index 8ab39c23..7c22cb43 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -16,6 +16,14 @@ will consitute of a breaking change warranting a new major release: # [unreleased] +## Changed + +- Refactored TM pipeline to optimize usage of the PTME and communication downlink bandwidth. + This was done by moving the dumping of TMs to the VCs into separate threads with permanent loops. + These threads are then able to process high TM loads on demand. The PUS TM funnel will route + PUS packets to the approrpiate persisten TM stores and then demultiplex the TM to all registered + TM destinations are before. + # [v1.36.0] 2023-03-08 eive-tmtc: v2.17.2 diff --git a/bsp_q7s/core/ObjectFactory.cpp b/bsp_q7s/core/ObjectFactory.cpp index 62aecde4..a3045e62 100644 --- a/bsp_q7s/core/ObjectFactory.cpp +++ b/bsp_q7s/core/ObjectFactory.cpp @@ -12,6 +12,9 @@ #include #include #include +#include +#include +#include #include "OBSWConfig.h" #include "bsp_q7s/boardtest/Q7STestTask.h" @@ -716,9 +719,7 @@ void ObjectFactory::createReactionWheelComponents(LinuxLibgpioIF* gpioComIF, #endif /* OBSW_ADD_RW == 1 */ } -ReturnValue_t ObjectFactory::createCcsdsComponents(LinuxLibgpioIF* gpioComIF, - PusTmFunnel& pusFunnel, - CcsdsIpCoreHandler** ipCoreHandler) { +ReturnValue_t ObjectFactory::createCcsdsComponents(CcsdsComponentArgs& args) { using namespace gpio; // GPIO definitions of signals connected to the virtual channel interfaces of the PTME IP Core GpioCookie* gpioCookiePtmeIp = new GpioCookie; @@ -739,20 +740,20 @@ ReturnValue_t ObjectFactory::createCcsdsComponents(LinuxLibgpioIF* gpioComIF, gpioCookiePtmeIp->addGpio(gpioIds::VC3_PAPB_BUSY, gpio); gpio = new GpiodRegularByLineName(q7s::gpioNames::PAPB_EMPTY_SIGNAL_VC3, "PAPB VC3"); gpioCookiePtmeIp->addGpio(gpioIds::VC3_PAPB_EMPTY, gpio); - gpioChecker(gpioComIF->addGpios(gpioCookiePtmeIp), "PTME PAPB VCs"); + gpioChecker(args.gpioComIF.addGpios(gpioCookiePtmeIp), "PTME PAPB VCs"); // Creating virtual channel interfaces VirtualChannelIF* vc0 = - new PapbVcInterface(gpioComIF, gpioIds::VC0_PAPB_BUSY, gpioIds::VC0_PAPB_EMPTY, q7s::UIO_PTME, - q7s::uiomapids::PTME_VC0); + new PapbVcInterface(&args.gpioComIF, gpioIds::VC0_PAPB_BUSY, gpioIds::VC0_PAPB_EMPTY, + q7s::UIO_PTME, q7s::uiomapids::PTME_VC0); VirtualChannelIF* vc1 = - new PapbVcInterface(gpioComIF, gpioIds::VC1_PAPB_BUSY, gpioIds::VC1_PAPB_EMPTY, q7s::UIO_PTME, - q7s::uiomapids::PTME_VC1); + new PapbVcInterface(&args.gpioComIF, gpioIds::VC1_PAPB_BUSY, gpioIds::VC1_PAPB_EMPTY, + q7s::UIO_PTME, q7s::uiomapids::PTME_VC1); VirtualChannelIF* vc2 = - new PapbVcInterface(gpioComIF, gpioIds::VC2_PAPB_BUSY, gpioIds::VC2_PAPB_EMPTY, q7s::UIO_PTME, - q7s::uiomapids::PTME_VC2); + new PapbVcInterface(&args.gpioComIF, gpioIds::VC2_PAPB_BUSY, gpioIds::VC2_PAPB_EMPTY, + q7s::UIO_PTME, q7s::uiomapids::PTME_VC2); VirtualChannelIF* vc3 = - new PapbVcInterface(gpioComIF, gpioIds::VC3_PAPB_BUSY, gpioIds::VC3_PAPB_EMPTY, q7s::UIO_PTME, - q7s::uiomapids::PTME_VC3); + new PapbVcInterface(&args.gpioComIF, gpioIds::VC3_PAPB_BUSY, gpioIds::VC3_PAPB_EMPTY, + q7s::UIO_PTME, q7s::uiomapids::PTME_VC3); // Creating ptme object and adding virtual channel interfaces Ptme* ptme = new Ptme(objects::PTME); ptme->addVcInterface(ccsds::VC0, vc0); @@ -763,29 +764,33 @@ ReturnValue_t ObjectFactory::createCcsdsComponents(LinuxLibgpioIF* gpioComIF, new AxiPtmeConfig(objects::AXI_PTME_CONFIG, q7s::UIO_PTME, q7s::uiomapids::PTME_CONFIG); PtmeConfig* ptmeConfig = new PtmeConfig(objects::PTME_CONFIG, axiPtmeConfig); - *ipCoreHandler = new CcsdsIpCoreHandler(objects::CCSDS_HANDLER, objects::CCSDS_PACKET_DISTRIBUTOR, - *ptmeConfig, LINK_STATE, gpioComIF, - gpioIds::RS485_EN_TX_CLOCK, gpioIds::RS485_EN_TX_DATA); - VirtualChannel* vc = new VirtualChannel(objects::PTME_VC0_LIVE_TM, ccsds::VC0, "PTME VC0 LIVE TM", - *ptme, LINK_STATE); - //(*ipCoreHandler)->addVirtualChannel(ccsds::VC0, vc); - vc = new VirtualChannel(objects::PTME_VC1_LOG_TM, ccsds::VC1, "PTME VC1 LOG TM", *ptme, - LINK_STATE); + *args.ipCoreHandler = new CcsdsIpCoreHandler( + objects::CCSDS_HANDLER, objects::CCSDS_PACKET_DISTRIBUTOR, *ptmeConfig, LINK_STATE, + &args.gpioComIF, gpioIds::RS485_EN_TX_CLOCK, gpioIds::RS485_EN_TX_DATA); + // This VC will receive all live TM + auto* vcWithQueue = + new VirtualChannelWithQueue(objects::PTME_VC0_LIVE_TM, ccsds::VC0, "PTME VC0 LIVE TM", *ptme, + LINK_STATE, args.tmStore, 500); + new LiveTmTask(objects::LIVE_TM_TASK, *vcWithQueue); + + // Set up log store. + auto* vc = new VirtualChannel(objects::PTME_VC1_LOG_TM, ccsds::VC1, "PTME VC1 LOG TM", *ptme, + LINK_STATE); + LogStores logStores(args.stores); + // Core task which handles the LOG store and takes care of dumping it as TM using a VC directly + new PersistentLogTmStoreTask(objects::LOG_STORE_TASK, args.ipcStore, logStores, *vc); - // pusFunnel.addPersistentTmStoreRouting(filters::okFilter(), vc->getReportReceptionQueue()); - // pusFunnel.addPersistentTmStoreRouting(filters::notOkFilter(), vc->getReportReceptionQueue()); - // pusFunnel.addPersistentTmStoreRouting(filters::miscFilter(), vc->getReportReceptionQueue()); - //(*ipCoreHandler)->addVirtualChannel(ccsds::VC1, vc); vc = new VirtualChannel(objects::PTME_VC2_HK_TM, ccsds::VC2, "PTME VC2 HK TM", *ptme, LINK_STATE); - // auto hkTmStoreTask = new PersistentSingleTmStoreTask(); - // pusFunnel.addPersistentTmStoreRouting(filters::hkFilter(), vc->getReportReceptionQueue()); - //(*ipCoreHandler)->addVirtualChannel(ccsds::VC2, vc); + // Core task which handles the HK store and takes care of dumping it as TM using a VC directly + new PersistentSingleTmStoreTask(objects::HK_STORE_TASK, args.ipcStore, *args.stores.hkStore, *vc); + vc = new VirtualChannel(objects::PTME_VC3_CFDP_TM, ccsds::VC3, "PTME VC3 CFDP TM", *ptme, LINK_STATE); - // TODO: Set VC destination in CFDP funnel. - //(*ipCoreHandler)->addVirtualChannel(ccsds::VC3, vc); + // Core task which handles the CFDP store and takes care of dumping it as TM using a VC directly + new PersistentSingleTmStoreTask(objects::CFDP_STORE_TASK, args.ipcStore, *args.stores.cfdpStore, + *vc); - ReturnValue_t result = (*ipCoreHandler)->connectModeTreeParent(satsystem::com::SUBSYSTEM); + ReturnValue_t result = (*args.ipCoreHandler)->connectModeTreeParent(satsystem::com::SUBSYSTEM); if (result != returnvalue::OK) { sif::error << "ObjectFactory::createCcsdsComponents: Connecting COM subsystem to CCSDS handler failed" @@ -797,14 +802,14 @@ ReturnValue_t ObjectFactory::createCcsdsComponents(LinuxLibgpioIF* gpioComIF, gpio = new GpiodRegularByLineName(q7s::gpioNames::PDEC_RESET, "PDEC Handler", Direction::OUT, Levels::LOW); gpioCookiePdec->addGpio(gpioIds::PDEC_RESET, gpio); - gpioChecker(gpioComIF->addGpios(gpioCookiePdec), "PDEC"); + gpioChecker(args.gpioComIF.addGpios(gpioCookiePdec), "PDEC"); struct UioNames uioNames {}; uioNames.configMemory = q7s::UIO_PDEC_CONFIG_MEMORY; uioNames.ramMemory = q7s::UIO_PDEC_RAM; uioNames.registers = q7s::UIO_PDEC_REGISTERS; uioNames.irq = q7s::UIO_PDEC_IRQ; - new PdecHandler(objects::PDEC_HANDLER, objects::CCSDS_HANDLER, gpioComIF, gpioIds::PDEC_RESET, - uioNames); + new PdecHandler(objects::PDEC_HANDLER, objects::CCSDS_HANDLER, &args.gpioComIF, + gpioIds::PDEC_RESET, uioNames); GpioCookie* gpioRS485Chip = new GpioCookie; gpio = new GpiodRegularByLineName(q7s::gpioNames::RS485_EN_TX_CLOCK, "RS485 Transceiver", Direction::OUT, Levels::LOW); @@ -819,7 +824,7 @@ ReturnValue_t ObjectFactory::createCcsdsComponents(LinuxLibgpioIF* gpioComIF, gpio = new GpiodRegularByLineName(q7s::gpioNames::RS485_EN_RX_DATA, "RS485 Transceiver", Direction::OUT, Levels::LOW); gpioRS485Chip->addGpio(gpioIds::RS485_EN_RX_DATA, gpio); - gpioChecker(gpioComIF->addGpios(gpioRS485Chip), "RS485 Transceiver"); + gpioChecker(args.gpioComIF.addGpios(gpioRS485Chip), "RS485 Transceiver"); return returnvalue::OK; } diff --git a/bsp_q7s/core/ObjectFactory.h b/bsp_q7s/core/ObjectFactory.h index d71ed359..c13f9c68 100644 --- a/bsp_q7s/core/ObjectFactory.h +++ b/bsp_q7s/core/ObjectFactory.h @@ -3,10 +3,12 @@ #include #include +#include #include #include #include #include +#include #include #include @@ -22,6 +24,24 @@ class GpioIF; namespace ObjectFactory { +struct CcsdsComponentArgs { + CcsdsComponentArgs(LinuxLibgpioIF& gpioIF, PusTmFunnel& funnel, StorageManagerIF& ipcStore, + StorageManagerIF& tmStore, PersistentTmStores& stores, + CcsdsIpCoreHandler** ipCoreHandler) + : gpioComIF(gpioIF), + pusFunnel(funnel), + ipcStore(ipcStore), + tmStore(tmStore), + stores(stores), + ipCoreHandler(ipCoreHandler) {} + LinuxLibgpioIF& gpioComIF; + PusTmFunnel& pusFunnel; + StorageManagerIF& ipcStore; + StorageManagerIF& tmStore; + PersistentTmStores& stores; + CcsdsIpCoreHandler** ipCoreHandler; +}; + void setStatics(); void produce(void* args); @@ -43,8 +63,7 @@ void createSolarArrayDeploymentComponents(PowerSwitchIF& pwrSwitcher, GpioIF& gp void createSyrlinksComponents(PowerSwitchIF* pwrSwitcher); void createPayloadComponents(LinuxLibgpioIF* gpioComIF, PowerSwitchIF& pwrSwitcher); void createReactionWheelComponents(LinuxLibgpioIF* gpioComIF, PowerSwitchIF* pwrSwitcher); -ReturnValue_t createCcsdsComponents(LinuxLibgpioIF* gpioComIF, PusTmFunnel& pusFunnel, - CcsdsIpCoreHandler** ipCoreHandler); +ReturnValue_t createCcsdsComponents(CcsdsComponentArgs& args); void createMiscComponents(); void createTestComponents(LinuxLibgpioIF* gpioComIF); diff --git a/bsp_q7s/fmObjectFactory.cpp b/bsp_q7s/fmObjectFactory.cpp index c8760478..0fecf58b 100644 --- a/bsp_q7s/fmObjectFactory.cpp +++ b/bsp_q7s/fmObjectFactory.cpp @@ -19,9 +19,12 @@ void ObjectFactory::produce(void* args) { HealthTableIF* healthTable = nullptr; PusTmFunnel* pusFunnel = nullptr; CfdpTmFunnel* cfdpFunnel = nullptr; + StorageManagerIF* ipcStore = nullptr; + StorageManagerIF* tmStore = nullptr; + PersistentTmStores stores; ObjectFactory::produceGenericObjects(&healthTable, &pusFunnel, &cfdpFunnel, - *SdCardManager::instance()); + *SdCardManager::instance(), &ipcStore, &tmStore, stores); LinuxLibgpioIF* gpioComIF = nullptr; SerialComIF* uartComIF = nullptr; @@ -74,7 +77,8 @@ void ObjectFactory::produce(void* args) { #endif /* OBSW_ADD_STAR_TRACKER == 1 */ #if OBSW_ADD_CCSDS_IP_CORES == 1 CcsdsIpCoreHandler* ipCoreHandler = nullptr; - createCcsdsComponents(gpioComIF, *pusFunnel, &ipCoreHandler); + CcsdsComponentArgs ccsdsArgs(*gpioComIF, *pusFunnel, *ipcStore, *tmStore, stores, &ipCoreHandler); + createCcsdsComponents(ccsdsArgs); #if OBSW_TM_TO_PTME == 1 // TODO: Remove this if not needed anymore // addTmtcIpCoresToFunnels(*ipCoreHandler, *pusFunnel, *cfdpFunnel); diff --git a/common/config/eive/objects.h b/common/config/eive/objects.h index bbab8a0a..d5a59791 100644 --- a/common/config/eive/objects.h +++ b/common/config/eive/objects.h @@ -168,6 +168,11 @@ enum commonObjects : uint32_t { HK_TM_STORE = 0x73020004, CFDP_TM_STORE = 0x73030000, + LIVE_TM_TASK = 0x73040000, + LOG_STORE_TASK = 0x73040001, + HK_STORE_TASK = 0x73040002, + CFDP_STORE_TASK = 0x73040003, + // Other stuff THERMAL_TEMP_INSERTER = 0x90000003, }; diff --git a/mission/core/GenericFactory.cpp b/mission/core/GenericFactory.cpp index e2e5c0c7..c7048cbc 100644 --- a/mission/core/GenericFactory.cpp +++ b/mission/core/GenericFactory.cpp @@ -34,6 +34,7 @@ #include #include #include +#include #include #include #include @@ -47,6 +48,7 @@ #include "mission/system/objects/RwAssembly.h" #include "mission/system/tree/acsModeTree.h" #include "mission/system/tree/tcsModeTree.h" +#include "mission/tmtc/tmFilters.h" #include "objects/systemObjectList.h" #include "tmtc/pusIds.h" @@ -87,7 +89,9 @@ EiveFaultHandler EIVE_FAULT_HANDLER; } // namespace cfdp void ObjectFactory::produceGenericObjects(HealthTableIF** healthTable_, PusTmFunnel** pusFunnel, - CfdpTmFunnel** cfdpFunnel, SdCardMountedIF& sdcMan) { + CfdpTmFunnel** cfdpFunnel, SdCardMountedIF& sdcMan, + StorageManagerIF** ipcStore, StorageManagerIF** tmStore, + PersistentTmStores& stores) { // Framework objects new EventManager(objects::EVENT_MANAGER); auto healthTable = new HealthTable(objects::HEALTH_TABLE); @@ -98,8 +102,6 @@ void ObjectFactory::produceGenericObjects(HealthTableIF** healthTable_, PusTmFun new VerificationReporter(); auto* timeStamper = new CdsShortTimeStamper(objects::TIME_STAMPER); StorageManagerIF* tcStore; - StorageManagerIF* tmStore; - StorageManagerIF* ipcStore; { PoolManager::LocalPoolConfig poolCfg = {{250, 16}, {250, 32}, {250, 64}, {150, 128}, {120, 1024}, {120, 2048}}; @@ -109,13 +111,13 @@ void ObjectFactory::produceGenericObjects(HealthTableIF** healthTable_, PusTmFun { PoolManager::LocalPoolConfig poolCfg = {{400, 32}, {400, 64}, {250, 128}, {150, 512}, {150, 1024}, {150, 2048}}; - tmStore = new PoolManager(objects::TM_STORE, poolCfg); + *tmStore = new PoolManager(objects::TM_STORE, poolCfg); } { PoolManager::LocalPoolConfig poolCfg = {{300, 16}, {200, 32}, {150, 64}, {150, 128}, {100, 256}, {50, 512}, {50, 1024}, {10, 2048}}; - ipcStore = new PoolManager(objects::IPC_STORE, poolCfg); + *ipcStore = new PoolManager(objects::IPC_STORE, poolCfg); } #if OBSW_ADD_TCPIP_SERVERS == 1 @@ -144,20 +146,71 @@ void ObjectFactory::produceGenericObjects(HealthTableIF** healthTable_, PusTmFun new CcsdsDistributor(config::EIVE_PUS_APID, objects::CCSDS_PACKET_DISTRIBUTOR); new PusDistributor(config::EIVE_PUS_APID, objects::PUS_PACKET_DISTRIBUTOR, ccsdsDistrib); - PusTmFunnel::FunnelCfg cfdpFunnelCfg(objects::CFDP_TM_FUNNEL, "CfdpTmFunnel", *tmStore, *ipcStore, - 50); + PusTmFunnel::FunnelCfg cfdpFunnelCfg(objects::CFDP_TM_FUNNEL, "CfdpTmFunnel", **tmStore, + **ipcStore, 50); *cfdpFunnel = new CfdpTmFunnel(cfdpFunnelCfg, config::EIVE_CFDP_APID); - auto* miscStore = new PersistentTmStore(objects::MISC_TM_STORE, "tm", "misc", - RolloverInterval::HOURLY, 2, *tmStore, sdcMan); - auto* okStore = new PersistentTmStore(objects::OK_TM_STORE, "tm", "ok", - RolloverInterval::MINUTELY, 30, *tmStore, sdcMan); - auto* notOkStore = new PersistentTmStore(objects::NOT_OK_TM_STORE, "tm", "nok", - RolloverInterval::MINUTELY, 30, *tmStore, sdcMan); - auto* hkStore = new PersistentTmStore(objects::HK_TM_STORE, "tm", "hk", - RolloverInterval::MINUTELY, 15, *tmStore, sdcMan); - PusTmFunnel::FunnelCfg pusFunnelCfg(objects::PUS_TM_FUNNEL, "PusTmFunnel", *tmStore, *ipcStore, + PusTmFunnel::FunnelCfg pusFunnelCfg(objects::PUS_TM_FUNNEL, "PusTmFunnel", **tmStore, **ipcStore, config::MAX_PUS_FUNNEL_QUEUE_DEPTH); + // The PUS funnel routes all live TM to the live destinations and to the TM stores. *pusFunnel = new PusTmFunnel(pusFunnelCfg, *timeStamper, sdcMan); + + // MISC store and PUS funnel to MISC store routing + // TODO: Make queue depth configurable + { + PersistentTmStoreArgs storeArgs(objects::MISC_TM_STORE, "tm", "misc", + + RolloverInterval::HOURLY, 2, **tmStore, sdcMan); + stores.miscStore = new PersistentTmStoreWithTmQueue(storeArgs, "MISC STORE", 500); + (*pusFunnel) + ->addPersistentTmStoreRouting(filters::miscFilter(), + stores.miscStore->getReportReceptionQueue(0)); + } + + // OK store and PUS Funnel to OK store routing + // TODO: Make queue depth configurable + { + PersistentTmStoreArgs storeArgs(objects::OK_TM_STORE, "tm", "ok", RolloverInterval::MINUTELY, + 30, **tmStore, sdcMan); + stores.okStore = new PersistentTmStoreWithTmQueue(storeArgs, "OK STORE", 500); + (*pusFunnel) + ->addPersistentTmStoreRouting(filters::okFilter(), + stores.okStore->getReportReceptionQueue(0)); + } + + // NOT OK store and PUS funnel to NOT OK store routing + // TODO: Make queue depth configurable + { + PersistentTmStoreArgs storeArgs(objects::NOT_OK_TM_STORE, "tm", "nok", + RolloverInterval::MINUTELY, 30, **tmStore, sdcMan); + stores.notOkStore = new PersistentTmStoreWithTmQueue(storeArgs, "NOT OK STORE", 500); + (*pusFunnel) + ->addPersistentTmStoreRouting(filters::notOkFilter(), + stores.notOkStore->getReportReceptionQueue(0)); + } + + // HK store and PUS funnel to HK store routing + // TODO: Make queue depth configurable + { + PersistentTmStoreArgs storeArgs(objects::HK_TM_STORE, "tm", "hk", RolloverInterval::MINUTELY, + 15, **tmStore, sdcMan); + stores.hkStore = new PersistentTmStoreWithTmQueue(storeArgs, "HK STORE", 500); + (*pusFunnel) + ->addPersistentTmStoreRouting(filters::hkFilter(), + stores.hkStore->getReportReceptionQueue(0)); + } + + // CFDP store and PUS funnel to CFDP store routing + // TODO: Make queue depth configurable + { + PersistentTmStoreArgs storeArgs(objects::CFDP_TM_STORE, "tm", "cfdp", + RolloverInterval::MINUTELY, 30, **tmStore, sdcMan); + stores.cfdpStore = new PersistentTmStoreWithTmQueue(storeArgs, "CFDP STORE", 500); + + (*pusFunnel) + ->addPersistentTmStoreRouting(filters::cfdpFilter(), + stores.cfdpStore->getReportReceptionQueue(0)); + } + #if OBSW_ADD_TCPIP_SERVERS == 1 #if OBSW_ADD_TMTC_UDP_SERVER == 1 (*cfdpFunnel)->addLiveDestination("UDP Server", *udpBridge, 0); @@ -208,7 +261,7 @@ void ObjectFactory::produceGenericObjects(HealthTableIF** healthTable_, PusTmFun new CfdpDistributor(distribCfg); auto* msgQueue = QueueFactory::instance()->createMessageQueue(32); - FsfwHandlerParams params(objects::CFDP_HANDLER, HOST_FS, **cfdpFunnel, *tcStore, *tmStore, + FsfwHandlerParams params(objects::CFDP_HANDLER, HOST_FS, **cfdpFunnel, *tcStore, **tmStore, *msgQueue); cfdp::IndicationCfg indicationCfg; UnsignedByteField apid(config::EIVE_LOCAL_CFDP_ENTITY_ID); diff --git a/mission/core/GenericFactory.h b/mission/core/GenericFactory.h index 5902ff7b..6fb5d73d 100644 --- a/mission/core/GenericFactory.h +++ b/mission/core/GenericFactory.h @@ -3,6 +3,7 @@ #include #include +#include #include "fsfw/objectmanager/SystemObjectIF.h" #include "fsfw/power/PowerSwitchIF.h" @@ -35,10 +36,20 @@ const std::array, EiveMax31855::NUM_RTDS> RT {objects::RTD_15_IC18_IMTQ, "RTD_15_IMTQ"}, }}; +struct PersistentTmStores { + PersistentTmStoreWithTmQueue* okStore; + PersistentTmStoreWithTmQueue* notOkStore; + PersistentTmStoreWithTmQueue* miscStore; + PersistentTmStoreWithTmQueue* hkStore; + PersistentTmStoreWithTmQueue* cfdpStore; +}; + namespace ObjectFactory { void produceGenericObjects(HealthTableIF** healthTable, PusTmFunnel** pusFunnel, - CfdpTmFunnel** cfdpFunnel, SdCardMountedIF& sdcMan); + CfdpTmFunnel** cfdpFunnel, SdCardMountedIF& sdcMan, + StorageManagerIF** ipcStore, StorageManagerIF** tmStore, + PersistentTmStores& stores); void createGenericHeaterComponents(GpioIF& gpioIF, PowerSwitchIF& pwrSwitcher, HeaterHandler*& heaterHandler); diff --git a/mission/tmtc/CMakeLists.txt b/mission/tmtc/CMakeLists.txt index ab5cf85d..b155e02e 100644 --- a/mission/tmtc/CMakeLists.txt +++ b/mission/tmtc/CMakeLists.txt @@ -12,6 +12,7 @@ target_sources( PusLiveDemux.cpp PersistentSingleTmStoreTask.cpp PersistentLogTmStoreTask.cpp + TmStoreTaskBase.cpp PusPacketFilter.cpp PusTmRouteByFilterHelper.cpp Service15TmStorage.cpp diff --git a/mission/tmtc/PersistentLogTmStoreTask.cpp b/mission/tmtc/PersistentLogTmStoreTask.cpp index 2102bcb7..0410893d 100644 --- a/mission/tmtc/PersistentLogTmStoreTask.cpp +++ b/mission/tmtc/PersistentLogTmStoreTask.cpp @@ -1 +1,28 @@ #include "PersistentLogTmStoreTask.h" + +#include + +PersistentLogTmStoreTask::PersistentLogTmStoreTask(object_id_t objectId, StorageManagerIF& ipcStore, + LogStores stores, VirtualChannel& channel) + : TmStoreTaskBase(objectId, ipcStore, channel), stores(stores) {} + +ReturnValue_t PersistentLogTmStoreTask::performOperation(uint8_t opCode) { + while (true) { + bool someonesBusy = false; + bool busy = handleOneStore(stores.okStore); + if (busy) { + someonesBusy = true; + } + busy = handleOneStore(stores.okStore); + if (busy) { + someonesBusy = true; + } + busy = handleOneStore(stores.miscStore); + if (busy) { + someonesBusy = true; + } + if (not someonesBusy) { + TaskFactory::delayTask(5); + } + } +} diff --git a/mission/tmtc/PersistentLogTmStoreTask.h b/mission/tmtc/PersistentLogTmStoreTask.h index d119fd33..a360c35c 100644 --- a/mission/tmtc/PersistentLogTmStoreTask.h +++ b/mission/tmtc/PersistentLogTmStoreTask.h @@ -5,22 +5,29 @@ #include #include #include +#include #include #include +#include #include struct LogStores { + LogStores(PersistentTmStores& stores) + : okStore(*stores.okStore), notOkStore(*stores.notOkStore), miscStore(*stores.miscStore) {} PersistentTmStoreWithTmQueue& okStore; PersistentTmStoreWithTmQueue& notOkStore; PersistentTmStoreWithTmQueue& miscStore; }; -class PersistentLogTmStoreTask : public SystemObject, public ExecutableObjectIF { +class PersistentLogTmStoreTask : public TmStoreTaskBase, public ExecutableObjectIF { public: PersistentLogTmStoreTask(object_id_t objectId, StorageManagerIF& ipcStore, LogStores tmStore, - VirtualChannelWithQueue& channel); + VirtualChannel& channel); + + ReturnValue_t performOperation(uint8_t opCode) override; private: + LogStores stores; }; #endif /* MISSION_TMTC_PERSISTENTLOGTMSTORETASK_H_ */ diff --git a/mission/tmtc/PersistentSingleTmStoreTask.cpp b/mission/tmtc/PersistentSingleTmStoreTask.cpp index 3b7f919c..e3bd018b 100644 --- a/mission/tmtc/PersistentSingleTmStoreTask.cpp +++ b/mission/tmtc/PersistentSingleTmStoreTask.cpp @@ -5,32 +5,12 @@ PersistentSingleTmStoreTask::PersistentSingleTmStoreTask(object_id_t objectId, StorageManagerIF& ipcStore, PersistentTmStoreWithTmQueue& tmStore, VirtualChannel& channel) - : SystemObject(objectId), ipcStore(ipcStore), storeWithQueue(tmStore), channel(channel) {} + : TmStoreTaskBase(objectId, ipcStore, channel), storeWithQueue(tmStore) {} ReturnValue_t PersistentSingleTmStoreTask::performOperation(uint8_t opCode) { - ReturnValue_t result; - auto& store = storeWithQueue.getTmStore(); - bool noTmToStoreReceived = false; - bool noTcRequestReceived = false; while (true) { - // Store TM persistently - result = storeWithQueue.handleNextTm(); - if (result == MessageQueueIF::NO_QUEUE) { - noTmToStoreReceived = true; - } - // Handle TC requests, for example deletion or retrieval requests. - result = store.handleCommandQueue(ipcStore); - if (result == MessageQueueIF::NO_QUEUE) { - noTcRequestReceived = true; - } - // Dump TMs when applicable - if (store.getState() == PersistentTmStore::State::DUMPING) { - size_t dumpedLen; - // TODO: Maybe do a bit of a delay every 100-200 packets? - // TODO: handle returnvalue? - store.dumpNextPacket(channel, dumpedLen); - } else if (noTcRequestReceived and noTmToStoreReceived) { - // Nothng to do, so sleep for a bit. + bool busy = handleOneStore(storeWithQueue); + if (not busy) { TaskFactory::delayTask(5); } } diff --git a/mission/tmtc/PersistentSingleTmStoreTask.h b/mission/tmtc/PersistentSingleTmStoreTask.h index 4ec9f03f..7776134a 100644 --- a/mission/tmtc/PersistentSingleTmStoreTask.h +++ b/mission/tmtc/PersistentSingleTmStoreTask.h @@ -4,9 +4,10 @@ #include #include #include +#include #include -class PersistentSingleTmStoreTask : public SystemObject, public ExecutableObjectIF { +class PersistentSingleTmStoreTask : public TmStoreTaskBase, public ExecutableObjectIF { public: PersistentSingleTmStoreTask(object_id_t objectId, StorageManagerIF& ipcStore, PersistentTmStoreWithTmQueue& storeWithQueue, @@ -15,9 +16,7 @@ class PersistentSingleTmStoreTask : public SystemObject, public ExecutableObject ReturnValue_t performOperation(uint8_t opCode) override; private: - StorageManagerIF& ipcStore; PersistentTmStoreWithTmQueue& storeWithQueue; - VirtualChannel& channel; }; #endif /* MISSION_TMTC_PERSISTENTSINGLETMSTORETASK_H_ */ diff --git a/mission/tmtc/PersistentTmStore.cpp b/mission/tmtc/PersistentTmStore.cpp index 8bcf59bd..0fe96c65 100644 --- a/mission/tmtc/PersistentTmStore.cpp +++ b/mission/tmtc/PersistentTmStore.cpp @@ -15,17 +15,14 @@ using namespace returnvalue; -PersistentTmStore::PersistentTmStore(object_id_t objectId, const char* baseDir, - std::string baseName, RolloverInterval intervalUnit, - uint32_t intervalCount, StorageManagerIF& tmStore, - SdCardMountedIF& sdcMan) - : SystemObject(objectId), - baseDir(baseDir), - baseName(std::move(baseName)), - sdcMan(sdcMan), - tmStore(tmStore) { +PersistentTmStore::PersistentTmStore(PersistentTmStoreArgs args) + : SystemObject(args.objectId), + tmStore(args.tmStore), + baseDir(args.baseDir), + baseName(std::move(args.baseName)), + sdcMan(args.sdcMan) { tcQueue = QueueFactory::instance()->createMessageQueue(); - calcDiffSeconds(intervalUnit, intervalCount); + calcDiffSeconds(args.intervalUnit, args.intervalCount); } ReturnValue_t PersistentTmStore::assignAndOrCreateMostRecentFile() { diff --git a/mission/tmtc/PersistentTmStore.h b/mission/tmtc/PersistentTmStore.h index 795c1fcd..34ad0ba0 100644 --- a/mission/tmtc/PersistentTmStore.h +++ b/mission/tmtc/PersistentTmStore.h @@ -17,6 +17,27 @@ enum class RolloverInterval { MINUTELY, HOURLY, DAILY }; +struct PersistentTmStoreArgs { + PersistentTmStoreArgs(object_id_t objectId, const char* baseDir, std::string baseName, + RolloverInterval intervalUnit, uint32_t intervalCount, + StorageManagerIF& tmStore, SdCardMountedIF& sdcMan) + : objectId(objectId), + baseDir(baseDir), + baseName(baseName), + intervalUnit(intervalUnit), + intervalCount(intervalCount), + tmStore(tmStore), + sdcMan(sdcMan) {} + + object_id_t objectId; + const char* baseDir; + std::string baseName; + RolloverInterval intervalUnit; + uint32_t intervalCount; + StorageManagerIF& tmStore; + SdCardMountedIF& sdcMan; +}; + class PersistentTmStore : public TmStoreFrontendSimpleIF, public SystemObject { public: enum class State { IDLE, DUMPING }; @@ -36,9 +57,7 @@ class PersistentTmStore : public TmStoreFrontendSimpleIF, public SystemObject { static constexpr Event FILE_TOO_LARGE = event::makeEvent(SUBSYSTEM_ID, 1, severity::LOW); static constexpr Event BUSY_DUMPING_EVENT = event::makeEvent(SUBSYSTEM_ID, 2, severity::INFO); - PersistentTmStore(object_id_t objectId, const char* baseDir, std::string baseName, - RolloverInterval intervalUnit, uint32_t intervalCount, - StorageManagerIF& tmStore, SdCardMountedIF& sdcMan); + PersistentTmStore(PersistentTmStoreArgs args); ReturnValue_t initializeTmStore(); State getState() const; @@ -52,6 +71,9 @@ class PersistentTmStore : public TmStoreFrontendSimpleIF, public SystemObject { // ReturnValue_t passPacket(PusTmReader& reader); ReturnValue_t storePacket(PusTmReader& reader); + protected: + StorageManagerIF& tmStore; + private: static constexpr uint8_t MAX_FILES_IN_ONE_SECOND = 10; static constexpr size_t MAX_FILESIZE = 8192; @@ -87,7 +109,6 @@ class PersistentTmStore : public TmStoreFrontendSimpleIF, public SystemObject { ActiveDumpParams dumpParams; std::optional activeFile; SdCardMountedIF& sdcMan; - StorageManagerIF& tmStore; /** * To get the queue where commands shall be sent. diff --git a/mission/tmtc/PersistentTmStoreWithTmQueue.cpp b/mission/tmtc/PersistentTmStoreWithTmQueue.cpp index b8d40adf..df4960d3 100644 --- a/mission/tmtc/PersistentTmStoreWithTmQueue.cpp +++ b/mission/tmtc/PersistentTmStoreWithTmQueue.cpp @@ -3,10 +3,10 @@ #include #include -PersistentTmStoreWithTmQueue::PersistentTmStoreWithTmQueue(StorageManagerIF& tmStore, - PersistentTmStore& persistentTmStore, +PersistentTmStoreWithTmQueue::PersistentTmStoreWithTmQueue(PersistentTmStoreArgs args, + const char* storeName, uint32_t tmQueueDepth) - : tmStore(tmStore), persistentTmStore(persistentTmStore) { + : PersistentTmStore(args), storeName(storeName) { tmQueue = QueueFactory::instance()->createMessageQueue(tmQueueDepth); } @@ -21,8 +21,13 @@ ReturnValue_t PersistentTmStoreWithTmQueue::handleNextTm() { return result; } PusTmReader reader(accessor.second.data(), accessor.second.size()); - persistentTmStore.storePacket(reader); + storePacket(reader); return returnvalue::OK; } -PersistentTmStore& PersistentTmStoreWithTmQueue::getTmStore() { return persistentTmStore; } +const char* PersistentTmStoreWithTmQueue::getName() const { return storeName; } + +MessageQueueId_t PersistentTmStoreWithTmQueue::getReportReceptionQueue( + uint8_t virtualChannel) const { + return tmQueue->getId(); +} diff --git a/mission/tmtc/PersistentTmStoreWithTmQueue.h b/mission/tmtc/PersistentTmStoreWithTmQueue.h index 05cc4d2d..be1026f8 100644 --- a/mission/tmtc/PersistentTmStoreWithTmQueue.h +++ b/mission/tmtc/PersistentTmStoreWithTmQueue.h @@ -2,18 +2,19 @@ #define MISSION_TMTC_PERSISTENTTMSTOREWITHTMQUEUE_H_ #include -class PersistentTmStoreWithTmQueue : public AcceptsTelemetryIF { +class PersistentTmStoreWithTmQueue : public PersistentTmStore, public AcceptsTelemetryIF { public: - PersistentTmStoreWithTmQueue(StorageManagerIF& tmStore, PersistentTmStore& persistentTmStore, + PersistentTmStoreWithTmQueue(PersistentTmStoreArgs args, const char* storeName, uint32_t tmQueueDepth); ReturnValue_t handleNextTm(); - PersistentTmStore& getTmStore(); + + [[nodiscard]] const char* getName() const override; + [[nodiscard]] MessageQueueId_t getReportReceptionQueue(uint8_t virtualChannel) const override; private: - StorageManagerIF& tmStore; + const char* storeName; MessageQueueIF* tmQueue; - PersistentTmStore& persistentTmStore; }; #endif /* MISSION_TMTC_PERSISTENTTMSTOREWITHTMQUEUE_H_ */ diff --git a/mission/tmtc/TmStoreTaskBase.cpp b/mission/tmtc/TmStoreTaskBase.cpp new file mode 100644 index 00000000..839cb754 --- /dev/null +++ b/mission/tmtc/TmStoreTaskBase.cpp @@ -0,0 +1,35 @@ +#include "TmStoreTaskBase.h" + +TmStoreTaskBase::TmStoreTaskBase(object_id_t objectId, StorageManagerIF& ipcStore, + VirtualChannel& channel) + : SystemObject(objectId), ipcStore(ipcStore), channel(channel) {} + +bool TmStoreTaskBase::handleOneStore(PersistentTmStoreWithTmQueue& store) { + bool tmToStoreReceived = true; + bool tcRequestReceived = true; + bool dumpsPerformed = false; + // Store TM persistently + ReturnValue_t result = store.handleNextTm(); + if (result == MessageQueueIF::NO_QUEUE) { + tmToStoreReceived = false; + } + // Handle TC requests, for example deletion or retrieval requests. + result = store.handleCommandQueue(ipcStore); + if (result == MessageQueueIF::NO_QUEUE) { + tcRequestReceived = false; + } + // Dump TMs when applicable + if (store.getState() == PersistentTmStore::State::DUMPING) { + size_t dumpedLen; + // TODO: Maybe do a bit of a delay every 100-200 packets? + // TODO: handle returnvalue? + result = store.dumpNextPacket(channel, dumpedLen); + if (result == returnvalue::OK) { + dumpsPerformed = true; + } + } + if (tcRequestReceived or tmToStoreReceived or dumpsPerformed) { + return true; + } + return false; +} diff --git a/mission/tmtc/TmStoreTaskBase.h b/mission/tmtc/TmStoreTaskBase.h new file mode 100644 index 00000000..b2f1f323 --- /dev/null +++ b/mission/tmtc/TmStoreTaskBase.h @@ -0,0 +1,22 @@ +#ifndef MISSION_TMTC_TMSTORETASKBASE_H_ +#define MISSION_TMTC_TMSTORETASKBASE_H_ + +#include +#include + +class TmStoreTaskBase : public SystemObject { + public: + TmStoreTaskBase(object_id_t objectId, StorageManagerIF& ipcStore, VirtualChannel& channel); + /** + * Handling for one store. Returns if anything was done. + * @param store + * @return + */ + bool handleOneStore(PersistentTmStoreWithTmQueue& store); + + private: + StorageManagerIF& ipcStore; + VirtualChannel& channel; +}; + +#endif /* MISSION_TMTC_TMSTORETASKBASE_H_ */ diff --git a/mission/tmtc/VirtualChannel.cpp b/mission/tmtc/VirtualChannel.cpp index fba64049..0c41ad86 100644 --- a/mission/tmtc/VirtualChannel.cpp +++ b/mission/tmtc/VirtualChannel.cpp @@ -3,9 +3,9 @@ VirtualChannel::VirtualChannel(object_id_t objectId, uint8_t vcId, const char* vcName, PtmeIF& ptme, const std::atomic_bool& linkStateProvider) : SystemObject(objectId), + ptme(ptme), vcId(vcId), vcName(vcName), - ptme(ptme), linkStateProvider(linkStateProvider) {} ReturnValue_t VirtualChannel::initialize() { return returnvalue::OK; } diff --git a/mission/tmtc/VirtualChannelWithQueue.cpp b/mission/tmtc/VirtualChannelWithQueue.cpp index 62557973..630552cb 100644 --- a/mission/tmtc/VirtualChannelWithQueue.cpp +++ b/mission/tmtc/VirtualChannelWithQueue.cpp @@ -7,15 +7,18 @@ #include "fsfw/serviceinterface/ServiceInterfaceStream.h" #include "fsfw/tmtcservices/TmTcMessage.h" -VirtualChannelWithQueue::VirtualChannelWithQueue(VirtualChannel& channel, StorageManagerIF& tmStore, - uint32_t tmQueueDepth, - const std::atomic_bool& linkStateProvider) - : channel(channel) { - auto mqArgs = MqArgs(channel.getObjectId(), reinterpret_cast(channel.getVcid())); +VirtualChannelWithQueue::VirtualChannelWithQueue(object_id_t objectId, uint8_t vcId, + const char* vcName, PtmeIF& ptme, + const std::atomic_bool& linkStateProvider, + StorageManagerIF& tmStore, uint32_t tmQueueDepth) + : VirtualChannel(objectId, vcId, vcName, ptme, linkStateProvider) { + auto mqArgs = MqArgs(getObjectId(), reinterpret_cast(getVcid())); tmQueue = QueueFactory::instance()->createMessageQueue( tmQueueDepth, MessageQueueMessage::MAX_MESSAGE_SIZE, &mqArgs); } +const char* VirtualChannelWithQueue::getName() const { return VirtualChannel::getName(); } + ReturnValue_t VirtualChannelWithQueue::sendNextTm() { TmTcMessage message; ReturnValue_t result = tmQueue->receiveMessage(&message); @@ -33,7 +36,7 @@ ReturnValue_t VirtualChannelWithQueue::sendNextTm() { return result; } - channel.write(data, size); + write(data, size); tmStore->deleteData(storeId); if (result != returnvalue::OK) { return result; @@ -44,5 +47,3 @@ ReturnValue_t VirtualChannelWithQueue::sendNextTm() { MessageQueueId_t VirtualChannelWithQueue::getReportReceptionQueue(uint8_t virtualChannel) const { return tmQueue->getId(); } - -VirtualChannel& VirtualChannelWithQueue::vc() { return channel; } diff --git a/mission/tmtc/VirtualChannelWithQueue.h b/mission/tmtc/VirtualChannelWithQueue.h index f7a2bef9..fdd0fca4 100644 --- a/mission/tmtc/VirtualChannelWithQueue.h +++ b/mission/tmtc/VirtualChannelWithQueue.h @@ -20,7 +20,7 @@ class StorageManagerIF; * * @author J. Meier */ -class VirtualChannelWithQueue : public AcceptsTelemetryIF { +class VirtualChannelWithQueue : public VirtualChannel, public AcceptsTelemetryIF { public: /** * @brief Constructor @@ -28,18 +28,15 @@ class VirtualChannelWithQueue : public AcceptsTelemetryIF { * @param vcId The virtual channel id assigned to this object * @param tmQueueDepth Queue depth of queue receiving telemetry from other objects */ - VirtualChannelWithQueue(VirtualChannel& channel, StorageManagerIF& tmStore, uint32_t tmQueueDepth, - const std::atomic_bool& linkStateProvider); + VirtualChannelWithQueue(object_id_t objectId, uint8_t vcId, const char* vcName, PtmeIF& ptme, + const std::atomic_bool& linkStateProvider, StorageManagerIF& tmStore, + uint32_t tmQueueDepth); MessageQueueId_t getReportReceptionQueue(uint8_t virtualChannel = 0) const override; + [[nodiscard]] const char* getName() const override; ReturnValue_t sendNextTm(); - VirtualChannel& vc(); - - const char* getName() const override; - private: - VirtualChannel& channel; MessageQueueIF* tmQueue = nullptr; StorageManagerIF* tmStore = nullptr; }; diff --git a/mission/tmtc/tmFilters.cpp b/mission/tmtc/tmFilters.cpp index 540df3de..944cd3be 100644 --- a/mission/tmtc/tmFilters.cpp +++ b/mission/tmtc/tmFilters.cpp @@ -49,3 +49,9 @@ PusPacketFilter filters::notOkFilter() { notOkFilter.addServiceSubservice(pus::PUS_SERVICE_1, 8); return notOkFilter; } + +PusPacketFilter filters::cfdpFilter() { + PusPacketFilter cfdpFilter; + cfdpFilter.addApid(config::EIVE_CFDP_APID); + return cfdpFilter; +} diff --git a/mission/tmtc/tmFilters.h b/mission/tmtc/tmFilters.h index fc5318f9..a358c8f0 100644 --- a/mission/tmtc/tmFilters.h +++ b/mission/tmtc/tmFilters.h @@ -4,6 +4,7 @@ namespace filters { +PusPacketFilter cfdpFilter(); PusPacketFilter hkFilter(); PusPacketFilter miscFilter(); PusPacketFilter okFilter(); From 1dee29aabd6c30c9f8c03604685601b01ff7fbaf Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 9 Mar 2023 19:43:38 +0100 Subject: [PATCH 039/112] changelog typo --- CHANGELOG.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index c2e0ff71..177b9687 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -22,7 +22,7 @@ will consitute of a breaking change warranting a new major release: This was done by moving the dumping of TMs to the VCs into separate threads with permanent loops. These threads are then able to process high TM loads on demand. The PUS TM funnel will route PUS packets to the approrpiate persisten TM stores and then demultiplex the TM to all registered - TM destinations are before. + TM destinations as before. ## Fixed From 3ebcbaa44f757f2a129085676866b1f1f0f053d9 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 9 Mar 2023 19:44:24 +0100 Subject: [PATCH 040/112] added fixed entry --- CHANGELOG.md | 1 + 1 file changed, 1 insertion(+) diff --git a/CHANGELOG.md b/CHANGELOG.md index 177b9687..43628dd6 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -26,6 +26,7 @@ will consitute of a breaking change warranting a new major release: ## Fixed +- `PAPB_EMPTY_SIGNAL_VC1` GPIO was not set up properly. - Fix for heater names: HPA heater (index 7) is now the Syrlinks heater. # [v1.36.0] 2023-03-08 From 245116403a8479a77af24527908a66653a5aae3b Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 9 Mar 2023 19:45:23 +0100 Subject: [PATCH 041/112] remove obsolete code --- mission/tmtc/CcsdsIpCoreHandler.cpp | 37 ----------------------------- mission/tmtc/CcsdsIpCoreHandler.h | 15 ------------ 2 files changed, 52 deletions(-) diff --git a/mission/tmtc/CcsdsIpCoreHandler.cpp b/mission/tmtc/CcsdsIpCoreHandler.cpp index 9a892977..ec6602cc 100644 --- a/mission/tmtc/CcsdsIpCoreHandler.cpp +++ b/mission/tmtc/CcsdsIpCoreHandler.cpp @@ -108,43 +108,6 @@ void CcsdsIpCoreHandler::readCommandQueue(void) { MessageQueueId_t CcsdsIpCoreHandler::getCommandQueue() const { return commandQueue->getId(); } -// void CcsdsIpCoreHandler::addVirtualChannel(VcId_t vcId, VirtualChannelWithQueue* virtualChannel) -// { -// if (vcId > config::NUMBER_OF_VIRTUAL_CHANNELS) { -// sif::warning << "CcsdsHandler::addVirtualChannel: Invalid virtual channel ID" << std::endl; -// return; -// } -// -// if (virtualChannel == nullptr) { -// sif::warning << "CcsdsHandler::addVirtualChannel: Invalid virtual channel interface" -// << std::endl; -// return; -// } -// -// auto status = virtualChannelMap.emplace(vcId, virtualChannel); -// if (status.second == false) { -// sif::warning << "CcsdsHandler::addVirtualChannel: Failed to add virtual channel to " -// "virtual channel map" -// << std::endl; -// return; -// } -// } - -// MessageQueueId_t CcsdsIpCoreHandler::getReportReceptionQueue(uint8_t virtualChannel) const { -// if (virtualChannel > config::NUMBER_OF_VIRTUAL_CHANNELS) { -// sif::debug << "CcsdsHandler::getReportReceptionQueue: Invalid virtual channel requested"; -// return MessageQueueIF::NO_QUEUE; -// } -// auto iter = virtualChannelMap.find(virtualChannel); -// if (iter != virtualChannelMap.end()) { -// return iter->second->getReportReceptionQueue(); -// } -// sif::warning << "CcsdsHandler::getReportReceptionQueue: Virtual channel with ID " -// << static_cast(virtualChannel) << " not in virtual channel map" -// << std::endl; -// return MessageQueueIF::NO_QUEUE; -// } - ReturnValue_t CcsdsIpCoreHandler::getParameter(uint8_t domainId, uint8_t uniqueIdentifier, ParameterWrapper* parameterWrapper, const ParameterWrapper* newValues, diff --git a/mission/tmtc/CcsdsIpCoreHandler.h b/mission/tmtc/CcsdsIpCoreHandler.h index 4a501ab5..a147a13f 100644 --- a/mission/tmtc/CcsdsIpCoreHandler.h +++ b/mission/tmtc/CcsdsIpCoreHandler.h @@ -69,13 +69,6 @@ class CcsdsIpCoreHandler : public SystemObject, ReturnValue_t performOperation(uint8_t operationCode = 0) override; ReturnValue_t initialize(); MessageQueueId_t getCommandQueue() const override; - /** - * Currently directly forwards requests to the virtual channels which might live - * in different threads. - * @param virtualChannel - * @return - */ - // MessageQueueId_t getReportReceptionQueue(uint8_t virtualChannel) const override; // ModesIF void getMode(Mode_t* mode, Submode_t* submode) override; @@ -84,14 +77,6 @@ class CcsdsIpCoreHandler : public SystemObject, void startTransition(Mode_t mode, Submode_t submode) override; void announceMode(bool recursive) override; - /** - * @brief Function to add a virtual channel - * - * @param virtualChannelId ID of the virtual channel to add - * @param virtualChannel Pointer to virtual channel object - */ - // void addVirtualChannel(VcId_t virtualChannelId, VirtualChannelWithQueue* virtualChannel); - ReturnValue_t getParameter(uint8_t domainId, uint8_t uniqueIdentifier, ParameterWrapper* parameterWrapper, const ParameterWrapper* newValues, uint16_t startAtIndex); From e6aa582fcb8a865f4663e2d316fb2259d29d6ddc Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 9 Mar 2023 19:52:13 +0100 Subject: [PATCH 042/112] link live TM --- bsp_q7s/core/ObjectFactory.cpp | 1 + bsp_q7s/core/ObjectFactory.h | 8 +++----- bsp_q7s/fmObjectFactory.cpp | 5 ++++- linux/ObjectFactory.cpp | 8 -------- linux/ObjectFactory.h | 2 -- 5 files changed, 8 insertions(+), 16 deletions(-) diff --git a/bsp_q7s/core/ObjectFactory.cpp b/bsp_q7s/core/ObjectFactory.cpp index a3045e62..b0bab8de 100644 --- a/bsp_q7s/core/ObjectFactory.cpp +++ b/bsp_q7s/core/ObjectFactory.cpp @@ -771,6 +771,7 @@ ReturnValue_t ObjectFactory::createCcsdsComponents(CcsdsComponentArgs& args) { auto* vcWithQueue = new VirtualChannelWithQueue(objects::PTME_VC0_LIVE_TM, ccsds::VC0, "PTME VC0 LIVE TM", *ptme, LINK_STATE, args.tmStore, 500); + args.liveDestination = vcWithQueue->getReportReceptionQueue(0); new LiveTmTask(objects::LIVE_TM_TASK, *vcWithQueue); // Set up log store. diff --git a/bsp_q7s/core/ObjectFactory.h b/bsp_q7s/core/ObjectFactory.h index c13f9c68..26433917 100644 --- a/bsp_q7s/core/ObjectFactory.h +++ b/bsp_q7s/core/ObjectFactory.h @@ -25,21 +25,19 @@ class GpioIF; namespace ObjectFactory { struct CcsdsComponentArgs { - CcsdsComponentArgs(LinuxLibgpioIF& gpioIF, PusTmFunnel& funnel, StorageManagerIF& ipcStore, - StorageManagerIF& tmStore, PersistentTmStores& stores, - CcsdsIpCoreHandler** ipCoreHandler) + CcsdsComponentArgs(LinuxLibgpioIF& gpioIF, StorageManagerIF& ipcStore, StorageManagerIF& tmStore, + PersistentTmStores& stores, CcsdsIpCoreHandler** ipCoreHandler) : gpioComIF(gpioIF), - pusFunnel(funnel), ipcStore(ipcStore), tmStore(tmStore), stores(stores), ipCoreHandler(ipCoreHandler) {} LinuxLibgpioIF& gpioComIF; - PusTmFunnel& pusFunnel; StorageManagerIF& ipcStore; StorageManagerIF& tmStore; PersistentTmStores& stores; CcsdsIpCoreHandler** ipCoreHandler; + AcceptsTelemetryIF* liveDestination = nullptr; }; void setStatics(); diff --git a/bsp_q7s/fmObjectFactory.cpp b/bsp_q7s/fmObjectFactory.cpp index 0fecf58b..68695f42 100644 --- a/bsp_q7s/fmObjectFactory.cpp +++ b/bsp_q7s/fmObjectFactory.cpp @@ -77,10 +77,13 @@ void ObjectFactory::produce(void* args) { #endif /* OBSW_ADD_STAR_TRACKER == 1 */ #if OBSW_ADD_CCSDS_IP_CORES == 1 CcsdsIpCoreHandler* ipCoreHandler = nullptr; - CcsdsComponentArgs ccsdsArgs(*gpioComIF, *pusFunnel, *ipcStore, *tmStore, stores, &ipCoreHandler); + CcsdsComponentArgs ccsdsArgs(*gpioComIF, *ipcStore, *tmStore, stores, &ipCoreHandler); createCcsdsComponents(ccsdsArgs); #if OBSW_TM_TO_PTME == 1 // TODO: Remove this if not needed anymore + if (*ccsdsArgs.liveDestination != nullptr) { + pusFunnel->addLiveDestination("VC0 LIVE TM", *ccsdsArgs.liveDestination, 0); + } // addTmtcIpCoresToFunnels(*ipCoreHandler, *pusFunnel, *cfdpFunnel); #endif #endif /* OBSW_ADD_CCSDS_IP_CORES == 1 */ diff --git a/linux/ObjectFactory.cpp b/linux/ObjectFactory.cpp index 43ea9e70..1ac86886 100644 --- a/linux/ObjectFactory.cpp +++ b/linux/ObjectFactory.cpp @@ -341,11 +341,3 @@ void ObjectFactory::gpioChecker(ReturnValue_t result, std::string output) { sif::error << "ObjectFactory: Adding GPIOs failed for " << output << std::endl; } } - -void ObjectFactory::addTmtcIpCoresToFunnels(CcsdsIpCoreHandler& ipCoreHandler, - PusTmFunnel& pusFunnel, CfdpTmFunnel& cfdpFunnel) { - // TODO: Consider removing this, the only additional object in the dest list will - // be the live VC - // cfdpFunnel.addDestination("PTME IP Core", ipCoreHandler, config::LIVE_TM); - // pusFunnel.addDestination("PTME IP Core", ipCoreHandler, config::LIVE_TM); -} diff --git a/linux/ObjectFactory.h b/linux/ObjectFactory.h index 0a7ab516..056dbd65 100644 --- a/linux/ObjectFactory.h +++ b/linux/ObjectFactory.h @@ -33,6 +33,4 @@ void gpioChecker(ReturnValue_t result, std::string output); AcsController* createAcsController(bool connectSubsystem); -void addTmtcIpCoresToFunnels(CcsdsIpCoreHandler& ipCoreHandler, PusTmFunnel& pusFunnel, - CfdpTmFunnel& cfdpFunnel); } // namespace ObjectFactory From d50cbe9e5b00504794fa744a734d7a2802e129cb Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 9 Mar 2023 20:16:00 +0100 Subject: [PATCH 043/112] added missing store initialization code --- bsp_q7s/core/ObjectFactory.cpp | 10 +++++--- bsp_q7s/fmObjectFactory.cpp | 4 +-- mission/tmtc/PersistentLogTmStoreTask.cpp | 27 +++++++++++++++----- mission/tmtc/PersistentLogTmStoreTask.h | 4 ++- mission/tmtc/PersistentSingleTmStoreTask.cpp | 10 ++++++-- mission/tmtc/PersistentSingleTmStoreTask.h | 6 +++-- mission/tmtc/TmStoreTaskBase.cpp | 25 ++++++++++++++++-- mission/tmtc/TmStoreTaskBase.h | 18 +++++++++++-- 8 files changed, 82 insertions(+), 22 deletions(-) diff --git a/bsp_q7s/core/ObjectFactory.cpp b/bsp_q7s/core/ObjectFactory.cpp index b0bab8de..721c5338 100644 --- a/bsp_q7s/core/ObjectFactory.cpp +++ b/bsp_q7s/core/ObjectFactory.cpp @@ -771,7 +771,7 @@ ReturnValue_t ObjectFactory::createCcsdsComponents(CcsdsComponentArgs& args) { auto* vcWithQueue = new VirtualChannelWithQueue(objects::PTME_VC0_LIVE_TM, ccsds::VC0, "PTME VC0 LIVE TM", *ptme, LINK_STATE, args.tmStore, 500); - args.liveDestination = vcWithQueue->getReportReceptionQueue(0); + args.liveDestination = vcWithQueue; new LiveTmTask(objects::LIVE_TM_TASK, *vcWithQueue); // Set up log store. @@ -779,17 +779,19 @@ ReturnValue_t ObjectFactory::createCcsdsComponents(CcsdsComponentArgs& args) { LINK_STATE); LogStores logStores(args.stores); // Core task which handles the LOG store and takes care of dumping it as TM using a VC directly - new PersistentLogTmStoreTask(objects::LOG_STORE_TASK, args.ipcStore, logStores, *vc); + new PersistentLogTmStoreTask(objects::LOG_STORE_TASK, args.ipcStore, logStores, *vc, + *SdCardManager::instance()); vc = new VirtualChannel(objects::PTME_VC2_HK_TM, ccsds::VC2, "PTME VC2 HK TM", *ptme, LINK_STATE); // Core task which handles the HK store and takes care of dumping it as TM using a VC directly - new PersistentSingleTmStoreTask(objects::HK_STORE_TASK, args.ipcStore, *args.stores.hkStore, *vc); + new PersistentSingleTmStoreTask(objects::HK_STORE_TASK, args.ipcStore, *args.stores.hkStore, *vc, + *SdCardManager::instance()); vc = new VirtualChannel(objects::PTME_VC3_CFDP_TM, ccsds::VC3, "PTME VC3 CFDP TM", *ptme, LINK_STATE); // Core task which handles the CFDP store and takes care of dumping it as TM using a VC directly new PersistentSingleTmStoreTask(objects::CFDP_STORE_TASK, args.ipcStore, *args.stores.cfdpStore, - *vc); + *vc, *SdCardManager::instance()); ReturnValue_t result = (*args.ipCoreHandler)->connectModeTreeParent(satsystem::com::SUBSYSTEM); if (result != returnvalue::OK) { diff --git a/bsp_q7s/fmObjectFactory.cpp b/bsp_q7s/fmObjectFactory.cpp index 68695f42..390e4e8c 100644 --- a/bsp_q7s/fmObjectFactory.cpp +++ b/bsp_q7s/fmObjectFactory.cpp @@ -80,11 +80,9 @@ void ObjectFactory::produce(void* args) { CcsdsComponentArgs ccsdsArgs(*gpioComIF, *ipcStore, *tmStore, stores, &ipCoreHandler); createCcsdsComponents(ccsdsArgs); #if OBSW_TM_TO_PTME == 1 - // TODO: Remove this if not needed anymore - if (*ccsdsArgs.liveDestination != nullptr) { + if (ccsdsArgs.liveDestination != nullptr) { pusFunnel->addLiveDestination("VC0 LIVE TM", *ccsdsArgs.liveDestination, 0); } - // addTmtcIpCoresToFunnels(*ipCoreHandler, *pusFunnel, *cfdpFunnel); #endif #endif /* OBSW_ADD_CCSDS_IP_CORES == 1 */ diff --git a/mission/tmtc/PersistentLogTmStoreTask.cpp b/mission/tmtc/PersistentLogTmStoreTask.cpp index 0410893d..5e715ca0 100644 --- a/mission/tmtc/PersistentLogTmStoreTask.cpp +++ b/mission/tmtc/PersistentLogTmStoreTask.cpp @@ -3,20 +3,26 @@ #include PersistentLogTmStoreTask::PersistentLogTmStoreTask(object_id_t objectId, StorageManagerIF& ipcStore, - LogStores stores, VirtualChannel& channel) - : TmStoreTaskBase(objectId, ipcStore, channel), stores(stores) {} + LogStores stores, VirtualChannel& channel, + SdCardMountedIF& sdcMan) + : TmStoreTaskBase(objectId, ipcStore, channel, sdcMan), stores(stores) {} ReturnValue_t PersistentLogTmStoreTask::performOperation(uint8_t opCode) { while (true) { - bool someonesBusy = false; - bool busy = handleOneStore(stores.okStore); - if (busy) { - someonesBusy = true; + if (not cyclicStoreCheck()) { + continue; } + bool someonesBusy = false; + bool busy = false; busy = handleOneStore(stores.okStore); if (busy) { someonesBusy = true; } + busy = handleOneStore(stores.notOkStore); + if (busy) { + someonesBusy = true; + } + busy = handleOneStore(stores.miscStore); if (busy) { someonesBusy = true; @@ -26,3 +32,12 @@ ReturnValue_t PersistentLogTmStoreTask::performOperation(uint8_t opCode) { } } } + +void PersistentLogTmStoreTask::initStoresIfPossible() { + if (sdcMan.isSdCardUsable(std::nullopt)) { + stores.okStore.initializeTmStore(); + stores.miscStore.initializeTmStore(); + stores.notOkStore.initializeTmStore(); + storesInitialized = true; + } +} diff --git a/mission/tmtc/PersistentLogTmStoreTask.h b/mission/tmtc/PersistentLogTmStoreTask.h index a360c35c..e106bd12 100644 --- a/mission/tmtc/PersistentLogTmStoreTask.h +++ b/mission/tmtc/PersistentLogTmStoreTask.h @@ -22,12 +22,14 @@ struct LogStores { class PersistentLogTmStoreTask : public TmStoreTaskBase, public ExecutableObjectIF { public: PersistentLogTmStoreTask(object_id_t objectId, StorageManagerIF& ipcStore, LogStores tmStore, - VirtualChannel& channel); + VirtualChannel& channel, SdCardMountedIF& sdcMan); ReturnValue_t performOperation(uint8_t opCode) override; private: LogStores stores; + + void initStoresIfPossible(); }; #endif /* MISSION_TMTC_PERSISTENTLOGTMSTORETASK_H_ */ diff --git a/mission/tmtc/PersistentSingleTmStoreTask.cpp b/mission/tmtc/PersistentSingleTmStoreTask.cpp index e3bd018b..aaac7f6e 100644 --- a/mission/tmtc/PersistentSingleTmStoreTask.cpp +++ b/mission/tmtc/PersistentSingleTmStoreTask.cpp @@ -4,14 +4,20 @@ PersistentSingleTmStoreTask::PersistentSingleTmStoreTask(object_id_t objectId, StorageManagerIF& ipcStore, PersistentTmStoreWithTmQueue& tmStore, - VirtualChannel& channel) - : TmStoreTaskBase(objectId, ipcStore, channel), storeWithQueue(tmStore) {} + VirtualChannel& channel, + SdCardMountedIF& sdcMan) + : TmStoreTaskBase(objectId, ipcStore, channel, sdcMan), storeWithQueue(tmStore) {} ReturnValue_t PersistentSingleTmStoreTask::performOperation(uint8_t opCode) { while (true) { + if (not cyclicStoreCheck()) { + continue; + } bool busy = handleOneStore(storeWithQueue); if (not busy) { TaskFactory::delayTask(5); } } } + +void PersistentSingleTmStoreTask::initStoresIfPossible() {} diff --git a/mission/tmtc/PersistentSingleTmStoreTask.h b/mission/tmtc/PersistentSingleTmStoreTask.h index 7776134a..012ba8e8 100644 --- a/mission/tmtc/PersistentSingleTmStoreTask.h +++ b/mission/tmtc/PersistentSingleTmStoreTask.h @@ -10,13 +10,15 @@ class PersistentSingleTmStoreTask : public TmStoreTaskBase, public ExecutableObjectIF { public: PersistentSingleTmStoreTask(object_id_t objectId, StorageManagerIF& ipcStore, - PersistentTmStoreWithTmQueue& storeWithQueue, - VirtualChannel& channel); + PersistentTmStoreWithTmQueue& storeWithQueue, VirtualChannel& channel, + SdCardMountedIF& sdcMan); ReturnValue_t performOperation(uint8_t opCode) override; private: PersistentTmStoreWithTmQueue& storeWithQueue; + + void initStoresIfPossible(); }; #endif /* MISSION_TMTC_PERSISTENTSINGLETMSTORETASK_H_ */ diff --git a/mission/tmtc/TmStoreTaskBase.cpp b/mission/tmtc/TmStoreTaskBase.cpp index 839cb754..325dc77c 100644 --- a/mission/tmtc/TmStoreTaskBase.cpp +++ b/mission/tmtc/TmStoreTaskBase.cpp @@ -1,8 +1,10 @@ #include "TmStoreTaskBase.h" +#include + TmStoreTaskBase::TmStoreTaskBase(object_id_t objectId, StorageManagerIF& ipcStore, - VirtualChannel& channel) - : SystemObject(objectId), ipcStore(ipcStore), channel(channel) {} + VirtualChannel& channel, SdCardMountedIF& sdcMan) + : SystemObject(objectId), ipcStore(ipcStore), channel(channel), sdcMan(sdcMan) {} bool TmStoreTaskBase::handleOneStore(PersistentTmStoreWithTmQueue& store) { bool tmToStoreReceived = true; @@ -33,3 +35,22 @@ bool TmStoreTaskBase::handleOneStore(PersistentTmStoreWithTmQueue& store) { } return false; } + +bool TmStoreTaskBase::cyclicStoreCheck() { + if (not storesInitialized) { + initStoresIfPossible(); + if (not storesInitialized) { + TaskFactory::delayTask(400); + return false; + } + } else if (sdCardCheckCd.hasTimedOut()) { + if (not sdcMan.isSdCardUsable(std::nullopt)) { + // Might be due to imminent shutdown or SD card switch. + storesInitialized = false; + TaskFactory::delayTask(100); + return false; + } + sdCardCheckCd.resetTimer(); + } + return true; +} diff --git a/mission/tmtc/TmStoreTaskBase.h b/mission/tmtc/TmStoreTaskBase.h index b2f1f323..a1df1f5c 100644 --- a/mission/tmtc/TmStoreTaskBase.h +++ b/mission/tmtc/TmStoreTaskBase.h @@ -1,12 +1,16 @@ #ifndef MISSION_TMTC_TMSTORETASKBASE_H_ #define MISSION_TMTC_TMSTORETASKBASE_H_ +#include #include #include class TmStoreTaskBase : public SystemObject { public: - TmStoreTaskBase(object_id_t objectId, StorageManagerIF& ipcStore, VirtualChannel& channel); + TmStoreTaskBase(object_id_t objectId, StorageManagerIF& ipcStore, VirtualChannel& channel, + SdCardMountedIF& sdcMan); + + protected: /** * Handling for one store. Returns if anything was done. * @param store @@ -14,9 +18,19 @@ class TmStoreTaskBase : public SystemObject { */ bool handleOneStore(PersistentTmStoreWithTmQueue& store); - private: + /** + * Occasionally check whether SD card is okay to be used. If not, poll whether it is ready to + * be used again and re-initialize stores. Returns whether store is okay to be used. + */ + bool cyclicStoreCheck(); + + virtual void initStoresIfPossible() = 0; + StorageManagerIF& ipcStore; + Countdown sdCardCheckCd = Countdown(800); VirtualChannel& channel; + bool storesInitialized = false; + SdCardMountedIF& sdcMan; }; #endif /* MISSION_TMTC_TMSTORETASKBASE_H_ */ From fd943a99b6cc79e4dcbfcf846f79706700e04270 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 9 Mar 2023 20:18:19 +0100 Subject: [PATCH 044/112] remove old code --- mission/tmtc/PusTmFunnel.cpp | 52 ++---------------------------------- mission/tmtc/PusTmFunnel.h | 2 -- 2 files changed, 2 insertions(+), 52 deletions(-) diff --git a/mission/tmtc/PusTmFunnel.cpp b/mission/tmtc/PusTmFunnel.cpp index 691ccd46..bb134ca9 100644 --- a/mission/tmtc/PusTmFunnel.cpp +++ b/mission/tmtc/PusTmFunnel.cpp @@ -19,30 +19,6 @@ PusTmFunnel::~PusTmFunnel() = default; ReturnValue_t PusTmFunnel::performOperation(uint8_t) { CommandMessage cmdMessage; ReturnValue_t result; - /* - try { - result = okStore.handleCommandQueue(ipcStore, *this); - if (result != returnvalue::OK) { - sif::error << "PusTmFunnel::performOperation: Issue handling OK store command" << std::endl; - } - result = notOkStore.handleCommandQueue(ipcStore, *this); - if (result != returnvalue::OK) { - sif::error << "PusTmFunnel::performOperation: Issue handling NOT OK store command" - << std::endl; - } - result = hkStore.handleCommandQueue(ipcStore, *this); - if (result != returnvalue::OK) { - sif::error << "PusTmFunnel::performOperation: Issue handling HK store command" << std::endl; - } - result = miscStore.handleCommandQueue(ipcStore, *this); - if (result != returnvalue::OK) { - sif::error << "PusTmFunnel::performOperation: Issue handling MISC store command" << std::endl; - } - } catch (const std::bad_optional_access &e) { - sif::error << e.what() << "when handling TM store command" << std::endl; - } - */ - TmTcMessage currentMessage; unsigned int count = 0; result = tmQueue->receiveMessage(¤tMessage); @@ -53,7 +29,7 @@ ReturnValue_t PusTmFunnel::performOperation(uint8_t) { break; } count++; - if (count == 500) { + if (count == 1000) { sif::error << "PusTmFunnel: Possible message storm detected" << std::endl; break; } @@ -99,36 +75,12 @@ ReturnValue_t PusTmFunnel::handleTmPacket(TmTcMessage &message) { } } + // Send to registered live targets. return demultiplexLivePackets(origStoreId, packetData, size); - // TODO: Will be moved to own thread. - // bool sdcUsable = sdcMan.isSdCardUsable(std::nullopt); - // initStoresIfPossible(sdcUsable); - // if (sdcUsable) { - // miscStore.passPacket(packet); - // okStore.passPacket(packet); - // notOkStore.passPacket(packet); - // hkStore.passPacket(packet); - // } } const char *PusTmFunnel::getName() const { return "PUS TM Funnel"; } -void PusTmFunnel::initStoresIfPossible(bool sdCardUsable) { - // TODO: Those will be moved to own thread. - if (not storesInitialized and sdCardUsable and sdcMan.getCurrentMountPrefix() != nullptr) { - // miscStore.initializeTmStore(); - // okStore.initializeTmStore(); - // hkStore.initializeTmStore(); - // notOkStore.initializeTmStore(); - storesInitialized = true; - } -} - -ReturnValue_t PusTmFunnel::initialize() { - // initStoresIfPossible(sdcMan.isSdCardUsable(std::nullopt)); - return returnvalue::OK; -} - void PusTmFunnel::addPersistentTmStoreRouting(PusPacketFilter filter, MessageQueueId_t dest) { persistentTmMap.addRouting(filter, dest); } diff --git a/mission/tmtc/PusTmFunnel.h b/mission/tmtc/PusTmFunnel.h index 3c22afa2..6c1835d1 100644 --- a/mission/tmtc/PusTmFunnel.h +++ b/mission/tmtc/PusTmFunnel.h @@ -42,8 +42,6 @@ class PusTmFunnel : public TmFunnelBase { PusTmRouteByFilterHelper persistentTmMap; ReturnValue_t handleTmPacket(TmTcMessage &message); - void initStoresIfPossible(bool sdCardUsable); - ReturnValue_t initialize() override; }; #endif // FSFW_EXAMPLE_COMMON_PUSTMFUNNEL_H From cb71b8cfb27f992015e4f48dff6ffbc74b656e6b Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 9 Mar 2023 20:25:43 +0100 Subject: [PATCH 045/112] schedule the new components --- bsp_q7s/core/ObjectFactory.cpp | 10 +++++----- bsp_q7s/core/scheduling.cpp | 30 ++++++++++++++++++++++++++++++ common/config/eive/objects.h | 6 +++--- 3 files changed, 38 insertions(+), 8 deletions(-) diff --git a/bsp_q7s/core/ObjectFactory.cpp b/bsp_q7s/core/ObjectFactory.cpp index 721c5338..35a0fff1 100644 --- a/bsp_q7s/core/ObjectFactory.cpp +++ b/bsp_q7s/core/ObjectFactory.cpp @@ -779,19 +779,19 @@ ReturnValue_t ObjectFactory::createCcsdsComponents(CcsdsComponentArgs& args) { LINK_STATE); LogStores logStores(args.stores); // Core task which handles the LOG store and takes care of dumping it as TM using a VC directly - new PersistentLogTmStoreTask(objects::LOG_STORE_TASK, args.ipcStore, logStores, *vc, + new PersistentLogTmStoreTask(objects::LOG_STORE_AND_TM_TASK, args.ipcStore, logStores, *vc, *SdCardManager::instance()); vc = new VirtualChannel(objects::PTME_VC2_HK_TM, ccsds::VC2, "PTME VC2 HK TM", *ptme, LINK_STATE); // Core task which handles the HK store and takes care of dumping it as TM using a VC directly - new PersistentSingleTmStoreTask(objects::HK_STORE_TASK, args.ipcStore, *args.stores.hkStore, *vc, - *SdCardManager::instance()); + new PersistentSingleTmStoreTask(objects::HK_STORE_AND_TM_TASK, args.ipcStore, + *args.stores.hkStore, *vc, *SdCardManager::instance()); vc = new VirtualChannel(objects::PTME_VC3_CFDP_TM, ccsds::VC3, "PTME VC3 CFDP TM", *ptme, LINK_STATE); // Core task which handles the CFDP store and takes care of dumping it as TM using a VC directly - new PersistentSingleTmStoreTask(objects::CFDP_STORE_TASK, args.ipcStore, *args.stores.cfdpStore, - *vc, *SdCardManager::instance()); + new PersistentSingleTmStoreTask(objects::CFDP_STORE_AND_TM_TASK, args.ipcStore, + *args.stores.cfdpStore, *vc, *SdCardManager::instance()); ReturnValue_t result = (*args.ipCoreHandler)->connectModeTreeParent(satsystem::com::SUBSYSTEM); if (result != returnvalue::OK) { diff --git a/bsp_q7s/core/scheduling.cpp b/bsp_q7s/core/scheduling.cpp index ec47232d..9a7467b9 100644 --- a/bsp_q7s/core/scheduling.cpp +++ b/bsp_q7s/core/scheduling.cpp @@ -180,6 +180,32 @@ void scheduling::initTasks() { if (result != returnvalue::OK) { scheduling::printAddObjectError("PDEC Handler", objects::PDEC_HANDLER); } + + // All the TM store tasks run in permanent loops, frequency does not matter + PeriodicTaskIF* liveTmTask = + factory->createPeriodicTask("LIVE_TM", 60, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.0, nullptr); + result = liveTmTask->addComponent(objects::LIVE_TM_TASK); + if (result != returnvalue::OK) { + scheduling::printAddObjectError("LIVE_TM", objects::LIVE_TM_TASK); + } + PeriodicTaskIF* logTmTask = factory->createPeriodicTask( + "LOG_STORE_AND_TM", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.0, nullptr); + result = logTmTask->addComponent(objects::LOG_STORE_AND_TM_TASK); + if (result != returnvalue::OK) { + scheduling::printAddObjectError("LOG_STORE_AND_TM", objects::LOG_STORE_AND_TM_TASK); + } + PeriodicTaskIF* hkTmTask = factory->createPeriodicTask( + "HK_STORE_AND_TM", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.0, nullptr); + result = hkTmTask->addComponent(objects::HK_STORE_AND_TM_TASK); + if (result != returnvalue::OK) { + scheduling::printAddObjectError("HK_STORE_AND_TM", objects::HK_STORE_AND_TM_TASK); + } + PeriodicTaskIF* cfdpTmTask = factory->createPeriodicTask( + "CFDP_STORE_AND_TM", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.0, nullptr); + result = cfdpTmTask->addComponent(objects::CFDP_STORE_AND_TM_TASK); + if (result != returnvalue::OK) { + scheduling::printAddObjectError("CFDP_STORE_AND_TM", objects::CFDP_STORE_AND_TM_TASK); + } #endif /* OBSW_ADD_CCSDS_IP_CORE == 1 */ #if OBSW_ADD_CFDP_COMPONENTS == 1 @@ -369,6 +395,10 @@ void scheduling::initTasks() { genericSysTask->startTask(); #if OBSW_ADD_CCSDS_IP_CORES == 1 pdecHandlerTask->startTask(); + liveTmTask->startTask(); + logTmTask->startTask(); + hkTmTask->startTask(); + cfdpTmTask->startTask(); #endif /* OBSW_ADD_CCSDS_IP_CORES == 1 */ coreCtrlTask->startTask(); diff --git a/common/config/eive/objects.h b/common/config/eive/objects.h index f689caf9..00b509f2 100644 --- a/common/config/eive/objects.h +++ b/common/config/eive/objects.h @@ -169,9 +169,9 @@ enum commonObjects : uint32_t { CFDP_TM_STORE = 0x73030000, LIVE_TM_TASK = 0x73040000, - LOG_STORE_TASK = 0x73040001, - HK_STORE_TASK = 0x73040002, - CFDP_STORE_TASK = 0x73040003, + LOG_STORE_AND_TM_TASK = 0x73040001, + HK_STORE_AND_TM_TASK = 0x73040002, + CFDP_STORE_AND_TM_TASK = 0x73040003, // Other stuff THERMAL_TEMP_INSERTER = 0x90000003, From df3fa1701765452e0668de604d424e731b6edbc9 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 9 Mar 2023 20:31:19 +0100 Subject: [PATCH 046/112] remove some more code --- mission/tmtc/PersistentTmStore.cpp | 33 ------------------------------ mission/tmtc/PersistentTmStore.h | 1 - 2 files changed, 34 deletions(-) diff --git a/mission/tmtc/PersistentTmStore.cpp b/mission/tmtc/PersistentTmStore.cpp index 0fe96c65..c95ca9b9 100644 --- a/mission/tmtc/PersistentTmStore.cpp +++ b/mission/tmtc/PersistentTmStore.cpp @@ -222,39 +222,6 @@ ReturnValue_t PersistentTmStore::loadNextDumpFile() { return returnvalue::OK; } -// void PersistentTmStore::fileToPackets(const std::filesystem::path& path, uint32_t unixStamp) { -// store_address_t storeId; -// TmTcMessage message; -// size_t size = std::filesystem::file_size(path); -// if (size < 6) { -// // Can't even read the CCSDS header -// return; -// } -// std::ifstream ifile(path, std::ios::binary); -// ifile.read(reinterpret_cast(fileBuf.data()), static_cast(size)); -// size_t currentIdx = 0; -// while (currentIdx < size) { -// PusTmReader reader(&timeReader, fileBuf.data(), fileBuf.size()); -// // CRC check to fully ensure this is a valid TM -// ReturnValue_t result = reader.parseDataWithCrcCheck(); -// if (result == returnvalue::OK) { -// // TODO: Blow the data out to the VC directly. Use IF function to do this. -// // result = tmStore.addData(&storeId, fileBuf.data() + currentIdx, -// // reader.getFullPacketLen()); if (result != returnvalue::OK) { -// // continue; -// // } -// // funnel.sendPacketToLiveDestinations(storeId, message, fileBuf.data() + currentIdx, -// // reader.getFullPacketLen()); -// currentIdx += reader.getFullPacketLen(); -// } else { -// sif::error << "Parsing of PUS TM failed with code " << result << std::endl; -// triggerEvent(POSSIBLE_FILE_CORRUPTION, result, unixStamp); -// // Stop for now, do not really know where to continue and we do not trust the file anymore. -// break; -// } -// } -// } - ReturnValue_t PersistentTmStore::dumpNextPacket(DirectTmSinkIF& tmSink, size_t& dumpedLen) { if (state == State::IDLE) { return returnvalue::FAILED; diff --git a/mission/tmtc/PersistentTmStore.h b/mission/tmtc/PersistentTmStore.h index 34ad0ba0..e5d7111d 100644 --- a/mission/tmtc/PersistentTmStore.h +++ b/mission/tmtc/PersistentTmStore.h @@ -68,7 +68,6 @@ class PersistentTmStore : public TmStoreFrontendSimpleIF, public SystemObject { ReturnValue_t startDumpFromUpTo(uint32_t fromUnixSeconds, uint32_t upToUnixSeconds); ReturnValue_t dumpNextPacket(DirectTmSinkIF& tmSink, size_t& dumpedLen); - // ReturnValue_t passPacket(PusTmReader& reader); ReturnValue_t storePacket(PusTmReader& reader); protected: From 00e04e8b77a2c39b489ef9a9f4b5c29bfd695e64 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 9 Mar 2023 20:38:50 +0100 Subject: [PATCH 047/112] fix host build, fix in filter helper --- bsp_hosted/ObjectFactory.cpp | 6 +++++- mission/tmtc/CcsdsIpCoreHandler.cpp | 3 +-- mission/tmtc/PusTmRouteByFilterHelper.cpp | 2 +- 3 files changed, 7 insertions(+), 4 deletions(-) diff --git a/bsp_hosted/ObjectFactory.cpp b/bsp_hosted/ObjectFactory.cpp index 5ef9e2c2..eb633339 100644 --- a/bsp_hosted/ObjectFactory.cpp +++ b/bsp_hosted/ObjectFactory.cpp @@ -58,8 +58,12 @@ void ObjectFactory::produce(void* args) { Factory::setStaticFrameworkObjectIds(); PusTmFunnel* pusFunnel; CfdpTmFunnel* cfdpFunnel; + StorageManagerIF* tmStore; + StorageManagerIF* ipcStore; + PersistentTmStores persistentStores; auto sdcMan = new DummySdCardManager("/tmp"); - ObjectFactory::produceGenericObjects(nullptr, &pusFunnel, &cfdpFunnel, *sdcMan); + ObjectFactory::produceGenericObjects(nullptr, &pusFunnel, &cfdpFunnel, *sdcMan, &ipcStore, + &tmStore, persistentStores); auto* dummyGpioIF = new DummyGpioIF(); auto* dummySwitcher = new DummyPowerSwitcher(objects::PCDU_HANDLER, 18, 0); diff --git a/mission/tmtc/CcsdsIpCoreHandler.cpp b/mission/tmtc/CcsdsIpCoreHandler.cpp index ec6602cc..838af4c0 100644 --- a/mission/tmtc/CcsdsIpCoreHandler.cpp +++ b/mission/tmtc/CcsdsIpCoreHandler.cpp @@ -73,9 +73,8 @@ ReturnValue_t CcsdsIpCoreHandler::initialize() { #if OBSW_SYRLINKS_SIMULATED == 1 // Update data on rising edge - ptmeConfig->invertTxClock(false); + ptmeConfig.invertTxClock(false); linkState = LINK_UP; - forwardLinkstate(); #endif /* OBSW_SYRLINKS_SIMULATED == 1*/ return result; diff --git a/mission/tmtc/PusTmRouteByFilterHelper.cpp b/mission/tmtc/PusTmRouteByFilterHelper.cpp index 63b95733..15adde05 100644 --- a/mission/tmtc/PusTmRouteByFilterHelper.cpp +++ b/mission/tmtc/PusTmRouteByFilterHelper.cpp @@ -5,7 +5,7 @@ PusTmRouteByFilterHelper::PusTmRouteByFilterHelper() = default; bool PusTmRouteByFilterHelper::packetMatches(PusTmReader& reader, MessageQueueId_t& destination) { - for (const auto filterAndDest : routerMap) { + for (const auto& filterAndDest : routerMap) { if (filterAndDest.first.packetMatches(reader)) { destination = filterAndDest.second; return true; From 2374dea493611ed356c1769442a2ba14bbc61045 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 9 Mar 2023 20:44:55 +0100 Subject: [PATCH 048/112] return whether file was swapped --- mission/tmtc/PersistentTmStore.cpp | 4 +++- mission/tmtc/PersistentTmStore.h | 2 +- mission/tmtc/TmStoreTaskBase.cpp | 4 +++- 3 files changed, 7 insertions(+), 3 deletions(-) diff --git a/mission/tmtc/PersistentTmStore.cpp b/mission/tmtc/PersistentTmStore.cpp index c95ca9b9..abf7d159 100644 --- a/mission/tmtc/PersistentTmStore.cpp +++ b/mission/tmtc/PersistentTmStore.cpp @@ -222,7 +222,7 @@ ReturnValue_t PersistentTmStore::loadNextDumpFile() { return returnvalue::OK; } -ReturnValue_t PersistentTmStore::dumpNextPacket(DirectTmSinkIF& tmSink, size_t& dumpedLen) { +ReturnValue_t PersistentTmStore::dumpNextPacket(DirectTmSinkIF& tmSink, size_t& dumpedLen, bool& fileHasSwapped) { if (state == State::IDLE) { return returnvalue::FAILED; } @@ -239,6 +239,7 @@ ReturnValue_t PersistentTmStore::dumpNextPacket(DirectTmSinkIF& tmSink, size_t& dumpParams.currentSize += reader.getFullPacketLen(); dumpedLen = reader.getFullPacketLen(); if (dumpParams.currentSize >= dumpParams.fileSize) { + fileHasSwapped = true; return loadNextDumpFile(); } } else { @@ -248,6 +249,7 @@ ReturnValue_t PersistentTmStore::dumpNextPacket(DirectTmSinkIF& tmSink, size_t& // restore the file dump, but for now do not trust the file. dumpedLen = 0; std::remove(dumpParams.dirEntry.path().c_str()); + fileHasSwapped = true; return loadNextDumpFile(); } return returnvalue::OK; diff --git a/mission/tmtc/PersistentTmStore.h b/mission/tmtc/PersistentTmStore.h index e5d7111d..3274a64c 100644 --- a/mission/tmtc/PersistentTmStore.h +++ b/mission/tmtc/PersistentTmStore.h @@ -66,7 +66,7 @@ class PersistentTmStore : public TmStoreFrontendSimpleIF, public SystemObject { void deleteUpTo(uint32_t unixSeconds); ReturnValue_t startDumpFrom(uint32_t fromUnixSeconds); ReturnValue_t startDumpFromUpTo(uint32_t fromUnixSeconds, uint32_t upToUnixSeconds); - ReturnValue_t dumpNextPacket(DirectTmSinkIF& tmSink, size_t& dumpedLen); + ReturnValue_t dumpNextPacket(DirectTmSinkIF& tmSink, size_t& dumpedLen, bool& fileHasSwapped); ReturnValue_t storePacket(PusTmReader& reader); diff --git a/mission/tmtc/TmStoreTaskBase.cpp b/mission/tmtc/TmStoreTaskBase.cpp index 325dc77c..c0809d90 100644 --- a/mission/tmtc/TmStoreTaskBase.cpp +++ b/mission/tmtc/TmStoreTaskBase.cpp @@ -23,9 +23,11 @@ bool TmStoreTaskBase::handleOneStore(PersistentTmStoreWithTmQueue& store) { // Dump TMs when applicable if (store.getState() == PersistentTmStore::State::DUMPING) { size_t dumpedLen; + bool fileHasSwapped; // TODO: Maybe do a bit of a delay every 100-200 packets? + // TODO: We could continously dump until a file swap during active downlink.. // TODO: handle returnvalue? - result = store.dumpNextPacket(channel, dumpedLen); + result = store.dumpNextPacket(channel, dumpedLen, fileHasSwapped); if (result == returnvalue::OK) { dumpsPerformed = true; } From 9cb7cefb856540b841e7c7203623799d3e37ff2d Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 9 Mar 2023 20:50:54 +0100 Subject: [PATCH 049/112] format --- mission/tmtc/PersistentTmStore.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/mission/tmtc/PersistentTmStore.cpp b/mission/tmtc/PersistentTmStore.cpp index abf7d159..ccfe8821 100644 --- a/mission/tmtc/PersistentTmStore.cpp +++ b/mission/tmtc/PersistentTmStore.cpp @@ -222,7 +222,8 @@ ReturnValue_t PersistentTmStore::loadNextDumpFile() { return returnvalue::OK; } -ReturnValue_t PersistentTmStore::dumpNextPacket(DirectTmSinkIF& tmSink, size_t& dumpedLen, bool& fileHasSwapped) { +ReturnValue_t PersistentTmStore::dumpNextPacket(DirectTmSinkIF& tmSink, size_t& dumpedLen, + bool& fileHasSwapped) { if (state == State::IDLE) { return returnvalue::FAILED; } From dd8b6ced8f3c1c094390985c9e7cf86dbe3170c4 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 9 Mar 2023 20:51:22 +0100 Subject: [PATCH 050/112] set initial mode --- mission/system/tree/system.cpp | 1 + tmtc | 2 +- 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/mission/system/tree/system.cpp b/mission/system/tree/system.cpp index 215f1b02..242ed8ef 100644 --- a/mission/system/tree/system.cpp +++ b/mission/system/tree/system.cpp @@ -35,6 +35,7 @@ void satsystem::init() { ModeListEntry entry; buildSafeSequence(EIVE_SYSTEM, entry); buildIdleSequence(EIVE_SYSTEM, entry); + EIVE_SYSTEM.setInitialMode(acs::AcsMode::SAFE, 0); } EiveSystem satsystem::EIVE_SYSTEM = EiveSystem(objects::EIVE_SYSTEM, 12, 24); diff --git a/tmtc b/tmtc index bf158bee..b0f51072 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit bf158bee2d79c95de3ac2e38f4e7d977699711b1 +Subproject commit b0f51072b20e4835a3e2143d8b3fb40d14240bfb From f8d432f6eb780b5b9ee66ff37e607ea6b5e501b8 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 9 Mar 2023 20:55:28 +0100 Subject: [PATCH 051/112] initial mode is off now --- mission/system/tree/system.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/mission/system/tree/system.cpp b/mission/system/tree/system.cpp index 242ed8ef..a7814fa1 100644 --- a/mission/system/tree/system.cpp +++ b/mission/system/tree/system.cpp @@ -35,7 +35,7 @@ void satsystem::init() { ModeListEntry entry; buildSafeSequence(EIVE_SYSTEM, entry); buildIdleSequence(EIVE_SYSTEM, entry); - EIVE_SYSTEM.setInitialMode(acs::AcsMode::SAFE, 0); + EIVE_SYSTEM.setInitialMode(HasModesIF::MODE_OFF, 0); } EiveSystem satsystem::EIVE_SYSTEM = EiveSystem(objects::EIVE_SYSTEM, 12, 24); From c8fe1b13593a54252e7c1b5b75c6771302ef2cc8 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 9 Mar 2023 22:11:43 +0100 Subject: [PATCH 052/112] slightly longer idle delays for store tasks --- mission/tmtc/PersistentLogTmStoreTask.cpp | 2 +- mission/tmtc/PersistentSingleTmStoreTask.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/mission/tmtc/PersistentLogTmStoreTask.cpp b/mission/tmtc/PersistentLogTmStoreTask.cpp index 5e715ca0..674ca053 100644 --- a/mission/tmtc/PersistentLogTmStoreTask.cpp +++ b/mission/tmtc/PersistentLogTmStoreTask.cpp @@ -28,7 +28,7 @@ ReturnValue_t PersistentLogTmStoreTask::performOperation(uint8_t opCode) { someonesBusy = true; } if (not someonesBusy) { - TaskFactory::delayTask(5); + TaskFactory::delayTask(10); } } } diff --git a/mission/tmtc/PersistentSingleTmStoreTask.cpp b/mission/tmtc/PersistentSingleTmStoreTask.cpp index aaac7f6e..38a09b65 100644 --- a/mission/tmtc/PersistentSingleTmStoreTask.cpp +++ b/mission/tmtc/PersistentSingleTmStoreTask.cpp @@ -15,7 +15,7 @@ ReturnValue_t PersistentSingleTmStoreTask::performOperation(uint8_t opCode) { } bool busy = handleOneStore(storeWithQueue); if (not busy) { - TaskFactory::delayTask(5); + TaskFactory::delayTask(10); } } } From 55bd87abb6283ffec95d00fbbc0f8623827d8b7e Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 9 Mar 2023 23:33:53 +0100 Subject: [PATCH 053/112] smaller tweaks --- bsp_q7s/core/scheduling.cpp | 1 - bsp_q7s/fs/SdCardManager.h | 2 +- linux/devices/ImtqPollingTask.cpp | 5 +++++ mission/system/objects/AcsSubsystem.cpp | 1 + 4 files changed, 7 insertions(+), 2 deletions(-) diff --git a/bsp_q7s/core/scheduling.cpp b/bsp_q7s/core/scheduling.cpp index ec47232d..616e7fe9 100644 --- a/bsp_q7s/core/scheduling.cpp +++ b/bsp_q7s/core/scheduling.cpp @@ -235,7 +235,6 @@ void scheduling::initTasks() { PeriodicTaskIF* acsSysTask = factory->createPeriodicTask( "ACS_SYS_TASK", 55, PeriodicTaskIF::MINIMUM_STACK_SIZE * 2, 0.4, missedDeadlineFunc); - static_cast(acsSysTask); result = acsSysTask->addComponent(objects::ACS_SUBSYSTEM); if (result != returnvalue::OK) { scheduling::printAddObjectError("ACS_SUBSYSTEM", objects::ACS_SUBSYSTEM); diff --git a/bsp_q7s/fs/SdCardManager.h b/bsp_q7s/fs/SdCardManager.h index 1cd09d7d..874fd786 100644 --- a/bsp_q7s/fs/SdCardManager.h +++ b/bsp_q7s/fs/SdCardManager.h @@ -227,7 +227,7 @@ class SdCardManager : public SystemObject, public SdCardMountedIF { MutexIF* prefLock = nullptr; MutexIF* defaultLock = nullptr; static constexpr MutexIF::TimeoutType LOCK_TYPE = MutexIF::TimeoutType::WAITING; - static constexpr uint32_t SD_LOCK_TIMEOUT = 250; + static constexpr uint32_t SD_LOCK_TIMEOUT = 400; static constexpr uint32_t OTHER_TIMEOUT = 20; static constexpr char LOCK_CTX[] = "SdCardManager"; diff --git a/linux/devices/ImtqPollingTask.cpp b/linux/devices/ImtqPollingTask.cpp index ad4b80ac..c15acd29 100644 --- a/linux/devices/ImtqPollingTask.cpp +++ b/linux/devices/ImtqPollingTask.cpp @@ -120,6 +120,11 @@ void ImtqPollingTask::handleMeasureStep() { } } + // The I2C IP core on EIVE sometimes glitches out. Send start MTM measurement twice. + cmdBuf[0] = imtq::CC::START_MTM_MEASUREMENT; + if (i2cCmdExecMeasure(imtq::CC::START_MTM_MEASUREMENT) != returnvalue::OK) { + return; + } cmdBuf[0] = imtq::CC::START_MTM_MEASUREMENT; if (i2cCmdExecMeasure(imtq::CC::START_MTM_MEASUREMENT) != returnvalue::OK) { return; diff --git a/mission/system/objects/AcsSubsystem.cpp b/mission/system/objects/AcsSubsystem.cpp index e4969ac1..3bab5273 100644 --- a/mission/system/objects/AcsSubsystem.cpp +++ b/mission/system/objects/AcsSubsystem.cpp @@ -56,6 +56,7 @@ ReturnValue_t AcsSubsystem::initialize() { } void AcsSubsystem::performChildOperation() { + // sif::debug << "ACS system thread running" << std::endl; handleEventMessages(); return Subsystem::performChildOperation(); } From 8b26d13070a314fb5bcdd712a691069762fa2d29 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 10 Mar 2023 02:05:51 +0100 Subject: [PATCH 054/112] the sd stuff is evil.. --- bsp_q7s/core/ObjectFactory.cpp | 2 +- bsp_q7s/core/ObjectFactory.h | 7 ++++++- bsp_q7s/core/scheduling.cpp | 13 ++++++------ bsp_q7s/fmObjectFactory.cpp | 3 ++- bsp_q7s/fs/SdCardManager.cpp | 1 + common/config/eive/definitions.h | 11 ++++++---- mission/core/GenericFactory.cpp | 17 +++++++++------- mission/tmtc/LiveTmTask.cpp | 16 +++++++++++---- mission/tmtc/LiveTmTask.h | 9 ++++++++- mission/tmtc/PersistentLogTmStoreTask.cpp | 15 +++++++------- mission/tmtc/PersistentLogTmStoreTask.h | 3 ++- mission/tmtc/PersistentSingleTmStoreTask.cpp | 14 ++++++++++--- mission/tmtc/PersistentSingleTmStoreTask.h | 3 ++- mission/tmtc/PusTmFunnel.cpp | 2 +- mission/tmtc/TmStoreTaskBase.cpp | 21 +++++++++++--------- mission/tmtc/TmStoreTaskBase.h | 4 ++-- mission/tmtc/VirtualChannelWithQueue.cpp | 8 ++++---- mission/tmtc/VirtualChannelWithQueue.h | 2 +- 18 files changed, 96 insertions(+), 55 deletions(-) diff --git a/bsp_q7s/core/ObjectFactory.cpp b/bsp_q7s/core/ObjectFactory.cpp index 35a0fff1..b3a9e751 100644 --- a/bsp_q7s/core/ObjectFactory.cpp +++ b/bsp_q7s/core/ObjectFactory.cpp @@ -772,7 +772,7 @@ ReturnValue_t ObjectFactory::createCcsdsComponents(CcsdsComponentArgs& args) { new VirtualChannelWithQueue(objects::PTME_VC0_LIVE_TM, ccsds::VC0, "PTME VC0 LIVE TM", *ptme, LINK_STATE, args.tmStore, 500); args.liveDestination = vcWithQueue; - new LiveTmTask(objects::LIVE_TM_TASK, *vcWithQueue); + new LiveTmTask(objects::LIVE_TM_TASK, args.pusFunnel, args.cfdpFunnel, *vcWithQueue); // Set up log store. auto* vc = new VirtualChannel(objects::PTME_VC1_LOG_TM, ccsds::VC1, "PTME VC1 LOG TM", *ptme, diff --git a/bsp_q7s/core/ObjectFactory.h b/bsp_q7s/core/ObjectFactory.h index 26433917..7b713005 100644 --- a/bsp_q7s/core/ObjectFactory.h +++ b/bsp_q7s/core/ObjectFactory.h @@ -26,16 +26,21 @@ namespace ObjectFactory { struct CcsdsComponentArgs { CcsdsComponentArgs(LinuxLibgpioIF& gpioIF, StorageManagerIF& ipcStore, StorageManagerIF& tmStore, - PersistentTmStores& stores, CcsdsIpCoreHandler** ipCoreHandler) + PersistentTmStores& stores, PusTmFunnel& pusFunnel, CfdpTmFunnel& cfdpFunnel, + CcsdsIpCoreHandler** ipCoreHandler) : gpioComIF(gpioIF), ipcStore(ipcStore), tmStore(tmStore), stores(stores), + pusFunnel(pusFunnel), + cfdpFunnel(cfdpFunnel), ipCoreHandler(ipCoreHandler) {} LinuxLibgpioIF& gpioComIF; StorageManagerIF& ipcStore; StorageManagerIF& tmStore; PersistentTmStores& stores; + PusTmFunnel& pusFunnel; + CfdpTmFunnel& cfdpFunnel; CcsdsIpCoreHandler** ipCoreHandler; AcceptsTelemetryIF* liveDestination = nullptr; }; diff --git a/bsp_q7s/core/scheduling.cpp b/bsp_q7s/core/scheduling.cpp index 9a7467b9..20885541 100644 --- a/bsp_q7s/core/scheduling.cpp +++ b/bsp_q7s/core/scheduling.cpp @@ -116,10 +116,10 @@ void scheduling::initTasks() { if (result != returnvalue::OK) { scheduling::printAddObjectError("CFDP_DISTRIBUTOR", objects::CFDP_DISTRIBUTOR); } - result = tmTcDistributor->addComponent(objects::TM_FUNNEL); - if (result != returnvalue::OK) { - scheduling::printAddObjectError("TM_FUNNEL", objects::TM_FUNNEL); - } + // result = tmTcDistributor->addComponent(objects::TM_FUNNEL); + // if (result != returnvalue::OK) { + // scheduling::printAddObjectError("TM_FUNNEL", objects::TM_FUNNEL); + // } #if OBSW_ADD_TCPIP_SERVERS == 1 #if OBSW_ADD_TMTC_UDP_SERVER == 1 @@ -181,6 +181,7 @@ void scheduling::initTasks() { scheduling::printAddObjectError("PDEC Handler", objects::PDEC_HANDLER); } +#endif /* OBSW_ADD_CCSDS_IP_CORE == 1 */ // All the TM store tasks run in permanent loops, frequency does not matter PeriodicTaskIF* liveTmTask = factory->createPeriodicTask("LIVE_TM", 60, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.0, nullptr); @@ -206,7 +207,6 @@ void scheduling::initTasks() { if (result != returnvalue::OK) { scheduling::printAddObjectError("CFDP_STORE_AND_TM", objects::CFDP_STORE_AND_TM_TASK); } -#endif /* OBSW_ADD_CCSDS_IP_CORE == 1 */ #if OBSW_ADD_CFDP_COMPONENTS == 1 PeriodicTaskIF* cfdpTask = factory->createPeriodicTask( @@ -261,7 +261,6 @@ void scheduling::initTasks() { PeriodicTaskIF* acsSysTask = factory->createPeriodicTask( "ACS_SYS_TASK", 55, PeriodicTaskIF::MINIMUM_STACK_SIZE * 2, 0.4, missedDeadlineFunc); - static_cast(acsSysTask); result = acsSysTask->addComponent(objects::ACS_SUBSYSTEM); if (result != returnvalue::OK) { scheduling::printAddObjectError("ACS_SUBSYSTEM", objects::ACS_SUBSYSTEM); @@ -395,11 +394,11 @@ void scheduling::initTasks() { genericSysTask->startTask(); #if OBSW_ADD_CCSDS_IP_CORES == 1 pdecHandlerTask->startTask(); +#endif /* OBSW_ADD_CCSDS_IP_CORES == 1 */ liveTmTask->startTask(); logTmTask->startTask(); hkTmTask->startTask(); cfdpTmTask->startTask(); -#endif /* OBSW_ADD_CCSDS_IP_CORES == 1 */ coreCtrlTask->startTask(); #if OBSW_ADD_SA_DEPL == 1 diff --git a/bsp_q7s/fmObjectFactory.cpp b/bsp_q7s/fmObjectFactory.cpp index 390e4e8c..3aab4409 100644 --- a/bsp_q7s/fmObjectFactory.cpp +++ b/bsp_q7s/fmObjectFactory.cpp @@ -77,7 +77,8 @@ void ObjectFactory::produce(void* args) { #endif /* OBSW_ADD_STAR_TRACKER == 1 */ #if OBSW_ADD_CCSDS_IP_CORES == 1 CcsdsIpCoreHandler* ipCoreHandler = nullptr; - CcsdsComponentArgs ccsdsArgs(*gpioComIF, *ipcStore, *tmStore, stores, &ipCoreHandler); + CcsdsComponentArgs ccsdsArgs(*gpioComIF, *ipcStore, *tmStore, stores, *pusFunnel, *cfdpFunnel, + &ipCoreHandler); createCcsdsComponents(ccsdsArgs); #if OBSW_TM_TO_PTME == 1 if (ccsdsArgs.liveDestination != nullptr) { diff --git a/bsp_q7s/fs/SdCardManager.cpp b/bsp_q7s/fs/SdCardManager.cpp index fa46f8e0..3eead2ec 100644 --- a/bsp_q7s/fs/SdCardManager.cpp +++ b/bsp_q7s/fs/SdCardManager.cpp @@ -2,6 +2,7 @@ #include #include +#include #include #include diff --git a/common/config/eive/definitions.h b/common/config/eive/definitions.h index 2b1292b3..cbd66e41 100644 --- a/common/config/eive/definitions.h +++ b/common/config/eive/definitions.h @@ -45,10 +45,13 @@ static constexpr uint32_t SA_DEPL_MAX_BURN_TIME = 180; static constexpr uint32_t CCSDS_HANDLER_QUEUE_SIZE = 50; static constexpr uint8_t NUMBER_OF_VIRTUAL_CHANNELS = 4; -static constexpr uint8_t VC0_QUEUE_SIZE = 80; -static constexpr uint8_t VC1_QUEUE_SIZE = 80; -static constexpr uint8_t VC2_QUEUE_SIZE = 50; -static constexpr uint8_t VC3_QUEUE_SIZE = 50; +static constexpr uint32_t VC0_LIVE_TM_QUEUE_SIZE = 300; +// There are three individual log stores! +static constexpr uint32_t MISC_STORE_QUEUE_SIZE = 200; +static constexpr uint32_t OK_STORE_QUEUE_SIZE = 350; +static constexpr uint32_t NOK_STORE_QUEUE_SIZE = 350; +static constexpr uint32_t HK_STORE_QUEUE_SIZE = 300; +static constexpr uint32_t CFDP_STORE_QUEUE_SIZE = 300; static constexpr uint32_t MAX_PUS_FUNNEL_QUEUE_DEPTH = 100; diff --git a/mission/core/GenericFactory.cpp b/mission/core/GenericFactory.cpp index 77364a4c..2f7beb8a 100644 --- a/mission/core/GenericFactory.cpp +++ b/mission/core/GenericFactory.cpp @@ -160,7 +160,8 @@ void ObjectFactory::produceGenericObjects(HealthTableIF** healthTable_, PusTmFun PersistentTmStoreArgs storeArgs(objects::MISC_TM_STORE, "tm", "misc", RolloverInterval::HOURLY, 2, **tmStore, sdcMan); - stores.miscStore = new PersistentTmStoreWithTmQueue(storeArgs, "MISC STORE", 500); + stores.miscStore = + new PersistentTmStoreWithTmQueue(storeArgs, "MISC STORE", config::MISC_STORE_QUEUE_SIZE); (*pusFunnel) ->addPersistentTmStoreRouting(filters::miscFilter(), stores.miscStore->getReportReceptionQueue(0)); @@ -171,7 +172,8 @@ void ObjectFactory::produceGenericObjects(HealthTableIF** healthTable_, PusTmFun { PersistentTmStoreArgs storeArgs(objects::OK_TM_STORE, "tm", "ok", RolloverInterval::MINUTELY, 30, **tmStore, sdcMan); - stores.okStore = new PersistentTmStoreWithTmQueue(storeArgs, "OK STORE", 500); + stores.okStore = + new PersistentTmStoreWithTmQueue(storeArgs, "OK STORE", config::OK_STORE_QUEUE_SIZE); (*pusFunnel) ->addPersistentTmStoreRouting(filters::okFilter(), stores.okStore->getReportReceptionQueue(0)); @@ -182,7 +184,8 @@ void ObjectFactory::produceGenericObjects(HealthTableIF** healthTable_, PusTmFun { PersistentTmStoreArgs storeArgs(objects::NOT_OK_TM_STORE, "tm", "nok", RolloverInterval::MINUTELY, 30, **tmStore, sdcMan); - stores.notOkStore = new PersistentTmStoreWithTmQueue(storeArgs, "NOT OK STORE", 500); + stores.notOkStore = + new PersistentTmStoreWithTmQueue(storeArgs, "NOT OK STORE", config::NOK_STORE_QUEUE_SIZE); (*pusFunnel) ->addPersistentTmStoreRouting(filters::notOkFilter(), stores.notOkStore->getReportReceptionQueue(0)); @@ -193,7 +196,8 @@ void ObjectFactory::produceGenericObjects(HealthTableIF** healthTable_, PusTmFun { PersistentTmStoreArgs storeArgs(objects::HK_TM_STORE, "tm", "hk", RolloverInterval::MINUTELY, 15, **tmStore, sdcMan); - stores.hkStore = new PersistentTmStoreWithTmQueue(storeArgs, "HK STORE", 500); + stores.hkStore = + new PersistentTmStoreWithTmQueue(storeArgs, "HK STORE", config::HK_STORE_QUEUE_SIZE); (*pusFunnel) ->addPersistentTmStoreRouting(filters::hkFilter(), stores.hkStore->getReportReceptionQueue(0)); @@ -204,7 +208,8 @@ void ObjectFactory::produceGenericObjects(HealthTableIF** healthTable_, PusTmFun { PersistentTmStoreArgs storeArgs(objects::CFDP_TM_STORE, "tm", "cfdp", RolloverInterval::MINUTELY, 30, **tmStore, sdcMan); - stores.cfdpStore = new PersistentTmStoreWithTmQueue(storeArgs, "CFDP STORE", 500); + stores.cfdpStore = + new PersistentTmStoreWithTmQueue(storeArgs, "CFDP STORE", config::CFDP_STORE_QUEUE_SIZE); (*pusFunnel) ->addPersistentTmStoreRouting(filters::cfdpFilter(), @@ -221,8 +226,6 @@ void ObjectFactory::produceGenericObjects(HealthTableIF** healthTable_, PusTmFun (*pusFunnel)->addLiveDestination("TCP Server", *tcpBridge, 0); #endif #endif - // Every TM packet goes through this funnel - new TmFunnelHandler(objects::TM_FUNNEL, **pusFunnel, **cfdpFunnel); // PUS service stack new Service1TelecommandVerification(objects::PUS_SERVICE_1_VERIFICATION, config::EIVE_PUS_APID, diff --git a/mission/tmtc/LiveTmTask.cpp b/mission/tmtc/LiveTmTask.cpp index 723ed26d..53a9f04a 100644 --- a/mission/tmtc/LiveTmTask.cpp +++ b/mission/tmtc/LiveTmTask.cpp @@ -1,16 +1,24 @@ #include "LiveTmTask.h" #include +#include -LiveTmTask::LiveTmTask(object_id_t objectId, VirtualChannelWithQueue& channel) - : SystemObject(objectId), channel(channel) {} +LiveTmTask::LiveTmTask(object_id_t objectId, PusTmFunnel& pusFunnel, CfdpTmFunnel& cfdpFunnel, + VirtualChannelWithQueue& channel) + : SystemObject(objectId), pusFunnel(pusFunnel), cfdpFunnel(cfdpFunnel), channel(channel) {} ReturnValue_t LiveTmTask::performOperation(uint8_t opCode) { while (true) { + // The funnel tasks are scheduled here directly as well. ReturnValue_t result = channel.sendNextTm(); if (result == MessageQueueIF::EMPTY) { - // 5 ms IDLE delay. Might tweak this in the future. - TaskFactory::delayTask(5); + if (tmFunnelCd.hasTimedOut()) { + pusFunnel.performOperation(0); + cfdpFunnel.performOperation(0); + tmFunnelCd.resetTimer(); + } + // 40 ms IDLE delay. Might tweak this in the future. + TaskFactory::delayTask(40); } } } diff --git a/mission/tmtc/LiveTmTask.h b/mission/tmtc/LiveTmTask.h index 598b1379..a0ca6b83 100644 --- a/mission/tmtc/LiveTmTask.h +++ b/mission/tmtc/LiveTmTask.h @@ -3,15 +3,22 @@ #include #include +#include +#include +#include #include class LiveTmTask : public SystemObject, public ExecutableObjectIF { public: - LiveTmTask(object_id_t objectId, VirtualChannelWithQueue& channel); + LiveTmTask(object_id_t objectId, PusTmFunnel& pusFunnel, CfdpTmFunnel& cfdpFunnel, + VirtualChannelWithQueue& channel); ReturnValue_t performOperation(uint8_t opCode) override; private: + Countdown tmFunnelCd = Countdown(100); + PusTmFunnel& pusFunnel; + CfdpTmFunnel& cfdpFunnel; VirtualChannelWithQueue& channel; }; diff --git a/mission/tmtc/PersistentLogTmStoreTask.cpp b/mission/tmtc/PersistentLogTmStoreTask.cpp index 674ca053..75bea255 100644 --- a/mission/tmtc/PersistentLogTmStoreTask.cpp +++ b/mission/tmtc/PersistentLogTmStoreTask.cpp @@ -1,6 +1,7 @@ #include "PersistentLogTmStoreTask.h" #include +#include PersistentLogTmStoreTask::PersistentLogTmStoreTask(object_id_t objectId, StorageManagerIF& ipcStore, LogStores stores, VirtualChannel& channel, @@ -14,30 +15,30 @@ ReturnValue_t PersistentLogTmStoreTask::performOperation(uint8_t opCode) { } bool someonesBusy = false; bool busy = false; - busy = handleOneStore(stores.okStore); + busy = handleOneStore(stores.okStore, tcHandlingCd); if (busy) { someonesBusy = true; } - busy = handleOneStore(stores.notOkStore); + busy = handleOneStore(stores.notOkStore, tcHandlingCd); if (busy) { someonesBusy = true; } - - busy = handleOneStore(stores.miscStore); + busy = handleOneStore(stores.miscStore, tcHandlingCd); if (busy) { someonesBusy = true; } if (not someonesBusy) { - TaskFactory::delayTask(10); + TaskFactory::delayTask(40); } } } -void PersistentLogTmStoreTask::initStoresIfPossible() { +bool PersistentLogTmStoreTask::initStoresIfPossible() { if (sdcMan.isSdCardUsable(std::nullopt)) { stores.okStore.initializeTmStore(); stores.miscStore.initializeTmStore(); stores.notOkStore.initializeTmStore(); - storesInitialized = true; + return true; } + return false; } diff --git a/mission/tmtc/PersistentLogTmStoreTask.h b/mission/tmtc/PersistentLogTmStoreTask.h index e106bd12..fc4242db 100644 --- a/mission/tmtc/PersistentLogTmStoreTask.h +++ b/mission/tmtc/PersistentLogTmStoreTask.h @@ -28,8 +28,9 @@ class PersistentLogTmStoreTask : public TmStoreTaskBase, public ExecutableObject private: LogStores stores; + Countdown tcHandlingCd = Countdown(400); - void initStoresIfPossible(); + bool initStoresIfPossible(); }; #endif /* MISSION_TMTC_PERSISTENTLOGTMSTORETASK_H_ */ diff --git a/mission/tmtc/PersistentSingleTmStoreTask.cpp b/mission/tmtc/PersistentSingleTmStoreTask.cpp index 38a09b65..3cd8da37 100644 --- a/mission/tmtc/PersistentSingleTmStoreTask.cpp +++ b/mission/tmtc/PersistentSingleTmStoreTask.cpp @@ -1,4 +1,5 @@ #include +#include #include PersistentSingleTmStoreTask::PersistentSingleTmStoreTask(object_id_t objectId, @@ -10,14 +11,21 @@ PersistentSingleTmStoreTask::PersistentSingleTmStoreTask(object_id_t objectId, ReturnValue_t PersistentSingleTmStoreTask::performOperation(uint8_t opCode) { while (true) { + // Delay done by the check if (not cyclicStoreCheck()) { continue; } - bool busy = handleOneStore(storeWithQueue); + bool busy = handleOneStore(storeWithQueue, tcHandlingCd); if (not busy) { - TaskFactory::delayTask(10); + TaskFactory::delayTask(40); } } } -void PersistentSingleTmStoreTask::initStoresIfPossible() {} +bool PersistentSingleTmStoreTask::initStoresIfPossible() { + if (sdcMan.isSdCardUsable(std::nullopt)) { + storeWithQueue.initializeTmStore(); + return true; + } + return false; +} diff --git a/mission/tmtc/PersistentSingleTmStoreTask.h b/mission/tmtc/PersistentSingleTmStoreTask.h index 012ba8e8..d7a021d1 100644 --- a/mission/tmtc/PersistentSingleTmStoreTask.h +++ b/mission/tmtc/PersistentSingleTmStoreTask.h @@ -17,8 +17,9 @@ class PersistentSingleTmStoreTask : public TmStoreTaskBase, public ExecutableObj private: PersistentTmStoreWithTmQueue& storeWithQueue; + Countdown tcHandlingCd = Countdown(400); - void initStoresIfPossible(); + bool initStoresIfPossible(); }; #endif /* MISSION_TMTC_PERSISTENTSINGLETMSTORETASK_H_ */ diff --git a/mission/tmtc/PusTmFunnel.cpp b/mission/tmtc/PusTmFunnel.cpp index bb134ca9..69d60a52 100644 --- a/mission/tmtc/PusTmFunnel.cpp +++ b/mission/tmtc/PusTmFunnel.cpp @@ -66,8 +66,8 @@ ReturnValue_t PusTmFunnel::handleTmPacket(TmTcMessage &message) { MessageQueueId_t destination; if (persistentTmMap.packetMatches(packet, destination)) { store_address_t storageId; - TmTcMessage msg(storageId); result = tmStore.addData(&storageId, packetData, size); + TmTcMessage msg(storageId); if (result != returnvalue::OK) { sif::error << "PusLiveDemux::handlePacket: Store too full to create data copy" << std::endl; } else { diff --git a/mission/tmtc/TmStoreTaskBase.cpp b/mission/tmtc/TmStoreTaskBase.cpp index c0809d90..e234af1e 100644 --- a/mission/tmtc/TmStoreTaskBase.cpp +++ b/mission/tmtc/TmStoreTaskBase.cpp @@ -1,25 +1,22 @@ #include "TmStoreTaskBase.h" #include +#include TmStoreTaskBase::TmStoreTaskBase(object_id_t objectId, StorageManagerIF& ipcStore, VirtualChannel& channel, SdCardMountedIF& sdcMan) : SystemObject(objectId), ipcStore(ipcStore), channel(channel), sdcMan(sdcMan) {} -bool TmStoreTaskBase::handleOneStore(PersistentTmStoreWithTmQueue& store) { +bool TmStoreTaskBase::handleOneStore(PersistentTmStoreWithTmQueue& store, Countdown& tcHandlingCd) { + ReturnValue_t result; bool tmToStoreReceived = true; bool tcRequestReceived = true; bool dumpsPerformed = false; // Store TM persistently - ReturnValue_t result = store.handleNextTm(); - if (result == MessageQueueIF::NO_QUEUE) { + result = store.handleNextTm(); + if (result == MessageQueueIF::EMPTY) { tmToStoreReceived = false; } - // Handle TC requests, for example deletion or retrieval requests. - result = store.handleCommandQueue(ipcStore); - if (result == MessageQueueIF::NO_QUEUE) { - tcRequestReceived = false; - } // Dump TMs when applicable if (store.getState() == PersistentTmStore::State::DUMPING) { size_t dumpedLen; @@ -31,6 +28,12 @@ bool TmStoreTaskBase::handleOneStore(PersistentTmStoreWithTmQueue& store) { if (result == returnvalue::OK) { dumpsPerformed = true; } + } else { + // Handle TC requests, for example deletion or retrieval requests. + result = store.handleCommandQueue(ipcStore); + if (result == MessageQueueIF::EMPTY) { + tcRequestReceived = false; + } } if (tcRequestReceived or tmToStoreReceived or dumpsPerformed) { return true; @@ -40,7 +43,7 @@ bool TmStoreTaskBase::handleOneStore(PersistentTmStoreWithTmQueue& store) { bool TmStoreTaskBase::cyclicStoreCheck() { if (not storesInitialized) { - initStoresIfPossible(); + storesInitialized = initStoresIfPossible(); if (not storesInitialized) { TaskFactory::delayTask(400); return false; diff --git a/mission/tmtc/TmStoreTaskBase.h b/mission/tmtc/TmStoreTaskBase.h index a1df1f5c..16042de6 100644 --- a/mission/tmtc/TmStoreTaskBase.h +++ b/mission/tmtc/TmStoreTaskBase.h @@ -16,7 +16,7 @@ class TmStoreTaskBase : public SystemObject { * @param store * @return */ - bool handleOneStore(PersistentTmStoreWithTmQueue& store); + bool handleOneStore(PersistentTmStoreWithTmQueue& store, Countdown& tcHandlingCd); /** * Occasionally check whether SD card is okay to be used. If not, poll whether it is ready to @@ -24,7 +24,7 @@ class TmStoreTaskBase : public SystemObject { */ bool cyclicStoreCheck(); - virtual void initStoresIfPossible() = 0; + virtual bool initStoresIfPossible() = 0; StorageManagerIF& ipcStore; Countdown sdCardCheckCd = Countdown(800); diff --git a/mission/tmtc/VirtualChannelWithQueue.cpp b/mission/tmtc/VirtualChannelWithQueue.cpp index 630552cb..884dbf89 100644 --- a/mission/tmtc/VirtualChannelWithQueue.cpp +++ b/mission/tmtc/VirtualChannelWithQueue.cpp @@ -11,7 +11,7 @@ VirtualChannelWithQueue::VirtualChannelWithQueue(object_id_t objectId, uint8_t v const char* vcName, PtmeIF& ptme, const std::atomic_bool& linkStateProvider, StorageManagerIF& tmStore, uint32_t tmQueueDepth) - : VirtualChannel(objectId, vcId, vcName, ptme, linkStateProvider) { + : VirtualChannel(objectId, vcId, vcName, ptme, linkStateProvider), tmStore(tmStore) { auto mqArgs = MqArgs(getObjectId(), reinterpret_cast(getVcid())); tmQueue = QueueFactory::instance()->createMessageQueue( tmQueueDepth, MessageQueueMessage::MAX_MESSAGE_SIZE, &mqArgs); @@ -28,16 +28,16 @@ ReturnValue_t VirtualChannelWithQueue::sendNextTm() { store_address_t storeId = message.getStorageId(); const uint8_t* data = nullptr; size_t size = 0; - result = tmStore->getData(storeId, &data, &size); + result = tmStore.getData(storeId, &data, &size); if (result != returnvalue::OK) { sif::warning << "VirtualChannel::performOperation: Failed to read data from TM store" << std::endl; - tmStore->deleteData(storeId); + tmStore.deleteData(storeId); return result; } write(data, size); - tmStore->deleteData(storeId); + tmStore.deleteData(storeId); if (result != returnvalue::OK) { return result; } diff --git a/mission/tmtc/VirtualChannelWithQueue.h b/mission/tmtc/VirtualChannelWithQueue.h index fdd0fca4..0c060a06 100644 --- a/mission/tmtc/VirtualChannelWithQueue.h +++ b/mission/tmtc/VirtualChannelWithQueue.h @@ -38,5 +38,5 @@ class VirtualChannelWithQueue : public VirtualChannel, public AcceptsTelemetryIF private: MessageQueueIF* tmQueue = nullptr; - StorageManagerIF* tmStore = nullptr; + StorageManagerIF& tmStore; }; From fae83a0fca90c23a9ae2918ae1d3cef29fd94ea4 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 10 Mar 2023 02:29:28 +0100 Subject: [PATCH 055/112] this should avoid lock issues al together --- bsp_q7s/core/CoreController.cpp | 25 +++++---- bsp_q7s/fs/SdCardManager.cpp | 89 ++++++++++++++++----------------- bsp_q7s/fs/SdCardManager.h | 10 ++-- 3 files changed, 65 insertions(+), 59 deletions(-) diff --git a/bsp_q7s/core/CoreController.cpp b/bsp_q7s/core/CoreController.cpp index f51f6bf9..d5023111 100644 --- a/bsp_q7s/core/CoreController.cpp +++ b/bsp_q7s/core/CoreController.cpp @@ -42,6 +42,11 @@ CoreController::CoreController(object_id_t objectId) if (not BLOCKING_SD_INIT) { sdcMan->setBlocking(false); } + Stopwatch watch; + sdcMan->updateSdCardStateFile(true); + sdcMan->updateSdStatePair(); + SdCardManager::SdStatePair sdStates; + sdcMan->getSdCardsStatus(sdStates); auto sdCard = sdcMan->getPreferredSdCard(); if (not sdCard.has_value()) { sif::error << "CoreController::initializeAfterTaskCreation: " @@ -50,7 +55,11 @@ CoreController::CoreController(object_id_t objectId) sdCard = sd::SdCard::SLOT_0; } sdInfo.active = sdCard.value(); - sdcMan->setActiveSdCard(sdInfo.active); + if (sdStates.first == sd::SdState::MOUNTED) { + sdcMan->setActiveSdCard(sd::SdCard::SLOT_0); + } else if (sdStates.second == sd::SdState::MOUNTED) { + sdcMan->setActiveSdCard(sd::SdCard::SLOT_1); + } currMntPrefix = sdcMan->getCurrentMountPrefix(); getCurrentBootCopy(CURRENT_CHIP, CURRENT_COPY); @@ -314,7 +323,7 @@ ReturnValue_t CoreController::checkModeCommand(Mode_t mode, Submode_t submode, ReturnValue_t CoreController::initSdCardBlocking() { // Create update status file - ReturnValue_t result = sdcMan->updateSdCardStateFile(); + ReturnValue_t result = sdcMan->updateSdCardStateFile(true); if (result != returnvalue::OK) { sif::warning << "CoreController::initialize: Updating SD card state file failed" << std::endl; } @@ -334,7 +343,7 @@ ReturnValue_t CoreController::initSdCardBlocking() { << static_cast(sdInfo.active) << std::endl; result = sdColdRedundantBlockingInit(); // Update status file - sdcMan->updateSdCardStateFile(); + sdcMan->updateSdCardStateFile(true); return result; } if (sdInfo.cfgMode == SdCfgMode::HOT_REDUNDANT) { @@ -342,7 +351,7 @@ ReturnValue_t CoreController::initSdCardBlocking() { sdCardSetup(sd::SdCard::SLOT_0, sd::SdState::MOUNTED, "0", false); sdCardSetup(sd::SdCard::SLOT_1, sd::SdState::MOUNTED, "1", false); // Update status file - sdcMan->updateSdCardStateFile(); + sdcMan->updateSdCardStateFile(true); } return returnvalue::OK; } @@ -395,7 +404,7 @@ ReturnValue_t CoreController::sdStateMachine() { if (sdFsmState == SdStates::GET_INFO) { if (not sdInfo.commandExecuted) { // Create updated status file - result = sdcMan->updateSdCardStateFile(); + result = sdcMan->updateSdCardStateFile(false); if (result != returnvalue::OK) { sif::warning << "CoreController::sdStateMachine: Updating SD card state file failed" << std::endl; @@ -543,12 +552,8 @@ ReturnValue_t CoreController::sdStateMachine() { if (sdFsmState == SdStates::SKIP_CYCLE_BEFORE_INFO_UPDATE) { sdFsmState = SdStates::UPDATE_INFO; } else if (sdFsmState == SdStates::UPDATE_INFO) { - // It is assumed that all tasks are running by the point this section is reached. - // Therefore, perform this operation in blocking mode because it does not take long - // and the ready state of the SD card is available sooner - sdcMan->setBlocking(true); // Update status file - result = sdcMan->updateSdCardStateFile(); + result = sdcMan->updateSdCardStateFile(true); if (result != returnvalue::OK) { sif::warning << "CoreController::initialize: Updating SD card state file failed" << std::endl; } diff --git a/bsp_q7s/fs/SdCardManager.cpp b/bsp_q7s/fs/SdCardManager.cpp index fa46f8e0..41569000 100644 --- a/bsp_q7s/fs/SdCardManager.cpp +++ b/bsp_q7s/fs/SdCardManager.cpp @@ -195,29 +195,9 @@ ReturnValue_t SdCardManager::setSdCardState(sd::SdCard sdCard, bool on) { return result; } -ReturnValue_t SdCardManager::getSdCardsStatus(SdStatePair& active) { - using namespace std; +ReturnValue_t SdCardManager::getSdCardsStatus(SdStatePair& sdStates) { MutexGuard mg(sdLock, LOCK_TYPE, SD_LOCK_TIMEOUT, LOCK_CTX); - std::error_code e; - if (not filesystem::exists(SD_STATE_FILE, e)) { - return STATUS_FILE_NEXISTS; - } - - // Now the file should exist in any case. Still check whether it exists. - fstream sdStatus(SD_STATE_FILE); - if (not sdStatus.good()) { - return STATUS_FILE_NEXISTS; - } - string line; - uint8_t idx = 0; - sd::SdCard currentSd = sd::SdCard::SLOT_0; - // Process status file line by line - while (std::getline(sdStatus, line)) { - processSdStatusLine(active, line, idx, currentSd); - } - if (active.first != sd::SdState::MOUNTED && active.second != sd::SdState::MOUNTED) { - sdCardActive = false; - } + sdStates = this->sdStates; return returnvalue::OK; } @@ -309,10 +289,9 @@ ReturnValue_t SdCardManager::sanitizeState(SdStatePair* statusPair, sd::SdCard p resetNonBlockingState = true; } if (statusPair == nullptr) { - sdStatusPtr = std::make_unique(); - statusPair = sdStatusPtr.get(); - getSdCardsStatus(*statusPair); + return returnvalue::FAILED; } + getSdCardsStatus(*statusPair); if (statusPair->first == sd::SdState::ON) { result = mountSdCard(prefSdCard); @@ -330,8 +309,34 @@ void SdCardManager::resetState() { currentOp = Operations::IDLE; } -void SdCardManager::processSdStatusLine(std::pair& active, - std::string& line, uint8_t& idx, sd::SdCard& currentSd) { +ReturnValue_t SdCardManager::updateSdStatePair() { + using namespace std; + + MutexGuard mg(sdLock, LOCK_TYPE, SD_LOCK_TIMEOUT, LOCK_CTX); + std::error_code e; + if (not filesystem::exists(SD_STATE_FILE, e)) { + return STATUS_FILE_NEXISTS; + } + + // Now the file should exist in any case. Still check whether it exists. + fstream sdStatus(SD_STATE_FILE); + if (not sdStatus.good()) { + return STATUS_FILE_NEXISTS; + } + string line; + uint8_t idx = 0; + sd::SdCard currentSd = sd::SdCard::SLOT_0; + // Process status file line by line + while (std::getline(sdStatus, line)) { + processSdStatusLine(line, idx, currentSd); + } + if (sdStates.first != sd::SdState::MOUNTED && sdStates.second != sd::SdState::MOUNTED) { + sdCardActive = false; + } + return returnvalue::OK; +} + +void SdCardManager::processSdStatusLine(std::string& line, uint8_t& idx, sd::SdCard& currentSd) { using namespace std; istringstream iss(line); string word; @@ -352,24 +357,24 @@ void SdCardManager::processSdStatusLine(std::pair& act if (word == "on") { if (currentSd == sd::SdCard::SLOT_0) { - active.first = sd::SdState::ON; + sdStates.first = sd::SdState::ON; } else { - active.second = sd::SdState::ON; + sdStates.second = sd::SdState::ON; } } else if (word == "off") { if (currentSd == sd::SdCard::SLOT_0) { - active.first = sd::SdState::OFF; + sdStates.first = sd::SdState::OFF; } else { - active.second = sd::SdState::OFF; + sdStates.second = sd::SdState::OFF; } } } if (mountLine) { if (currentSd == sd::SdCard::SLOT_0) { - active.first = sd::SdState::MOUNTED; + sdStates.first = sd::SdState::MOUNTED; } else { - active.second = sd::SdState::MOUNTED; + sdStates.second = sd::SdState::MOUNTED; } } @@ -400,7 +405,7 @@ ReturnValue_t SdCardManager::setPreferredSdCard(sd::SdCard sdCard) { return scratch::writeNumber(scratch::PREFERED_SDC_KEY, static_cast(sdCard)); } -ReturnValue_t SdCardManager::updateSdCardStateFile() { +ReturnValue_t SdCardManager::updateSdCardStateFile(bool blocking) { if (cmdExecutor.getCurrentState() == CommandExecutor::States::PENDING) { return CommandExecutor::COMMAND_PENDING; } @@ -475,35 +480,29 @@ bool SdCardManager::isSdCardUsable(std::optional sdCard) { } } - SdCardManager::SdStatePair active; - ReturnValue_t result = this->getSdCardsStatus(active); - - if (result != returnvalue::OK) { - sif::debug << "SdCardManager::isSdCardMounted: Failed to get SD card active state"; - return false; - } + MutexGuard mg(sdLock, LOCK_TYPE, SD_LOCK_TIMEOUT, LOCK_CTX); if (not sdCard) { - if (active.first == sd::MOUNTED or active.second == sd::MOUNTED) { + if (sdStates.first == sd::MOUNTED or sdStates.second == sd::MOUNTED) { return true; } return false; } if (sdCard == sd::SLOT_0) { - if (active.first == sd::MOUNTED) { + if (sdStates.first == sd::MOUNTED) { return true; } else { return false; } } if (sdCard == sd::SLOT_1) { - if (active.second == sd::MOUNTED) { + if (sdStates.second == sd::MOUNTED) { return true; } else { return false; } } if (sdCard == sd::BOTH) { - if (active.first == sd::MOUNTED && active.second == sd::MOUNTED) { + if (sdStates.first == sd::MOUNTED && sdStates.second == sd::MOUNTED) { return true; } } diff --git a/bsp_q7s/fs/SdCardManager.h b/bsp_q7s/fs/SdCardManager.h index 1cd09d7d..adc44bb8 100644 --- a/bsp_q7s/fs/SdCardManager.h +++ b/bsp_q7s/fs/SdCardManager.h @@ -25,7 +25,7 @@ class MutexIF; * state */ class SdCardManager : public SystemObject, public SdCardMountedIF { - friend class SdCardAccess; + friend class CoreController; public: using mountInitCb = ReturnValue_t (*)(void* args); @@ -125,7 +125,7 @@ class SdCardManager : public SystemObject, public SdCardMountedIF { * - CommandExecutor::COMMAND_PENDING: Non-blocking command is pending * - returnvalue::FAILED: blocking command failed */ - ReturnValue_t updateSdCardStateFile(); + ReturnValue_t updateSdCardStateFile(bool blocking); /** * Get the state of the SD cards. If the state file does not exist, this function will @@ -218,6 +218,7 @@ class SdCardManager : public SystemObject, public SdCardMountedIF { private: CommandExecutor cmdExecutor; + SdStatePair sdStates; Operations currentOp = Operations::IDLE; bool blocking = false; bool sdCardActive = true; @@ -233,10 +234,11 @@ class SdCardManager : public SystemObject, public SdCardMountedIF { SdCardManager(); + ReturnValue_t updateSdStatePair(); + ReturnValue_t setSdCardState(sd::SdCard sdCard, bool on); - void processSdStatusLine(SdStatePair& active, std::string& line, uint8_t& idx, - sd::SdCard& currentSd); + void processSdStatusLine(std::string& line, uint8_t& idx, sd::SdCard& currentSd); std::optional currentPrefix; From 677a3f95bda21e1a04d8662b29338e750dc3505c Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 10 Mar 2023 02:45:21 +0100 Subject: [PATCH 056/112] always update sd state file in blocking manner --- bsp_q7s/core/CoreController.cpp | 19 +++++++++++-------- bsp_q7s/fs/SdCardManager.cpp | 4 ++-- bsp_q7s/fs/SdCardManager.h | 2 +- 3 files changed, 14 insertions(+), 11 deletions(-) diff --git a/bsp_q7s/core/CoreController.cpp b/bsp_q7s/core/CoreController.cpp index d5023111..7eb0fe5f 100644 --- a/bsp_q7s/core/CoreController.cpp +++ b/bsp_q7s/core/CoreController.cpp @@ -42,8 +42,9 @@ CoreController::CoreController(object_id_t objectId) if (not BLOCKING_SD_INIT) { sdcMan->setBlocking(false); } - Stopwatch watch; - sdcMan->updateSdCardStateFile(true); + // Set up state of SD card manager and own initial state. + // Stopwatch watch; + sdcMan->updateSdCardStateFile(); sdcMan->updateSdStatePair(); SdCardManager::SdStatePair sdStates; sdcMan->getSdCardsStatus(sdStates); @@ -323,7 +324,7 @@ ReturnValue_t CoreController::checkModeCommand(Mode_t mode, Submode_t submode, ReturnValue_t CoreController::initSdCardBlocking() { // Create update status file - ReturnValue_t result = sdcMan->updateSdCardStateFile(true); + ReturnValue_t result = sdcMan->updateSdCardStateFile(); if (result != returnvalue::OK) { sif::warning << "CoreController::initialize: Updating SD card state file failed" << std::endl; } @@ -343,7 +344,7 @@ ReturnValue_t CoreController::initSdCardBlocking() { << static_cast(sdInfo.active) << std::endl; result = sdColdRedundantBlockingInit(); // Update status file - sdcMan->updateSdCardStateFile(true); + sdcMan->updateSdCardStateFile(); return result; } if (sdInfo.cfgMode == SdCfgMode::HOT_REDUNDANT) { @@ -351,7 +352,7 @@ ReturnValue_t CoreController::initSdCardBlocking() { sdCardSetup(sd::SdCard::SLOT_0, sd::SdState::MOUNTED, "0", false); sdCardSetup(sd::SdCard::SLOT_1, sd::SdState::MOUNTED, "1", false); // Update status file - sdcMan->updateSdCardStateFile(true); + sdcMan->updateSdCardStateFile(); } return returnvalue::OK; } @@ -404,12 +405,14 @@ ReturnValue_t CoreController::sdStateMachine() { if (sdFsmState == SdStates::GET_INFO) { if (not sdInfo.commandExecuted) { // Create updated status file - result = sdcMan->updateSdCardStateFile(false); + result = sdcMan->updateSdCardStateFile(); if (result != returnvalue::OK) { sif::warning << "CoreController::sdStateMachine: Updating SD card state file failed" << std::endl; } - sdInfo.commandExecuted = true; + sdFsmState = SdStates::SET_STATE_SELF; + sdInfo.commandExecuted = false; + sdInfo.cycleCount = 0; } else { nonBlockingOpChecking(SdStates::SET_STATE_SELF, 4, "Updating SDC file"); } @@ -553,7 +556,7 @@ ReturnValue_t CoreController::sdStateMachine() { sdFsmState = SdStates::UPDATE_INFO; } else if (sdFsmState == SdStates::UPDATE_INFO) { // Update status file - result = sdcMan->updateSdCardStateFile(true); + result = sdcMan->updateSdCardStateFile(); if (result != returnvalue::OK) { sif::warning << "CoreController::initialize: Updating SD card state file failed" << std::endl; } diff --git a/bsp_q7s/fs/SdCardManager.cpp b/bsp_q7s/fs/SdCardManager.cpp index 41569000..0ced8a04 100644 --- a/bsp_q7s/fs/SdCardManager.cpp +++ b/bsp_q7s/fs/SdCardManager.cpp @@ -405,14 +405,14 @@ ReturnValue_t SdCardManager::setPreferredSdCard(sd::SdCard sdCard) { return scratch::writeNumber(scratch::PREFERED_SDC_KEY, static_cast(sdCard)); } -ReturnValue_t SdCardManager::updateSdCardStateFile(bool blocking) { +ReturnValue_t SdCardManager::updateSdCardStateFile() { if (cmdExecutor.getCurrentState() == CommandExecutor::States::PENDING) { return CommandExecutor::COMMAND_PENDING; } MutexGuard mg(sdLock, LOCK_TYPE, SD_LOCK_TIMEOUT, LOCK_CTX); // Use q7hw utility and pipe the command output into the state file std::string updateCmd = "q7hw sd info all > " + std::string(SD_STATE_FILE); - cmdExecutor.load(updateCmd, blocking, printCmdOutput); + cmdExecutor.load(updateCmd, true, printCmdOutput); ReturnValue_t result = cmdExecutor.execute(); if (blocking and result != returnvalue::OK) { utility::handleSystemError(cmdExecutor.getLastError(), "SdCardManager::mountSdCard"); diff --git a/bsp_q7s/fs/SdCardManager.h b/bsp_q7s/fs/SdCardManager.h index adc44bb8..cee06894 100644 --- a/bsp_q7s/fs/SdCardManager.h +++ b/bsp_q7s/fs/SdCardManager.h @@ -125,7 +125,7 @@ class SdCardManager : public SystemObject, public SdCardMountedIF { * - CommandExecutor::COMMAND_PENDING: Non-blocking command is pending * - returnvalue::FAILED: blocking command failed */ - ReturnValue_t updateSdCardStateFile(bool blocking); + ReturnValue_t updateSdCardStateFile(); /** * Get the state of the SD cards. If the state file does not exist, this function will From f3c3e8a4430d7becefaba9872b2d0eb3ddfc3036 Mon Sep 17 00:00:00 2001 From: meggert Date: Fri, 10 Mar 2023 09:17:19 +0100 Subject: [PATCH 057/112] corrected vector length to 1 --- mission/controller/acs/AcsParameters.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/mission/controller/acs/AcsParameters.h b/mission/controller/acs/AcsParameters.h index 4d6aa14a..8dc6e1ee 100644 --- a/mission/controller/acs/AcsParameters.h +++ b/mission/controller/acs/AcsParameters.h @@ -817,7 +817,7 @@ class AcsParameters : public HasParametersIF { double sunMagAngleMin = 5 * M_PI / 180; - double sunTargetDirLeop[3] = {0, .5, .5}; + double sunTargetDirLeop[3] = {0, sqrt(.5), sqrt(.5)}; double sunTargetDir[3] = {0, 0, 1}; double satRateRef[3] = {0, 0, 0}; From 0dbd6b703d4aae29c8279aa96c1872e697c41d43 Mon Sep 17 00:00:00 2001 From: meggert Date: Fri, 10 Mar 2023 09:44:30 +0100 Subject: [PATCH 058/112] small fixes --- mission/controller/acs/ActuatorCmd.cpp | 2 +- mission/controller/acs/Guidance.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/mission/controller/acs/ActuatorCmd.cpp b/mission/controller/acs/ActuatorCmd.cpp index 37212113..588ee82a 100644 --- a/mission/controller/acs/ActuatorCmd.cpp +++ b/mission/controller/acs/ActuatorCmd.cpp @@ -16,7 +16,7 @@ ActuatorCmd::~ActuatorCmd() {} void ActuatorCmd::scalingTorqueRws(const double *rwTrq, double *rwTrqScaled, double maxTorque) { double maxValue = 0; - for (int i = 0; i < 4; i++) { // size of torque, always 4 ? + for (int i = 0; i < 4; i++) { if (abs(rwTrq[i]) > maxValue) { maxValue = abs(rwTrq[i]); } diff --git a/mission/controller/acs/Guidance.cpp b/mission/controller/acs/Guidance.cpp index 71cb227e..ca312876 100644 --- a/mission/controller/acs/Guidance.cpp +++ b/mission/controller/acs/Guidance.cpp @@ -544,7 +544,7 @@ void Guidance::getTargetParamsSafe(double sunTargetSafe[3], double satRateSafe[3 if (not std::filesystem::exists(SD_0_SKEWED_PTG_FILE, e) or not std::filesystem::exists(SD_1_SKEWED_PTG_FILE, e)) { // ToDo: if file does not exist anymore - std::memcpy(sunTargetSafe, acsParameters.safeModeControllerParameters.sunTargetDir, + std::memcpy(sunTargetSafe, acsParameters->safeModeControllerParameters.sunTargetDir, 3 * sizeof(double)); } else { std::memcpy(sunTargetSafe, acsParameters->safeModeControllerParameters.sunTargetDirLeop, From e4efd422349e170323a7e8e46bb10e20d586a2cb Mon Sep 17 00:00:00 2001 From: meggert Date: Fri, 10 Mar 2023 10:28:31 +0100 Subject: [PATCH 059/112] fixed idle mode param commands changing target mode params --- mission/controller/acs/AcsParameters.cpp | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/mission/controller/acs/AcsParameters.cpp b/mission/controller/acs/AcsParameters.cpp index 0d3785cc..f39ea601 100644 --- a/mission/controller/acs/AcsParameters.cpp +++ b/mission/controller/acs/AcsParameters.cpp @@ -345,31 +345,31 @@ ReturnValue_t AcsParameters::getParameter(uint8_t domainId, uint8_t parameterId, case (0x9): // IdleModeControllerParameters switch (parameterId) { case 0x0: - parameterWrapper->set(targetModeControllerParameters.zeta); + parameterWrapper->set(idleModeControllerParameters.zeta); break; case 0x1: - parameterWrapper->set(targetModeControllerParameters.om); + parameterWrapper->set(idleModeControllerParameters.om); break; case 0x2: - parameterWrapper->set(targetModeControllerParameters.omMax); + parameterWrapper->set(idleModeControllerParameters.omMax); break; case 0x3: - parameterWrapper->set(targetModeControllerParameters.qiMin); + parameterWrapper->set(idleModeControllerParameters.qiMin); break; case 0x4: - parameterWrapper->set(targetModeControllerParameters.gainNullspace); + parameterWrapper->set(idleModeControllerParameters.gainNullspace); break; case 0x5: - parameterWrapper->setVector(targetModeControllerParameters.desatMomentumRef); + parameterWrapper->setVector(idleModeControllerParameters.desatMomentumRef); break; case 0x6: - parameterWrapper->set(targetModeControllerParameters.deSatGainFactor); + parameterWrapper->set(idleModeControllerParameters.deSatGainFactor); break; case 0x7: - parameterWrapper->set(targetModeControllerParameters.desatOn); + parameterWrapper->set(idleModeControllerParameters.desatOn); break; case 0x8: - parameterWrapper->set(targetModeControllerParameters.enableAntiStiction); + parameterWrapper->set(idleModeControllerParameters.enableAntiStiction); break; default: From 75a80b55ec4f0fc763bd2159913292f5296f443b Mon Sep 17 00:00:00 2001 From: meggert Date: Fri, 10 Mar 2023 10:29:27 +0100 Subject: [PATCH 060/112] changelog --- CHANGELOG.md | 2 ++ 1 file changed, 2 insertions(+) diff --git a/CHANGELOG.md b/CHANGELOG.md index 16c371e5..1dc9062e 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -32,6 +32,8 @@ will consitute of a breaking change warranting a new major release: instances. - Instead of updating the `gsTargetModeControllerParameters`, the `targetModeControllerParameters` were updated. +- Instead of updating the `idleModeControllerParameters`, the `targetModeControllerParameters` + were updated. - Fixed Idle Mode Controller never calling `ptgLaw` and therefore never calculating control values. - Fixed wrong check on wether file used for persistant boolean flag on successful still existed. From 9a30ae5175715b93be7f436d073515d101369d0b Mon Sep 17 00:00:00 2001 From: meggert Date: Fri, 10 Mar 2023 10:30:01 +0100 Subject: [PATCH 061/112] who knows what that todo was good for --- mission/controller/acs/Guidance.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/mission/controller/acs/Guidance.cpp b/mission/controller/acs/Guidance.cpp index ca312876..35a2f025 100644 --- a/mission/controller/acs/Guidance.cpp +++ b/mission/controller/acs/Guidance.cpp @@ -542,8 +542,7 @@ ReturnValue_t Guidance::getDistributionMatrixRw(ACS::SensorValues *sensorValues, void Guidance::getTargetParamsSafe(double sunTargetSafe[3], double satRateSafe[3]) { std::error_code e; if (not std::filesystem::exists(SD_0_SKEWED_PTG_FILE, e) or - not std::filesystem::exists(SD_1_SKEWED_PTG_FILE, - e)) { // ToDo: if file does not exist anymore + not std::filesystem::exists(SD_1_SKEWED_PTG_FILE, e)) { std::memcpy(sunTargetSafe, acsParameters->safeModeControllerParameters.sunTargetDir, 3 * sizeof(double)); } else { From a9b514ddc80dcfd409754bb10cc9e24a1d8edddb Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 10 Mar 2023 11:12:44 +0100 Subject: [PATCH 062/112] solved in different PR --- bsp_q7s/fs/SdCardManager.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/bsp_q7s/fs/SdCardManager.h b/bsp_q7s/fs/SdCardManager.h index 874fd786..1cd09d7d 100644 --- a/bsp_q7s/fs/SdCardManager.h +++ b/bsp_q7s/fs/SdCardManager.h @@ -227,7 +227,7 @@ class SdCardManager : public SystemObject, public SdCardMountedIF { MutexIF* prefLock = nullptr; MutexIF* defaultLock = nullptr; static constexpr MutexIF::TimeoutType LOCK_TYPE = MutexIF::TimeoutType::WAITING; - static constexpr uint32_t SD_LOCK_TIMEOUT = 400; + static constexpr uint32_t SD_LOCK_TIMEOUT = 250; static constexpr uint32_t OTHER_TIMEOUT = 20; static constexpr char LOCK_CTX[] = "SdCardManager"; From cca8734908168e42943eda1efc85652b4ae48165 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 10 Mar 2023 11:15:08 +0100 Subject: [PATCH 063/112] add it at actuate step as well --- linux/devices/ImtqPollingTask.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/linux/devices/ImtqPollingTask.cpp b/linux/devices/ImtqPollingTask.cpp index c15acd29..fbd5f847 100644 --- a/linux/devices/ImtqPollingTask.cpp +++ b/linux/devices/ImtqPollingTask.cpp @@ -182,6 +182,11 @@ void ImtqPollingTask::handleActuateStep() { TaskFactory::delayTask(10); cmdLen = 1; + // The I2C IP core on EIVE sometimes glitches out. Send start MTM measurement twice. + cmdBuf[0] = imtq::CC::START_MTM_MEASUREMENT; + if (i2cCmdExecActuate(imtq::CC::START_MTM_MEASUREMENT) != returnvalue::OK) { + return; + } cmdBuf[0] = imtq::CC::START_MTM_MEASUREMENT; if (i2cCmdExecActuate(imtq::CC::START_MTM_MEASUREMENT) != returnvalue::OK) { return; From 86e48eea6deb048bbe00a7d64913bda28717ccea Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 10 Mar 2023 11:16:02 +0100 Subject: [PATCH 064/112] changelog update --- CHANGELOG.md | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/CHANGELOG.md b/CHANGELOG.md index 4d2e2cbb..b601b8bd 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -20,6 +20,11 @@ will consitute of a breaking change warranting a new major release: - Fix for heater names: HPA heater (index 7) is now the Syrlinks heater. +## Changed + +- Request raw MTM measurement twice for IMTQ, might reduce number of times measurement could not + be retrieved. + # [v1.36.0] 2023-03-08 eive-tmtc: v2.17.2 From 3caa9dea75b6de4ef84fc0df63591a006afc7cb2 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 10 Mar 2023 11:18:34 +0100 Subject: [PATCH 065/112] changelog --- CHANGELOG.md | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/CHANGELOG.md b/CHANGELOG.md index 4d2e2cbb..bfcb003c 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -20,6 +20,13 @@ will consitute of a breaking change warranting a new major release: - Fix for heater names: HPA heater (index 7) is now the Syrlinks heater. +## Changed + +- More fixes and improvements for SD card handling. Extend SD card setup in core controller to + create full initial state for SD card manager are core controller as early as possible, turn + execution of setup file update blocking. This might solve the issue with the SD card manager + sometimes blocking for a long time. + # [v1.36.0] 2023-03-08 eive-tmtc: v2.17.2 From cb8a49775d06460a76485023bdac687fface0cdb Mon Sep 17 00:00:00 2001 From: meggert Date: Fri, 10 Mar 2023 11:37:04 +0100 Subject: [PATCH 066/112] added protection to not command rwSpeeds larger than the allowed speed range --- mission/controller/AcsController.cpp | 4 ++-- mission/controller/acs/AcsParameters.cpp | 9 ++++++--- mission/controller/acs/AcsParameters.h | 1 + mission/controller/acs/ActuatorCmd.cpp | 9 ++++++++- mission/controller/acs/ActuatorCmd.h | 2 +- 5 files changed, 18 insertions(+), 7 deletions(-) diff --git a/mission/controller/AcsController.cpp b/mission/controller/AcsController.cpp index f827950a..c7bbe0aa 100644 --- a/mission/controller/AcsController.cpp +++ b/mission/controller/AcsController.cpp @@ -416,7 +416,6 @@ void AcsController::performPointingCtrl() { enableAntiStiction = acsParameters.inertialModeControllerParameters.enableAntiStiction; break; } - if (enableAntiStiction) { ptgCtrl.rwAntistiction(&sensorValues, torqueRwsScaled); } @@ -425,13 +424,14 @@ void AcsController::performPointingCtrl() { sensorValues.rw1Set.currSpeed.value, sensorValues.rw2Set.currSpeed.value, sensorValues.rw3Set.currSpeed.value, sensorValues.rw4Set.currSpeed.value, torqueRwsScaled, cmdSpeedRws, acsParameters.onBoardParams.sampleTime, + acsParameters.rwHandlingParameters.maxRwSpeed, acsParameters.rwHandlingParameters.inertiaWheel); actuatorCmd.cmdDipolMtq(mgtDpDes, cmdDipolMtqs, *acsParameters.magnetorquerParameter.inverseAlignment, acsParameters.magnetorquerParameter.dipolMax); updateCtrlValData(targetQuat, errorQuat, errorAngle, targetSatRotRate); - updateActuatorCmdData(rwTrqNs, cmdSpeedRws, cmdDipolMtqs); + updateActuatorCmdData(torqueRwsScaled, cmdSpeedRws, cmdDipolMtqs); // commandActuators(cmdDipolMtqs[0], cmdDipolMtqs[1], cmdDipolMtqs[2], // acsParameters.magnetorquesParameter.torqueDuration, cmdSpeedRws[0], // cmdSpeedRws[1], cmdSpeedRws[2], cmdSpeedRws[3], diff --git a/mission/controller/acs/AcsParameters.cpp b/mission/controller/acs/AcsParameters.cpp index f39ea601..4abe0d7a 100644 --- a/mission/controller/acs/AcsParameters.cpp +++ b/mission/controller/acs/AcsParameters.cpp @@ -270,15 +270,18 @@ ReturnValue_t AcsParameters::getParameter(uint8_t domainId, uint8_t parameterId, parameterWrapper->set(rwHandlingParameters.maxTrq); break; case 0x2: - parameterWrapper->set(rwHandlingParameters.stictionSpeed); + parameterWrapper->set(rwHandlingParameters.maxRwSpeed); break; case 0x3: - parameterWrapper->set(rwHandlingParameters.stictionReleaseSpeed); + parameterWrapper->set(rwHandlingParameters.stictionSpeed); break; case 0x4: - parameterWrapper->set(rwHandlingParameters.stictionTorque); + parameterWrapper->set(rwHandlingParameters.stictionReleaseSpeed); break; case 0x5: + parameterWrapper->set(rwHandlingParameters.stictionTorque); + break; + case 0x6: parameterWrapper->set(rwHandlingParameters.rampTime); break; default: diff --git a/mission/controller/acs/AcsParameters.h b/mission/controller/acs/AcsParameters.h index 8dc6e1ee..98cbd9ad 100644 --- a/mission/controller/acs/AcsParameters.h +++ b/mission/controller/acs/AcsParameters.h @@ -784,6 +784,7 @@ class AcsParameters : public HasParametersIF { struct RwHandlingParameters { double inertiaWheel = 0.000028198; double maxTrq = 0.0032; // 3.2 [mNm] + int32_t maxRwSpeed = 65000; // 0.1 RPM int32_t stictionSpeed = 100; // RPM int32_t stictionReleaseSpeed = 120; // RPM double stictionTorque = 0.0006; diff --git a/mission/controller/acs/ActuatorCmd.cpp b/mission/controller/acs/ActuatorCmd.cpp index 588ee82a..592fc69d 100644 --- a/mission/controller/acs/ActuatorCmd.cpp +++ b/mission/controller/acs/ActuatorCmd.cpp @@ -30,7 +30,7 @@ void ActuatorCmd::scalingTorqueRws(const double *rwTrq, double *rwTrqScaled, dou void ActuatorCmd::cmdSpeedToRws(int32_t speedRw0, int32_t speedRw1, int32_t speedRw2, int32_t speedRw3, const double *rwTorque, int32_t *rwCmdSpeed, - double sampleTime, double inertiaWheel) { + double sampleTime, int32_t maxRwSpeed, double inertiaWheel) { using namespace Math; // Calculating the commanded speed in RPM for every reaction wheel @@ -45,6 +45,13 @@ void ActuatorCmd::cmdSpeedToRws(int32_t speedRw0, int32_t speedRw1, int32_t spee deltaSpeedInt[i] = std::round(deltaSpeed[i]); } VectorOperations::add(speedRws, deltaSpeedInt, rwCmdSpeed, 4); + for (uint8_t i = 0; i < 4; i++) { + if (rwCmdSpeed[i] > maxRwSpeed) { + rwCmdSpeed[i] = maxRwSpeed; + } else if (rwCmdSpeed[i] < -maxRwSpeed) { + rwCmdSpeed[i] = -maxRwSpeed; + } + } VectorOperations::mulScalar(rwCmdSpeed, 10, rwCmdSpeed, 4); } diff --git a/mission/controller/acs/ActuatorCmd.h b/mission/controller/acs/ActuatorCmd.h index def3c1b6..269e0191 100644 --- a/mission/controller/acs/ActuatorCmd.h +++ b/mission/controller/acs/ActuatorCmd.h @@ -29,7 +29,7 @@ class ActuatorCmd { */ void cmdSpeedToRws(int32_t speedRw0, int32_t speedRw1, int32_t speedRw2, int32_t speedRw3, const double *rwTorque, int32_t *rwCmdSpeed, double sampleTime, - double inertiaWheel); + int32_t maxRwSpeed, double inertiaWheel); /* * @brief: cmdDipolMtq() gives the commanded dipol moment for the magnetorques From 555e0ce49da693b3c0eccfd4ee4fabf2a427c478 Mon Sep 17 00:00:00 2001 From: meggert Date: Fri, 10 Mar 2023 11:39:31 +0100 Subject: [PATCH 067/112] changelog --- CHANGELOG.md | 1 + mission/controller/acs/control/PtgCtrl.cpp | 14 +++++++------- 2 files changed, 8 insertions(+), 7 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 1dc9062e..a6d45d74 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -20,6 +20,7 @@ will consitute of a breaking change warranting a new major release: - `SensorProcessing` now includes an FDIR for GPS altitude. If the measured GPS altitude is out of bounds of the range defined in the `AcsParameters`, the altitude defaults to an altitude set in the `AcsParameters`. +- `AcsController` will now never command a RW speed larger than the maximum allowed speed. ## Fixed diff --git a/mission/controller/acs/control/PtgCtrl.cpp b/mission/controller/acs/control/PtgCtrl.cpp index c7c8d2f0..01c047db 100644 --- a/mission/controller/acs/control/PtgCtrl.cpp +++ b/mission/controller/acs/control/PtgCtrl.cpp @@ -78,19 +78,19 @@ void PtgCtrl::ptgLaw(AcsParameters::PointingLawParameters *pointingLawParameters pErrorSign[i] = pError[i]; } } - // Torque for quaternion error + // torque for quaternion error double torqueQuat[3] = {0, 0, 0}; MatrixOperations::multiply(*gainMatrix, pErrorSign, torqueQuat, 3, 3, 1); VectorOperations::mulScalar(torqueQuat, -1, torqueQuat, 3); - // Torque for rate error + // torque for rate error double torqueRate[3] = {0, 0, 0}; MatrixOperations::multiply(*(acsParameters->inertiaEIVE.inertiaMatrix), deltaRate, torqueRate, 3, 3, 1); VectorOperations::mulScalar(torqueRate, cInt, torqueRate, 3); VectorOperations::mulScalar(torqueRate, -1, torqueRate, 3); - // Final commanded Torque for every reaction wheel + // final commanded Torque for every reaction wheel double torque[3] = {0, 0, 0}; VectorOperations::add(torqueRate, torqueQuat, torque, 3); MatrixOperations::multiply(rwPseudoInv, torque, torqueRws, 4, 3, 1); @@ -108,7 +108,7 @@ void PtgCtrl::ptgDesaturation(AcsParameters::PointingLawParameters *pointingLawP return; } - // calculating momentum of satellite and momentum of reaction wheels + // calculating momentum of satellite and momentum of reaction wheels double speedRws[4] = {(double)*speedRw0, (double)*speedRw1, (double)*speedRw2, (double)*speedRw3}; double momentumRwU[4] = {0, 0, 0, 0}, momentumRw[3] = {0, 0, 0}; VectorOperations::mulScalar(speedRws, acsParameters->rwHandlingParameters.inertiaWheel, @@ -119,11 +119,11 @@ void PtgCtrl::ptgDesaturation(AcsParameters::PointingLawParameters *pointingLawP MatrixOperations::multiply(*(acsParameters->inertiaEIVE.inertiaMatrix), satRate, momentumSat, 3, 3, 1); VectorOperations::add(momentumSat, momentumRw, momentumTotal, 3); - // calculating momentum error + // calculating momentum error double deltaMomentum[3] = {0, 0, 0}; VectorOperations::subtract(momentumTotal, pointingLawParameters->desatMomentumRef, deltaMomentum, 3); - // resulting magnetic dipole command + // resulting magnetic dipole command double crossMomentumMagField[3] = {0, 0, 0}; VectorOperations::cross(deltaMomentum, magFieldEst, crossMomentumMagField); double normMag = VectorOperations::norm(magFieldEst, 3), factor = 0; @@ -137,7 +137,7 @@ void PtgCtrl::ptgNullspace(AcsParameters::PointingLawParameters *pointingLawPara double speedRws[4] = {(double)*speedRw0, (double)*speedRw1, (double)*speedRw2, (double)*speedRw3}; double wheelMomentum[4] = {0, 0, 0, 0}; double rpmOffset[4] = {1, 1, 1, -1}, factor = 350 * 2 * Math::PI / 60; - // Conversion to [rad/s] for further calculations + // conversion to [rad/s] for further calculations VectorOperations::mulScalar(rpmOffset, factor, rpmOffset, 4); VectorOperations::mulScalar(speedRws, 2 * Math::PI / 60, speedRws, 4); double diffRwSpeed[4] = {0, 0, 0, 0}; From b1c4241b03f4ef5d7ff508276c992b75e06f97ce Mon Sep 17 00:00:00 2001 From: meggert Date: Fri, 10 Mar 2023 11:55:18 +0100 Subject: [PATCH 068/112] changed perform operation --- mission/controller/AcsController.cpp | 15 +++++++++------ 1 file changed, 9 insertions(+), 6 deletions(-) diff --git a/mission/controller/AcsController.cpp b/mission/controller/AcsController.cpp index 25ad8706..bc0fa754 100644 --- a/mission/controller/AcsController.cpp +++ b/mission/controller/AcsController.cpp @@ -112,13 +112,16 @@ void AcsController::performControlOperation() { } case InternalState::READY: { if (mode != MODE_OFF) { - switch (submode) { + switch (mode) { case acs::SAFE: - performSafe(); - break; - case acs::DETUMBLE: - performDetumble(); - break; + switch (submode) { + case SUBMODE_NONE: + performSafe(); + break; + case acs::DETUMBLE: + performDetumble(); + break; + } case acs::PTG_IDLE: case acs::PTG_TARGET: case acs::PTG_TARGET_GS: From 170976566b9e0ce2d6545790faa3249a6eceda46 Mon Sep 17 00:00:00 2001 From: meggert Date: Fri, 10 Mar 2023 12:11:10 +0100 Subject: [PATCH 069/112] acsCtrl does not allow ON or NORMAL anymore --- mission/acsDefs.h | 12 ++++++------ mission/controller/AcsController.cpp | 10 ++++++++-- 2 files changed, 14 insertions(+), 8 deletions(-) diff --git a/mission/acsDefs.h b/mission/acsDefs.h index 9b7916af..f824efbf 100644 --- a/mission/acsDefs.h +++ b/mission/acsDefs.h @@ -10,12 +10,12 @@ namespace acs { enum AcsMode : Mode_t { OFF = HasModesIF::MODE_OFF, SAFE = 10, - DETUMBLE = 11, - PTG_IDLE = 12, - PTG_NADIR = 13, - PTG_TARGET = 14, - PTG_TARGET_GS = 15, - PTG_INERTIAL = 16, + PTG_IDLE = 11, + PTG_NADIR = 12, + PTG_TARGET = 13, + PTG_TARGET_GS = 14, + PTG_INERTIAL = 15, + DETUMBLE = 20, }; // static constexpr uint8_t ACS_SYSTEM_DETUMBLE_SUBMODE = 1; diff --git a/mission/controller/AcsController.cpp b/mission/controller/AcsController.cpp index bc0fa754..9ae0ed7d 100644 --- a/mission/controller/AcsController.cpp +++ b/mission/controller/AcsController.cpp @@ -639,8 +639,14 @@ ReturnValue_t AcsController::checkModeCommand(Mode_t mode, Submode_t submode, } else { return INVALID_SUBMODE; } - } else if ((mode == MODE_ON) || (mode == MODE_NORMAL)) { - if ((submode < acs::AcsMode::SAFE) or (submode > acs::AcsMode::PTG_INERTIAL)) { + } else if (not((mode < acs::AcsMode::SAFE) or (mode > acs::AcsMode::PTG_INERTIAL))) { + if (mode == acs::AcsMode::SAFE) { + if (not((submode == SUBMODE_NONE) or (submode == acs::AcsMode::DETUMBLE))) { + return INVALID_SUBMODE; + } else { + return returnvalue::OK; + } + } else if (not(submode == SUBMODE_NONE)) { return INVALID_SUBMODE; } else { return returnvalue::OK; From ba0bc1b98b0c69064ebb2a2e687ae54644d8fcea Mon Sep 17 00:00:00 2001 From: meggert Date: Fri, 10 Mar 2023 12:46:26 +0100 Subject: [PATCH 070/112] anounce mode changes --- mission/controller/AcsController.cpp | 13 ++++++++----- 1 file changed, 8 insertions(+), 5 deletions(-) diff --git a/mission/controller/AcsController.cpp b/mission/controller/AcsController.cpp index 9ae0ed7d..fbe57395 100644 --- a/mission/controller/AcsController.cpp +++ b/mission/controller/AcsController.cpp @@ -663,12 +663,15 @@ void AcsController::announceMode(bool recursive) { const char *modeStr = "UNKNOWN"; if (mode == HasModesIF::MODE_OFF) { modeStr = "OFF"; - } else if (mode == HasModesIF::MODE_ON) { - modeStr = "ON"; - } else if (mode == DeviceHandlerIF::MODE_NORMAL) { - modeStr = "NORMAL"; + } else { + *modeStr = acs::getModeStr(static_cast(mode)); + } + const char *submodeStr = "UNKNOWN"; + if (submode == HasModesIF::SUBMODE_NONE) { + submodeStr = "NONE"; + } else { + *submodeStr = acs::getModeStr(static_cast(mode)); } - const char *submodeStr = acs::getModeStr(static_cast(submode)); sif::info << "ACS controller is now in " << modeStr << " mode with " << submodeStr << " submode" << std::endl; return ExtendedControllerBase::announceMode(recursive); From c80426309d32a38f0fda56f51a692297083a31cf Mon Sep 17 00:00:00 2001 From: meggert Date: Fri, 10 Mar 2023 12:50:18 +0100 Subject: [PATCH 071/112] fixed automatic switch between safe and detumble --- mission/system/objects/AcsSubsystem.cpp | 14 ++------------ 1 file changed, 2 insertions(+), 12 deletions(-) diff --git a/mission/system/objects/AcsSubsystem.cpp b/mission/system/objects/AcsSubsystem.cpp index 3bab5273..2221c7e8 100644 --- a/mission/system/objects/AcsSubsystem.cpp +++ b/mission/system/objects/AcsSubsystem.cpp @@ -42,16 +42,6 @@ ReturnValue_t AcsSubsystem::initialize() { if (result != returnvalue::OK) { sif::error << "AcsSubsystem: Subscribing for acs::SAFE_RATE_RECOVERY failed" << std::endl; } - result = - manager->subscribeToEvent(eventQueue->getId(), event::getEventId(acs::MULTIPLE_RW_INVALID)); - if (result != returnvalue::OK) { - sif::error << "AcsSubsystem: Subscribing for acs::MULTIPLE_RW_INVALID failed" << std::endl; - } - result = manager->subscribeToEvent(eventQueue->getId(), - event::getEventId(acs::MEKF_INVALID_MODE_VIOLATION)); - if (result != returnvalue::OK) { - sif::error << "AcsSubsystem: Subscribing for acs::MULTIPLE_RW_INVALID failed" << std::endl; - } return Subsystem::initialize(); } @@ -70,7 +60,7 @@ void AcsSubsystem::handleEventMessages() { case EventMessage::EVENT_MESSAGE: if (event.getEvent() == acs::SAFE_RATE_VIOLATION) { CommandMessage msg; - ModeMessage::setCmdModeMessage(msg, acs::AcsMode::DETUMBLE, 0); + ModeMessage::setCmdModeMessage(msg, acs::AcsMode::SAFE, acs::AcsMode::DETUMBLE); status = commandQueue->sendMessage(commandQueue->getId(), &msg); if (result != returnvalue::OK) { sif::error << "AcsSubsystem: sending DETUMBLE mode cmd to self has failed" << std::endl; @@ -78,7 +68,7 @@ void AcsSubsystem::handleEventMessages() { } if (event.getEvent() == acs::SAFE_RATE_RECOVERY) { CommandMessage msg; - ModeMessage::setCmdModeMessage(msg, acs::AcsMode::SAFE, 0); + ModeMessage::setCmdModeMessage(msg, acs::AcsMode::SAFE, SUBMODE_NONE); status = commandQueue->sendMessage(commandQueue->getId(), &msg); if (status != returnvalue::OK) { sif::error << "AcsSubsystem: sending SAFE mode cmd to self has failed" << std::endl; From c85c2cf4b66f1842452b51457d6637c296a7f66c Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 10 Mar 2023 13:17:46 +0100 Subject: [PATCH 072/112] this should be it for OBSW --- mission/acsDefs.cpp | 4 -- mission/acsDefs.h | 3 +- mission/controller/AcsController.cpp | 12 ++-- mission/system/objects/AcsSubsystem.cpp | 4 +- mission/system/objects/EiveSystem.cpp | 4 -- mission/system/tree/acsModeTree.cpp | 95 ++++--------------------- mission/system/tree/system.cpp | 7 +- 7 files changed, 28 insertions(+), 101 deletions(-) diff --git a/mission/acsDefs.cpp b/mission/acsDefs.cpp index 00686b15..4027896c 100644 --- a/mission/acsDefs.cpp +++ b/mission/acsDefs.cpp @@ -11,10 +11,6 @@ const char* acs::getModeStr(AcsMode mode) { modeStr = "SAFE"; break; } - case (acs::AcsMode::DETUMBLE): { - modeStr = "DETUBMLE"; - break; - } case (acs::AcsMode::PTG_NADIR): { modeStr = "POITNING NADIR"; break; diff --git a/mission/acsDefs.h b/mission/acsDefs.h index f824efbf..a724bbd7 100644 --- a/mission/acsDefs.h +++ b/mission/acsDefs.h @@ -15,9 +15,10 @@ enum AcsMode : Mode_t { PTG_TARGET = 13, PTG_TARGET_GS = 14, PTG_INERTIAL = 15, - DETUMBLE = 20, }; +enum SafeSubmode : Submode_t { DEFAULT = 0, DETUMBLE = 1 }; + // static constexpr uint8_t ACS_SYSTEM_DETUMBLE_SUBMODE = 1; static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::ACS_SUBSYSTEM; diff --git a/mission/controller/AcsController.cpp b/mission/controller/AcsController.cpp index fbe57395..2ff5547b 100644 --- a/mission/controller/AcsController.cpp +++ b/mission/controller/AcsController.cpp @@ -641,7 +641,7 @@ ReturnValue_t AcsController::checkModeCommand(Mode_t mode, Submode_t submode, } } else if (not((mode < acs::AcsMode::SAFE) or (mode > acs::AcsMode::PTG_INERTIAL))) { if (mode == acs::AcsMode::SAFE) { - if (not((submode == SUBMODE_NONE) or (submode == acs::AcsMode::DETUMBLE))) { + if (not((submode == SUBMODE_NONE) or (submode == acs::SafeSubmode::DETUMBLE))) { return INVALID_SUBMODE; } else { return returnvalue::OK; @@ -664,13 +664,17 @@ void AcsController::announceMode(bool recursive) { if (mode == HasModesIF::MODE_OFF) { modeStr = "OFF"; } else { - *modeStr = acs::getModeStr(static_cast(mode)); + modeStr = acs::getModeStr(static_cast(mode)); } const char *submodeStr = "UNKNOWN"; if (submode == HasModesIF::SUBMODE_NONE) { submodeStr = "NONE"; - } else { - *submodeStr = acs::getModeStr(static_cast(mode)); + } + if (mode == acs::AcsMode::SAFE) { + acs::SafeSubmode safeSubmode = static_cast(this->submode); + if (safeSubmode == acs::SafeSubmode::DETUMBLE) { + submodeStr = "DETUMBLE"; + } } sif::info << "ACS controller is now in " << modeStr << " mode with " << submodeStr << " submode" << std::endl; diff --git a/mission/system/objects/AcsSubsystem.cpp b/mission/system/objects/AcsSubsystem.cpp index 2221c7e8..d407f2e8 100644 --- a/mission/system/objects/AcsSubsystem.cpp +++ b/mission/system/objects/AcsSubsystem.cpp @@ -60,7 +60,7 @@ void AcsSubsystem::handleEventMessages() { case EventMessage::EVENT_MESSAGE: if (event.getEvent() == acs::SAFE_RATE_VIOLATION) { CommandMessage msg; - ModeMessage::setCmdModeMessage(msg, acs::AcsMode::SAFE, acs::AcsMode::DETUMBLE); + ModeMessage::setCmdModeMessage(msg, acs::AcsMode::SAFE, acs::SafeSubmode::DETUMBLE); status = commandQueue->sendMessage(commandQueue->getId(), &msg); if (result != returnvalue::OK) { sif::error << "AcsSubsystem: sending DETUMBLE mode cmd to self has failed" << std::endl; @@ -68,7 +68,7 @@ void AcsSubsystem::handleEventMessages() { } if (event.getEvent() == acs::SAFE_RATE_RECOVERY) { CommandMessage msg; - ModeMessage::setCmdModeMessage(msg, acs::AcsMode::SAFE, SUBMODE_NONE); + ModeMessage::setCmdModeMessage(msg, acs::AcsMode::SAFE, acs::SafeSubmode::DEFAULT); status = commandQueue->sendMessage(commandQueue->getId(), &msg); if (status != returnvalue::OK) { sif::error << "AcsSubsystem: sending SAFE mode cmd to self has failed" << std::endl; diff --git a/mission/system/objects/EiveSystem.cpp b/mission/system/objects/EiveSystem.cpp index 26707bf1..65711706 100644 --- a/mission/system/objects/EiveSystem.cpp +++ b/mission/system/objects/EiveSystem.cpp @@ -17,10 +17,6 @@ void EiveSystem::announceMode(bool recursive) { modeStr = "SAFE"; break; } - case (acs::AcsMode::DETUMBLE): { - modeStr = "DETUBMLE"; - break; - } case (acs::AcsMode::PTG_IDLE): { modeStr = "POINTING IDLE"; break; diff --git a/mission/system/tree/acsModeTree.cpp b/mission/system/tree/acsModeTree.cpp index ce419d0b..95effa7f 100644 --- a/mission/system/tree/acsModeTree.cpp +++ b/mission/system/tree/acsModeTree.cpp @@ -20,7 +20,6 @@ namespace { const auto check = subsystem::checkInsert; void buildOffSequence(Subsystem& ss, ModeListEntry& eh); -void buildDetumbleSequence(Subsystem& ss, ModeListEntry& entryHelper); void buildSafeSequence(Subsystem& ss, ModeListEntry& entryHelper); void buildIdleSequence(Subsystem& ss, ModeListEntry& entryHelper); void buildTargetPtNadirSequence(Subsystem& ss, ModeListEntry& eh); @@ -43,15 +42,6 @@ auto ACS_TABLE_OFF_TRANS_0 = auto ACS_TABLE_OFF_TRANS_1 = std::make_pair((acs::AcsMode::OFF << 24) | 3, FixedArrayList()); -auto ACS_SEQUENCE_DETUMBLE = - std::make_pair(acs::AcsMode::DETUMBLE, FixedArrayList()); -auto ACS_TABLE_DETUMBLE_TGT = - std::make_pair((acs::AcsMode::DETUMBLE << 24) | 1, FixedArrayList()); -auto ACS_TABLE_DETUMBLE_TRANS_0 = - std::make_pair((acs::AcsMode::DETUMBLE << 24) | 2, FixedArrayList()); -auto ACS_TABLE_DETUMBLE_TRANS_1 = - std::make_pair((acs::AcsMode::DETUMBLE << 24) | 3, FixedArrayList()); - auto ACS_SEQUENCE_SAFE = std::make_pair(acs::AcsMode::SAFE, FixedArrayList()); auto ACS_TABLE_SAFE_TGT = std::make_pair((acs::AcsMode::SAFE << 24) | 1, FixedArrayList()); @@ -130,7 +120,6 @@ Subsystem& satsystem::acs::init() { buildOffSequence(ACS_SUBSYSTEM, entry); buildSafeSequence(ACS_SUBSYSTEM, entry); - buildDetumbleSequence(ACS_SUBSYSTEM, entry); buildIdleSequence(ACS_SUBSYSTEM, entry); buildTargetPtSequence(ACS_SUBSYSTEM, entry); buildTargetPtGsSequence(ACS_SUBSYSTEM, entry); @@ -206,8 +195,8 @@ void buildSafeSequence(Subsystem& ss, ModeListEntry& eh) { eh.setCheckSuccess(checkSuccess); check(sequence.insert(eh), ctxc); }; - // Build SAFE target - iht(objects::ACS_CONTROLLER, NML, acs::AcsMode::SAFE, ACS_TABLE_SAFE_TGT.second); + // Build SAFE target. Allow detumble submode. + iht(objects::ACS_CONTROLLER, acs::AcsMode::SAFE, 0, ACS_TABLE_SAFE_TGT.second, true); iht(objects::IMTQ_ASSY, NML, 0, ACS_TABLE_SAFE_TGT.second); iht(objects::SUS_BOARD_ASS, NML, 0, ACS_TABLE_SAFE_TGT.second, true); iht(objects::ACS_BOARD_ASS, NML, 0, ACS_TABLE_SAFE_TGT.second, true); @@ -225,7 +214,8 @@ void buildSafeSequence(Subsystem& ss, ModeListEntry& eh) { // SUS board transition table is defined above // Build SAFE transition 1 - iht(objects::ACS_CONTROLLER, NML, acs::AcsMode::SAFE, ACS_TABLE_SAFE_TRANS_1.second); + iht(objects::ACS_CONTROLLER, acs::AcsMode::SAFE, acs::SafeSubmode::DEFAULT, + ACS_TABLE_SAFE_TRANS_1.second); check(ss.addTable(&ACS_TABLE_SAFE_TRANS_1.second, ACS_TABLE_SAFE_TRANS_1.first, false, true), ctxc); @@ -238,61 +228,6 @@ void buildSafeSequence(Subsystem& ss, ModeListEntry& eh) { ctxc); } -void buildDetumbleSequence(Subsystem& ss, ModeListEntry& eh) { - std::string context = "satsystem::acs::buildDetumbleSequence"; - auto ctxc = context.c_str(); - // Insert Helper Table - auto iht = [&](object_id_t obj, Mode_t mode, Submode_t submode, - ArrayList& sequence, bool allowAllSubmodes = false) { - eh.setObject(obj); - eh.setMode(mode); - eh.setSubmode(submode); - if (allowAllSubmodes) { - eh.allowAllSubmodes(); - } - check(sequence.insert(eh), ctxc); - }; - // Insert Helper Sequence - auto ihs = [&](ArrayList& sequence, Mode_t tableId, uint32_t waitSeconds, - bool checkSuccess) { - eh.setTableId(tableId); - eh.setWaitSeconds(waitSeconds); - eh.setCheckSuccess(checkSuccess); - check(sequence.insert(eh), ctxc); - }; - // Build DETUMBLE target - iht(objects::ACS_CONTROLLER, NML, acs::AcsMode::DETUMBLE, ACS_TABLE_DETUMBLE_TGT.second); - iht(objects::IMTQ_ASSY, NML, 0, ACS_TABLE_DETUMBLE_TGT.second); - iht(objects::SUS_BOARD_ASS, NML, 0, ACS_TABLE_DETUMBLE_TGT.second, true); - iht(objects::ACS_BOARD_ASS, NML, 0, ACS_TABLE_DETUMBLE_TGT.second, true); - check(ss.addTable(&ACS_TABLE_DETUMBLE_TGT.second, ACS_TABLE_DETUMBLE_TGT.first, false, true), - ctxc); - - // Build DETUMBLE transition 0 - iht(objects::IMTQ_ASSY, NML, 0, ACS_TABLE_DETUMBLE_TRANS_0.second); - iht(objects::ACS_BOARD_ASS, NML, duallane::A_SIDE, ACS_TABLE_DETUMBLE_TRANS_0.second, true); - iht(objects::SUS_BOARD_ASS, NML, duallane::A_SIDE, ACS_TABLE_DETUMBLE_TRANS_0.second, true); - iht(objects::STR_ASSY, OFF, 0, ACS_TABLE_DETUMBLE_TRANS_0.second); - iht(objects::RW_ASSY, OFF, 0, ACS_TABLE_DETUMBLE_TRANS_0.second); - check(ss.addTable(&ACS_TABLE_DETUMBLE_TRANS_0.second, ACS_TABLE_DETUMBLE_TRANS_0.first, false, - true), - ctxc); - - // Build DETUMBLE transition 1 - iht(objects::ACS_CONTROLLER, NML, acs::AcsMode::DETUMBLE, ACS_TABLE_DETUMBLE_TRANS_1.second); - check(ss.addTable(&ACS_TABLE_DETUMBLE_TRANS_1.second, ACS_TABLE_DETUMBLE_TRANS_1.first, false, - true), - ctxc); - - // Build DETUMBLE sequence - ihs(ACS_SEQUENCE_DETUMBLE.second, ACS_TABLE_DETUMBLE_TGT.first, 0, true); - ihs(ACS_SEQUENCE_DETUMBLE.second, ACS_TABLE_DETUMBLE_TRANS_0.first, 0, false); - ihs(ACS_SEQUENCE_DETUMBLE.second, ACS_TABLE_DETUMBLE_TRANS_1.first, 0, false); - check(ss.addSequence(&ACS_SEQUENCE_DETUMBLE.second, ACS_SEQUENCE_DETUMBLE.first, - ACS_SEQUENCE_SAFE.first, false, true), - ctxc); -} - void buildIdleSequence(Subsystem& ss, ModeListEntry& eh) { std::string context = "satsystem::acs::buildIdleSequence"; auto ctxc = context.c_str(); @@ -316,7 +251,7 @@ void buildIdleSequence(Subsystem& ss, ModeListEntry& eh) { check(sequence.insert(eh), ctxc); }; // Build IDLE target - iht(objects::ACS_CONTROLLER, NML, acs::AcsMode::PTG_IDLE, ACS_TABLE_IDLE_TGT.second); + iht(objects::ACS_CONTROLLER, acs::AcsMode::PTG_IDLE, 0, ACS_TABLE_IDLE_TGT.second); iht(objects::IMTQ_ASSY, NML, 0, ACS_TABLE_IDLE_TGT.second); iht(objects::RW_ASSY, NML, 0, ACS_TABLE_IDLE_TGT.second); iht(objects::STR_ASSY, NML, 0, ACS_TABLE_IDLE_TGT.second); @@ -333,7 +268,7 @@ void buildIdleSequence(Subsystem& ss, ModeListEntry& eh) { ss.addTable(&ACS_TABLE_IDLE_TRANS_0.second, ACS_TABLE_IDLE_TRANS_0.first, false, true); // Build IDLE transition 1 - iht(objects::ACS_CONTROLLER, NML, acs::AcsMode::PTG_IDLE, ACS_TABLE_IDLE_TRANS_1.second); + iht(objects::ACS_CONTROLLER, acs::AcsMode::PTG_IDLE, 0, ACS_TABLE_IDLE_TRANS_1.second); ss.addTable(&ACS_TABLE_IDLE_TRANS_1.second, ACS_TABLE_IDLE_TRANS_1.first, false, true); // Build IDLE sequence @@ -368,7 +303,7 @@ void buildTargetPtSequence(Subsystem& ss, ModeListEntry& eh) { }; // Build TARGET PT table - iht(objects::ACS_CONTROLLER, NML, acs::AcsMode::PTG_TARGET, ACS_TABLE_PTG_TARGET_TGT.second); + iht(objects::ACS_CONTROLLER, acs::AcsMode::PTG_TARGET, 0, ACS_TABLE_PTG_TARGET_TGT.second); iht(objects::IMTQ_ASSY, NML, 0, ACS_TABLE_PTG_TARGET_TGT.second); iht(objects::SUS_BOARD_ASS, NML, 0, ACS_TABLE_PTG_TARGET_TGT.second, true); iht(objects::ACS_BOARD_ASS, NML, 0, ACS_TABLE_PTG_TARGET_TGT.second, true); @@ -379,7 +314,7 @@ void buildTargetPtSequence(Subsystem& ss, ModeListEntry& eh) { // Transition 0 already built // Build TARGET PT transition 1 - iht(objects::ACS_CONTROLLER, NML, acs::AcsMode::PTG_TARGET, ACS_TABLE_PTG_TARGET_TRANS_1.second); + iht(objects::ACS_CONTROLLER, acs::AcsMode::PTG_TARGET, 0, ACS_TABLE_PTG_TARGET_TRANS_1.second); check(ss.addTable(&ACS_TABLE_PTG_TARGET_TRANS_1.second, ACS_TABLE_PTG_TARGET_TRANS_1.first, false, true), ctxc); @@ -417,8 +352,7 @@ void buildTargetPtNadirSequence(Subsystem& ss, ModeListEntry& eh) { }; // Build TARGET PT table - iht(objects::ACS_CONTROLLER, NML, acs::AcsMode::PTG_TARGET, - ACS_TABLE_PTG_TARGET_NADIR_TGT.second); + iht(objects::ACS_CONTROLLER, acs::AcsMode::PTG_NADIR, 0, ACS_TABLE_PTG_TARGET_NADIR_TGT.second); iht(objects::IMTQ_ASSY, NML, 0, ACS_TABLE_PTG_TARGET_NADIR_TGT.second); iht(objects::SUS_BOARD_ASS, NML, 0, ACS_TABLE_PTG_TARGET_NADIR_TGT.second, true); iht(objects::ACS_BOARD_ASS, NML, 0, ACS_TABLE_PTG_TARGET_NADIR_TGT.second, true); @@ -430,7 +364,7 @@ void buildTargetPtNadirSequence(Subsystem& ss, ModeListEntry& eh) { // Transition 0 already built // Build TARGET PT transition 1 - iht(objects::ACS_CONTROLLER, NML, acs::AcsMode::PTG_NADIR, + iht(objects::ACS_CONTROLLER, acs::AcsMode::PTG_NADIR, 0, ACS_TABLE_PTG_TARGET_NADIR_TRANS_1.second); check(ss.addTable(TableEntry(ACS_TABLE_PTG_TARGET_NADIR_TRANS_1.first, &ACS_TABLE_PTG_TARGET_NADIR_TRANS_1.second)), @@ -471,8 +405,7 @@ void buildTargetPtGsSequence(Subsystem& ss, ModeListEntry& eh) { }; // Build TARGET PT table - iht(objects::ACS_CONTROLLER, NML, acs::AcsMode::PTG_TARGET_GS, - ACS_TABLE_PTG_TARGET_GS_TGT.second); + iht(objects::ACS_CONTROLLER, acs::AcsMode::PTG_TARGET_GS, 0, ACS_TABLE_PTG_TARGET_GS_TGT.second); iht(objects::IMTQ_ASSY, NML, 0, ACS_TABLE_PTG_TARGET_GS_TGT.second); iht(objects::SUS_BOARD_ASS, NML, 0, ACS_TABLE_PTG_TARGET_GS_TGT.second, true); iht(objects::ACS_BOARD_ASS, NML, 0, ACS_TABLE_PTG_TARGET_GS_TGT.second, true); @@ -484,7 +417,7 @@ void buildTargetPtGsSequence(Subsystem& ss, ModeListEntry& eh) { // Transition 0 already built // Build TARGET PT transition 1 - iht(objects::ACS_CONTROLLER, NML, acs::AcsMode::PTG_TARGET_GS, + iht(objects::ACS_CONTROLLER, acs::AcsMode::PTG_TARGET_GS, 0, ACS_TABLE_PTG_TARGET_GS_TRANS_1.second); check(ss.addTable(TableEntry(ACS_TABLE_PTG_TARGET_GS_TRANS_1.first, &ACS_TABLE_PTG_TARGET_GS_TRANS_1.second)), @@ -524,7 +457,7 @@ void buildTargetPtInertialSequence(Subsystem& ss, ModeListEntry& eh) { }; // Build TARGET PT table - iht(objects::ACS_CONTROLLER, NML, acs::AcsMode::PTG_INERTIAL, + iht(objects::ACS_CONTROLLER, acs::AcsMode::PTG_INERTIAL, 0, ACS_TABLE_PTG_TARGET_INERTIAL_TGT.second); iht(objects::IMTQ_ASSY, NML, 0, ACS_TABLE_PTG_TARGET_INERTIAL_TGT.second); iht(objects::SUS_BOARD_ASS, NML, 0, ACS_TABLE_PTG_TARGET_INERTIAL_TGT.second, true); @@ -537,7 +470,7 @@ void buildTargetPtInertialSequence(Subsystem& ss, ModeListEntry& eh) { // Transition 0 already built // Build TARGET PT transition 1 - iht(objects::ACS_CONTROLLER, NML, acs::AcsMode::PTG_INERTIAL, + iht(objects::ACS_CONTROLLER, acs::AcsMode::PTG_INERTIAL, 0, ACS_TABLE_PTG_TARGET_INERTIAL_TRANS_1.second); check(ss.addTable(TableEntry(ACS_TABLE_PTG_TARGET_INERTIAL_TRANS_1.first, &ACS_TABLE_PTG_TARGET_INERTIAL_TRANS_1.second)), diff --git a/mission/system/tree/system.cpp b/mission/system/tree/system.cpp index a7814fa1..dde32aef 100644 --- a/mission/system/tree/system.cpp +++ b/mission/system/tree/system.cpp @@ -82,11 +82,8 @@ void buildSafeSequence(Subsystem& ss, ModeListEntry& eh) { check(sequence.insert(eh), ctxc); }; - // Do no track ACS for now because it might jump to detumble mode and back to safe as part of - // normal operations. - // UPDATE: This could be re-enabled as soon as the detumble mode is a submode of - // ACS CTRL safe mode. - // iht(objects::ACS_SUBSYSTEM, acs::AcsMode::SAFE, 0, EIVE_TABLE_SAFE_TGT.second, true); + // Do no track submode to allow transitions to DETUMBLE submode. + iht(objects::ACS_SUBSYSTEM, acs::AcsMode::SAFE, 0, EIVE_TABLE_SAFE_TGT.second, true); iht(objects::PL_SUBSYSTEM, OFF, 0, EIVE_TABLE_SAFE_TGT.second); check(ss.addTable(TableEntry(EIVE_TABLE_SAFE_TGT.first, &EIVE_TABLE_SAFE_TGT.second)), ctxc); From 0b09816b4af89f848430b528419499eadfbdae58 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 10 Mar 2023 13:37:31 +0100 Subject: [PATCH 073/112] bump tmtc --- tmtc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tmtc b/tmtc index b0f51072..a249d718 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit b0f51072b20e4835a3e2143d8b3fb40d14240bfb +Subproject commit a249d7184011e2c739b5145f4dff74dccaa7020d From 2f4f7f088e1c74a3c182efc441b3643f26e84a54 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 10 Mar 2023 13:58:50 +0100 Subject: [PATCH 074/112] add missing break --- mission/controller/AcsController.cpp | 1 + tmtc | 2 +- 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/mission/controller/AcsController.cpp b/mission/controller/AcsController.cpp index 2ff5547b..ff0aa008 100644 --- a/mission/controller/AcsController.cpp +++ b/mission/controller/AcsController.cpp @@ -122,6 +122,7 @@ void AcsController::performControlOperation() { performDetumble(); break; } + break; case acs::PTG_IDLE: case acs::PTG_TARGET: case acs::PTG_TARGET_GS: diff --git a/tmtc b/tmtc index a249d718..d5685adb 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit a249d7184011e2c739b5145f4dff74dccaa7020d +Subproject commit d5685adb48c3b49eb923beaa2137705ec6d9db4d From 37a32bb6e953ad0d7e0f0d00becf243eec1b8646 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 10 Mar 2023 14:37:02 +0100 Subject: [PATCH 075/112] bump deps --- fsfw | 2 +- tmtc | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/fsfw b/fsfw index 23d9b44b..c162acb7 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit 23d9b44b3e02bb0d35e4622d125b48e9b44fee2c +Subproject commit c162acb7df6102e304057dcdda4fb93285052f03 diff --git a/tmtc b/tmtc index d5685adb..9f905524 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit d5685adb48c3b49eb923beaa2137705ec6d9db4d +Subproject commit 9f905524b6f2b10b1e8bcd9139c21a206cdf8aa3 From 2e431668dd50067a5f9267a1c002ffdaef2a1e2b Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 10 Mar 2023 14:59:52 +0100 Subject: [PATCH 076/112] larger event queues now --- CHANGELOG.md | 3 ++- fsfw | 2 +- mission/core/GenericFactory.cpp | 6 +++--- mission/system/tree/acsModeTree.cpp | 3 ++- 4 files changed, 8 insertions(+), 6 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index e8e4aaca..cb7c3c65 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -28,7 +28,8 @@ will consitute of a breaking change warranting a new major release: sometimes blocking for a long time. - Request raw MTM measurement twice for IMTQ, might reduce number of times measurement could not be retrieved. - +- Event manager and event service have larger queues now: 45 -> 120 for Service 5, 80 -> 120 for + evebt manager # [v1.36.0] 2023-03-08 eive-tmtc: v2.17.2 diff --git a/fsfw b/fsfw index c162acb7..4d6f6e6b 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit c162acb7df6102e304057dcdda4fb93285052f03 +Subproject commit 4d6f6e6b23b5c0486dad6be8abba7681114a05fe diff --git a/mission/core/GenericFactory.cpp b/mission/core/GenericFactory.cpp index c6a3e216..e8eb9210 100644 --- a/mission/core/GenericFactory.cpp +++ b/mission/core/GenericFactory.cpp @@ -86,7 +86,7 @@ EiveFaultHandler EIVE_FAULT_HANDLER; void ObjectFactory::produceGenericObjects(HealthTableIF** healthTable_, PusTmFunnel** pusFunnel, CfdpTmFunnel** cfdpFunnel, SdCardMountedIF& sdcMan) { // Framework objects - new EventManager(objects::EVENT_MANAGER); + new EventManager(objects::EVENT_MANAGER, 120); auto healthTable = new HealthTable(objects::HEALTH_TABLE); if (healthTable_ != nullptr) { *healthTable_ = healthTable; @@ -162,14 +162,14 @@ void ObjectFactory::produceGenericObjects(HealthTableIF** healthTable_, PusTmFun // PUS service stack new Service1TelecommandVerification(objects::PUS_SERVICE_1_VERIFICATION, config::EIVE_PUS_APID, - pus::PUS_SERVICE_1, objects::PUS_TM_FUNNEL, 20); + pus::PUS_SERVICE_1, objects::PUS_TM_FUNNEL, 40); new Service2DeviceAccess(objects::PUS_SERVICE_2_DEVICE_ACCESS, config::EIVE_PUS_APID, pus::PUS_SERVICE_2, 3, 10); new Service3Housekeeping(objects::PUS_SERVICE_3_HOUSEKEEPING, config::EIVE_PUS_APID, pus::PUS_SERVICE_3); new Service5EventReporting( PsbParams(objects::PUS_SERVICE_5_EVENT_REPORTING, config::EIVE_PUS_APID, pus::PUS_SERVICE_5), - 15, 45); + 15, 120); new Service8FunctionManagement(objects::PUS_SERVICE_8_FUNCTION_MGMT, config::EIVE_PUS_APID, pus::PUS_SERVICE_8, 16, 60); new Service9TimeManagement( diff --git a/mission/system/tree/acsModeTree.cpp b/mission/system/tree/acsModeTree.cpp index 95effa7f..9b0c573a 100644 --- a/mission/system/tree/acsModeTree.cpp +++ b/mission/system/tree/acsModeTree.cpp @@ -196,7 +196,8 @@ void buildSafeSequence(Subsystem& ss, ModeListEntry& eh) { check(sequence.insert(eh), ctxc); }; // Build SAFE target. Allow detumble submode. - iht(objects::ACS_CONTROLLER, acs::AcsMode::SAFE, 0, ACS_TABLE_SAFE_TGT.second, true); + iht(objects::ACS_CONTROLLER, acs::AcsMode::SAFE, acs::SafeSubmode::DEFAULT, + ACS_TABLE_SAFE_TGT.second, true); iht(objects::IMTQ_ASSY, NML, 0, ACS_TABLE_SAFE_TGT.second); iht(objects::SUS_BOARD_ASS, NML, 0, ACS_TABLE_SAFE_TGT.second, true); iht(objects::ACS_BOARD_ASS, NML, 0, ACS_TABLE_SAFE_TGT.second, true); From b6fc9d65b7852c3fc6fa0c38aba4f72424beebf4 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 10 Mar 2023 15:01:59 +0100 Subject: [PATCH 077/112] changelog --- CHANGELOG.md | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index cb7c3c65..35890493 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -29,7 +29,10 @@ will consitute of a breaking change warranting a new major release: - Request raw MTM measurement twice for IMTQ, might reduce number of times measurement could not be retrieved. - Event manager and event service have larger queues now: 45 -> 120 for Service 5, 80 -> 120 for - evebt manager + event manager +- ACS mode changes: The ACS CTRL submodes are now modes. DETUBMLE is now submode of SAFE mode. +- EIVE system now tracks the mode of the ACS subsyste in SAFE mode. + # [v1.36.0] 2023-03-08 eive-tmtc: v2.17.2 From 6452242f2f25485c240f344c37d908986fde8671 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 10 Mar 2023 15:06:05 +0100 Subject: [PATCH 078/112] fix merge conflict properly --- mission/system/objects/EiveSystem.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/mission/system/objects/EiveSystem.cpp b/mission/system/objects/EiveSystem.cpp index 17cd85d0..ee1db4c2 100644 --- a/mission/system/objects/EiveSystem.cpp +++ b/mission/system/objects/EiveSystem.cpp @@ -89,7 +89,7 @@ void EiveSystem::handleEventMessages() { case EventMessage::EVENT_MESSAGE: if (event.getEvent() == acs::SAFE_RATE_VIOLATION) { CommandMessage msg; - ModeMessage::setCmdModeMessage(msg, acs::AcsMode::DETUMBLE, 0); + ModeMessage::setCmdModeMessage(msg, acs::AcsMode::SAFE, acs::SafeSubmode::DETUMBLE); status = commandQueue->sendMessage(commandQueue->getId(), &msg); if (result != returnvalue::OK) { sif::error << "AcsSubsystem: sending DETUMBLE mode cmd to self has failed" << std::endl; @@ -97,7 +97,7 @@ void EiveSystem::handleEventMessages() { } if (event.getEvent() == acs::SAFE_RATE_RECOVERY) { CommandMessage msg; - ModeMessage::setCmdModeMessage(msg, acs::AcsMode::SAFE, 0); + ModeMessage::setCmdModeMessage(msg, acs::AcsMode::SAFE, acs::SafeSubmode::DEFAULT); status = commandQueue->sendMessage(commandQueue->getId(), &msg); if (status != returnvalue::OK) { sif::error << "AcsSubsystem: sending SAFE mode cmd to self has failed" << std::endl; From 4a386ad3d18a8d19bb1466e413c2e0447ea284e1 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 10 Mar 2023 15:21:36 +0100 Subject: [PATCH 079/112] simplification --- CHANGELOG.md | 3 ++- mission/controller/AcsController.cpp | 2 ++ mission/controller/acs/AcsParameters.h | 4 ++-- mission/system/objects/EiveSystem.cpp | 31 ++------------------------ 4 files changed, 8 insertions(+), 32 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 48c18074..e153b91b 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -22,6 +22,8 @@ will consitute of a breaking change warranting a new major release: ## Changed +- ACS CTRL transition to DETUBMLE is now done in CTRL internally. No + system level handling necessary anymore. - More fixes and improvements for SD card handling. Extend SD card setup in core controller to create full initial state for SD card manager are core controller as early as possible, turn execution of setup file update blocking. This might solve the issue with the SD card manager @@ -47,7 +49,6 @@ eive-tmtc: v2.17.2 ## Changed -- Move ACS event handling to system component. - Persistent TM stores will now create new files on each reboot. - Fast ACS subsystem commanding: Command SUS board consecutively with other devices now - Star Tracker: Use ground confguration for EM and flight config for FM by default. diff --git a/mission/controller/AcsController.cpp b/mission/controller/AcsController.cpp index ff0aa008..2ae2a7bd 100644 --- a/mission/controller/AcsController.cpp +++ b/mission/controller/AcsController.cpp @@ -198,6 +198,7 @@ void AcsController::performSafe() { detumbleCounter = 0; // Triggers detumble mode transition in subsystem triggerEvent(acs::SAFE_RATE_VIOLATION); + startTransition(mode, acs::SafeSubmode::DETUMBLE); } updateCtrlValData(errAng); @@ -245,6 +246,7 @@ void AcsController::performDetumble() { detumbleCounter = 0; // Triggers safe mode transition in subsystem triggerEvent(acs::SAFE_RATE_RECOVERY); + startTransition(mode, acs::SafeSubmode::DEFAULT); } disableCtrlValData(); diff --git a/mission/controller/acs/AcsParameters.h b/mission/controller/acs/AcsParameters.h index 11de10a3..8471fc44 100644 --- a/mission/controller/acs/AcsParameters.h +++ b/mission/controller/acs/AcsParameters.h @@ -924,8 +924,8 @@ class AcsParameters : public HasParametersIF { } magnetorquesParameter; struct DetumbleParameter { - uint8_t detumblecounter = 75; // 30 s - double omegaDetumbleStart = 2 * M_PI / 180; + uint8_t detumblecounter = 75; // 30 s + double omegaDetumbleStart = 0; // 2 * M_PI / 180; double omegaDetumbleEnd = 0.4 * M_PI / 180; double gainD = pow(10.0, -3.3); } detumbleParameter; diff --git a/mission/system/objects/EiveSystem.cpp b/mission/system/objects/EiveSystem.cpp index ee1db4c2..bb2a229d 100644 --- a/mission/system/objects/EiveSystem.cpp +++ b/mission/system/objects/EiveSystem.cpp @@ -1,5 +1,6 @@ #include "EiveSystem.h" +#include #include #include #include @@ -65,44 +66,16 @@ ReturnValue_t EiveSystem::initialize() { << std::endl; #endif return ObjectManagerIF::CHILD_INIT_FAILED; - ; } - result = - manager->subscribeToEvent(eventQueue->getId(), event::getEventId(acs::MULTIPLE_RW_INVALID)); - if (result != returnvalue::OK) { - sif::error << "AcsSubsystem: Subscribing for acs::MULTIPLE_RW_INVALID failed" << std::endl; - } - result = manager->subscribeToEvent(eventQueue->getId(), - event::getEventId(acs::MEKF_INVALID_MODE_VIOLATION)); - if (result != returnvalue::OK) { - sif::error << "AcsSubsystem: Subscribing for acs::MULTIPLE_RW_INVALID failed" << std::endl; - } - return returnvalue::OK; + return Subsystem::initialize(); } void EiveSystem::handleEventMessages() { EventMessage event; for (ReturnValue_t result = eventQueue->receiveMessage(&event); result == returnvalue::OK; result = eventQueue->receiveMessage(&event)) { - ReturnValue_t status; switch (event.getMessageId()) { case EventMessage::EVENT_MESSAGE: - if (event.getEvent() == acs::SAFE_RATE_VIOLATION) { - CommandMessage msg; - ModeMessage::setCmdModeMessage(msg, acs::AcsMode::SAFE, acs::SafeSubmode::DETUMBLE); - status = commandQueue->sendMessage(commandQueue->getId(), &msg); - if (result != returnvalue::OK) { - sif::error << "AcsSubsystem: sending DETUMBLE mode cmd to self has failed" << std::endl; - } - } - if (event.getEvent() == acs::SAFE_RATE_RECOVERY) { - CommandMessage msg; - ModeMessage::setCmdModeMessage(msg, acs::AcsMode::SAFE, acs::SafeSubmode::DEFAULT); - status = commandQueue->sendMessage(commandQueue->getId(), &msg); - if (status != returnvalue::OK) { - sif::error << "AcsSubsystem: sending SAFE mode cmd to self has failed" << std::endl; - } - } break; default: sif::debug << "AcsSubsystem::performChildOperation: Did not subscribe " From 04541b4a19a8dd227c259059b24c1d2e6179dba4 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 10 Mar 2023 15:35:17 +0100 Subject: [PATCH 080/112] revert change --- mission/controller/acs/AcsParameters.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/mission/controller/acs/AcsParameters.h b/mission/controller/acs/AcsParameters.h index 8471fc44..11de10a3 100644 --- a/mission/controller/acs/AcsParameters.h +++ b/mission/controller/acs/AcsParameters.h @@ -924,8 +924,8 @@ class AcsParameters : public HasParametersIF { } magnetorquesParameter; struct DetumbleParameter { - uint8_t detumblecounter = 75; // 30 s - double omegaDetumbleStart = 0; // 2 * M_PI / 180; + uint8_t detumblecounter = 75; // 30 s + double omegaDetumbleStart = 2 * M_PI / 180; double omegaDetumbleEnd = 0.4 * M_PI / 180; double gainD = pow(10.0, -3.3); } detumbleParameter; From bc0f1cad7b039ef261127676f012574a90c9b3ec Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 10 Mar 2023 15:36:24 +0100 Subject: [PATCH 081/112] re-generate csvs --- bsp_hosted/fsfwconfig/events/translateEvents.cpp | 2 +- bsp_hosted/fsfwconfig/objects/translateObjects.cpp | 6 +++--- generators/bsp_hosted_objects.csv | 2 +- generators/bsp_q7s_objects.csv | 2 +- generators/events/translateEvents.cpp | 2 +- generators/objects/translateObjects.cpp | 6 +++--- linux/fsfwconfig/events/translateEvents.cpp | 2 +- linux/fsfwconfig/objects/translateObjects.cpp | 6 +++--- tmtc | 2 +- 9 files changed, 15 insertions(+), 15 deletions(-) diff --git a/bsp_hosted/fsfwconfig/events/translateEvents.cpp b/bsp_hosted/fsfwconfig/events/translateEvents.cpp index ed1436e0..26bc5118 100644 --- a/bsp_hosted/fsfwconfig/events/translateEvents.cpp +++ b/bsp_hosted/fsfwconfig/events/translateEvents.cpp @@ -1,7 +1,7 @@ /** * @brief Auto-generated event translation file. Contains 269 translations. * @details - * Generated on: 2023-03-08 16:44:32 + * Generated on: 2023-03-10 15:36:00 */ #include "translateEvents.h" diff --git a/bsp_hosted/fsfwconfig/objects/translateObjects.cpp b/bsp_hosted/fsfwconfig/objects/translateObjects.cpp index ad419fa0..4faacd00 100644 --- a/bsp_hosted/fsfwconfig/objects/translateObjects.cpp +++ b/bsp_hosted/fsfwconfig/objects/translateObjects.cpp @@ -2,7 +2,7 @@ * @brief Auto-generated object translation file. * @details * Contains 160 translations. - * Generated on: 2023-03-08 16:44:32 + * Generated on: 2023-03-10 15:36:00 */ #include "translateObjects.h" @@ -138,7 +138,7 @@ const char *HEATER_3_OBC_BRD_STRING = "HEATER_3_OBC_BRD"; const char *HEATER_4_CAMERA_STRING = "HEATER_4_CAMERA"; const char *HEATER_5_STR_STRING = "HEATER_5_STR"; const char *HEATER_6_DRO_STRING = "HEATER_6_DRO"; -const char *HEATER_7_HPA_STRING = "HEATER_7_HPA"; +const char *HEATER_7_SYRLINKS_STRING = "HEATER_7_SYRLINKS"; const char *ACS_BOARD_ASS_STRING = "ACS_BOARD_ASS"; const char *SUS_BOARD_ASS_STRING = "SUS_BOARD_ASS"; const char *TCS_BOARD_ASS_STRING = "TCS_BOARD_ASS"; @@ -434,7 +434,7 @@ const char *translateObject(object_id_t object) { case 0x60000006: return HEATER_6_DRO_STRING; case 0x60000007: - return HEATER_7_HPA_STRING; + return HEATER_7_SYRLINKS_STRING; case 0x73000001: return ACS_BOARD_ASS_STRING; case 0x73000002: diff --git a/generators/bsp_hosted_objects.csv b/generators/bsp_hosted_objects.csv index 254ebe87..0b970626 100644 --- a/generators/bsp_hosted_objects.csv +++ b/generators/bsp_hosted_objects.csv @@ -130,7 +130,7 @@ 0x60000004;HEATER_4_CAMERA 0x60000005;HEATER_5_STR 0x60000006;HEATER_6_DRO -0x60000007;HEATER_7_HPA +0x60000007;HEATER_7_SYRLINKS 0x73000001;ACS_BOARD_ASS 0x73000002;SUS_BOARD_ASS 0x73000003;TCS_BOARD_ASS diff --git a/generators/bsp_q7s_objects.csv b/generators/bsp_q7s_objects.csv index c1171c16..cc893edd 100644 --- a/generators/bsp_q7s_objects.csv +++ b/generators/bsp_q7s_objects.csv @@ -135,7 +135,7 @@ 0x60000004;HEATER_4_CAMERA 0x60000005;HEATER_5_STR 0x60000006;HEATER_6_DRO -0x60000007;HEATER_7_HPA +0x60000007;HEATER_7_SYRLINKS 0x73000001;ACS_BOARD_ASS 0x73000002;SUS_BOARD_ASS 0x73000003;TCS_BOARD_ASS diff --git a/generators/events/translateEvents.cpp b/generators/events/translateEvents.cpp index ed1436e0..26bc5118 100644 --- a/generators/events/translateEvents.cpp +++ b/generators/events/translateEvents.cpp @@ -1,7 +1,7 @@ /** * @brief Auto-generated event translation file. Contains 269 translations. * @details - * Generated on: 2023-03-08 16:44:32 + * Generated on: 2023-03-10 15:36:00 */ #include "translateEvents.h" diff --git a/generators/objects/translateObjects.cpp b/generators/objects/translateObjects.cpp index 4950a981..647a23bd 100644 --- a/generators/objects/translateObjects.cpp +++ b/generators/objects/translateObjects.cpp @@ -2,7 +2,7 @@ * @brief Auto-generated object translation file. * @details * Contains 164 translations. - * Generated on: 2023-03-08 16:44:32 + * Generated on: 2023-03-10 15:36:00 */ #include "translateObjects.h" @@ -143,7 +143,7 @@ const char *HEATER_3_OBC_BRD_STRING = "HEATER_3_OBC_BRD"; const char *HEATER_4_CAMERA_STRING = "HEATER_4_CAMERA"; const char *HEATER_5_STR_STRING = "HEATER_5_STR"; const char *HEATER_6_DRO_STRING = "HEATER_6_DRO"; -const char *HEATER_7_HPA_STRING = "HEATER_7_HPA"; +const char *HEATER_7_SYRLINKS_STRING = "HEATER_7_SYRLINKS"; const char *ACS_BOARD_ASS_STRING = "ACS_BOARD_ASS"; const char *SUS_BOARD_ASS_STRING = "SUS_BOARD_ASS"; const char *TCS_BOARD_ASS_STRING = "TCS_BOARD_ASS"; @@ -448,7 +448,7 @@ const char *translateObject(object_id_t object) { case 0x60000006: return HEATER_6_DRO_STRING; case 0x60000007: - return HEATER_7_HPA_STRING; + return HEATER_7_SYRLINKS_STRING; case 0x73000001: return ACS_BOARD_ASS_STRING; case 0x73000002: diff --git a/linux/fsfwconfig/events/translateEvents.cpp b/linux/fsfwconfig/events/translateEvents.cpp index ed1436e0..26bc5118 100644 --- a/linux/fsfwconfig/events/translateEvents.cpp +++ b/linux/fsfwconfig/events/translateEvents.cpp @@ -1,7 +1,7 @@ /** * @brief Auto-generated event translation file. Contains 269 translations. * @details - * Generated on: 2023-03-08 16:44:32 + * Generated on: 2023-03-10 15:36:00 */ #include "translateEvents.h" diff --git a/linux/fsfwconfig/objects/translateObjects.cpp b/linux/fsfwconfig/objects/translateObjects.cpp index 4950a981..647a23bd 100644 --- a/linux/fsfwconfig/objects/translateObjects.cpp +++ b/linux/fsfwconfig/objects/translateObjects.cpp @@ -2,7 +2,7 @@ * @brief Auto-generated object translation file. * @details * Contains 164 translations. - * Generated on: 2023-03-08 16:44:32 + * Generated on: 2023-03-10 15:36:00 */ #include "translateObjects.h" @@ -143,7 +143,7 @@ const char *HEATER_3_OBC_BRD_STRING = "HEATER_3_OBC_BRD"; const char *HEATER_4_CAMERA_STRING = "HEATER_4_CAMERA"; const char *HEATER_5_STR_STRING = "HEATER_5_STR"; const char *HEATER_6_DRO_STRING = "HEATER_6_DRO"; -const char *HEATER_7_HPA_STRING = "HEATER_7_HPA"; +const char *HEATER_7_SYRLINKS_STRING = "HEATER_7_SYRLINKS"; const char *ACS_BOARD_ASS_STRING = "ACS_BOARD_ASS"; const char *SUS_BOARD_ASS_STRING = "SUS_BOARD_ASS"; const char *TCS_BOARD_ASS_STRING = "TCS_BOARD_ASS"; @@ -448,7 +448,7 @@ const char *translateObject(object_id_t object) { case 0x60000006: return HEATER_6_DRO_STRING; case 0x60000007: - return HEATER_7_HPA_STRING; + return HEATER_7_SYRLINKS_STRING; case 0x73000001: return ACS_BOARD_ASS_STRING; case 0x73000002: diff --git a/tmtc b/tmtc index 0add5c6a..e32a6ded 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 0add5c6ac5eda7e6b37e966e84d3122d0d44b80d +Subproject commit e32a6ded6661d450dbc75a7ab0194e8048af3d5c From 49d060d20e5a4e7bac52f02734f9c9be8109f33d Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 10 Mar 2023 15:37:34 +0100 Subject: [PATCH 082/112] bump tmtc --- tmtc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tmtc b/tmtc index 9f905524..e32a6ded 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 9f905524b6f2b10b1e8bcd9139c21a206cdf8aa3 +Subproject commit e32a6ded6661d450dbc75a7ab0194e8048af3d5c From 879bce4f76639cbe49b3088b3101cc5118b8aa18 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 10 Mar 2023 16:22:46 +0100 Subject: [PATCH 083/112] further increase store size --- mission/core/GenericFactory.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/mission/core/GenericFactory.cpp b/mission/core/GenericFactory.cpp index 2c1a39df..fe1a6319 100644 --- a/mission/core/GenericFactory.cpp +++ b/mission/core/GenericFactory.cpp @@ -109,8 +109,8 @@ void ObjectFactory::produceGenericObjects(HealthTableIF** healthTable_, PusTmFun } { - PoolManager::LocalPoolConfig poolCfg = {{400, 32}, {400, 64}, {250, 128}, - {150, 512}, {150, 1024}, {150, 2048}}; + PoolManager::LocalPoolConfig poolCfg = {{300, 32}, {300, 32}, {400, 64}, {250, 128}, + {150, 512}, {150, 1024}, {150, 1024}, {150, 2048}}; *tmStore = new PoolManager(objects::TM_STORE, poolCfg); } From e0024e738e6f6bfc2c5bc3cbf11a4cecbd8c8a51 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 10 Mar 2023 16:49:12 +0100 Subject: [PATCH 084/112] dedicated store for RAM to FileStore IPC --- bsp_q7s/fmObjectFactory.cpp | 2 ++ common/config/eive/objects.h | 1 + mission/core/GenericFactory.cpp | 22 ++++++++++------------ mission/tmtc/CfdpTmFunnel.cpp | 18 ++++++++++++++++-- mission/tmtc/CfdpTmFunnel.h | 5 ++++- mission/tmtc/PusTmFunnel.cpp | 8 ++++---- mission/tmtc/PusTmFunnel.h | 4 +++- 7 files changed, 40 insertions(+), 20 deletions(-) diff --git a/bsp_q7s/fmObjectFactory.cpp b/bsp_q7s/fmObjectFactory.cpp index 3aab4409..34a7c9dc 100644 --- a/bsp_q7s/fmObjectFactory.cpp +++ b/bsp_q7s/fmObjectFactory.cpp @@ -1,4 +1,6 @@ #include +#include +#include #include #include "OBSWConfig.h" diff --git a/common/config/eive/objects.h b/common/config/eive/objects.h index 00b509f2..e22133e2 100644 --- a/common/config/eive/objects.h +++ b/common/config/eive/objects.h @@ -172,6 +172,7 @@ enum commonObjects : uint32_t { LOG_STORE_AND_TM_TASK = 0x73040001, HK_STORE_AND_TM_TASK = 0x73040002, CFDP_STORE_AND_TM_TASK = 0x73040003, + DOWNLINK_RAM_STORE = 0x73040004, // Other stuff THERMAL_TEMP_INSERTER = 0x90000003, diff --git a/mission/core/GenericFactory.cpp b/mission/core/GenericFactory.cpp index fe1a6319..b6fc5ca1 100644 --- a/mission/core/GenericFactory.cpp +++ b/mission/core/GenericFactory.cpp @@ -119,6 +119,9 @@ void ObjectFactory::produceGenericObjects(HealthTableIF** healthTable_, PusTmFun {100, 256}, {50, 512}, {50, 1024}, {10, 2048}}; *ipcStore = new PoolManager(objects::IPC_STORE, poolCfg); } + PoolManager::LocalPoolConfig poolCfg = {{300, 32}, {400, 64}, {250, 128}, + {150, 512}, {150, 1024}, {150, 2048}}; + auto* ramToFileStore = new PoolManager(objects::DOWNLINK_RAM_STORE, poolCfg); #if OBSW_ADD_TCPIP_SERVERS == 1 #if OBSW_ADD_TMTC_UDP_SERVER == 1 @@ -148,18 +151,17 @@ void ObjectFactory::produceGenericObjects(HealthTableIF** healthTable_, PusTmFun PusTmFunnel::FunnelCfg cfdpFunnelCfg(objects::CFDP_TM_FUNNEL, "CfdpTmFunnel", **tmStore, **ipcStore, 50); - *cfdpFunnel = new CfdpTmFunnel(cfdpFunnelCfg, config::EIVE_CFDP_APID); + *cfdpFunnel = new CfdpTmFunnel(cfdpFunnelCfg, *ramToFileStore, config::EIVE_CFDP_APID); PusTmFunnel::FunnelCfg pusFunnelCfg(objects::PUS_TM_FUNNEL, "PusTmFunnel", **tmStore, **ipcStore, config::MAX_PUS_FUNNEL_QUEUE_DEPTH); // The PUS funnel routes all live TM to the live destinations and to the TM stores. - *pusFunnel = new PusTmFunnel(pusFunnelCfg, *timeStamper, sdcMan); + *pusFunnel = new PusTmFunnel(pusFunnelCfg, *ramToFileStore, *timeStamper, sdcMan); // MISC store and PUS funnel to MISC store routing - // TODO: Make queue depth configurable { PersistentTmStoreArgs storeArgs(objects::MISC_TM_STORE, "tm", "misc", - RolloverInterval::HOURLY, 2, **tmStore, sdcMan); + RolloverInterval::HOURLY, 2, *ramToFileStore, sdcMan); stores.miscStore = new PersistentTmStoreWithTmQueue(storeArgs, "MISC STORE", config::MISC_STORE_QUEUE_SIZE); (*pusFunnel) @@ -168,10 +170,9 @@ void ObjectFactory::produceGenericObjects(HealthTableIF** healthTable_, PusTmFun } // OK store and PUS Funnel to OK store routing - // TODO: Make queue depth configurable { PersistentTmStoreArgs storeArgs(objects::OK_TM_STORE, "tm", "ok", RolloverInterval::MINUTELY, - 30, **tmStore, sdcMan); + 30, *ramToFileStore, sdcMan); stores.okStore = new PersistentTmStoreWithTmQueue(storeArgs, "OK STORE", config::OK_STORE_QUEUE_SIZE); (*pusFunnel) @@ -180,10 +181,9 @@ void ObjectFactory::produceGenericObjects(HealthTableIF** healthTable_, PusTmFun } // NOT OK store and PUS funnel to NOT OK store routing - // TODO: Make queue depth configurable { PersistentTmStoreArgs storeArgs(objects::NOT_OK_TM_STORE, "tm", "nok", - RolloverInterval::MINUTELY, 30, **tmStore, sdcMan); + RolloverInterval::MINUTELY, 30, *ramToFileStore, sdcMan); stores.notOkStore = new PersistentTmStoreWithTmQueue(storeArgs, "NOT OK STORE", config::NOK_STORE_QUEUE_SIZE); (*pusFunnel) @@ -192,10 +192,9 @@ void ObjectFactory::produceGenericObjects(HealthTableIF** healthTable_, PusTmFun } // HK store and PUS funnel to HK store routing - // TODO: Make queue depth configurable { PersistentTmStoreArgs storeArgs(objects::HK_TM_STORE, "tm", "hk", RolloverInterval::MINUTELY, - 15, **tmStore, sdcMan); + 15, *ramToFileStore, sdcMan); stores.hkStore = new PersistentTmStoreWithTmQueue(storeArgs, "HK STORE", config::HK_STORE_QUEUE_SIZE); (*pusFunnel) @@ -204,10 +203,9 @@ void ObjectFactory::produceGenericObjects(HealthTableIF** healthTable_, PusTmFun } // CFDP store and PUS funnel to CFDP store routing - // TODO: Make queue depth configurable { PersistentTmStoreArgs storeArgs(objects::CFDP_TM_STORE, "tm", "cfdp", - RolloverInterval::MINUTELY, 30, **tmStore, sdcMan); + RolloverInterval::MINUTELY, 30, *ramToFileStore, sdcMan); stores.cfdpStore = new PersistentTmStoreWithTmQueue(storeArgs, "CFDP STORE", config::CFDP_STORE_QUEUE_SIZE); diff --git a/mission/tmtc/CfdpTmFunnel.cpp b/mission/tmtc/CfdpTmFunnel.cpp index 26b308da..8bbbb3f6 100644 --- a/mission/tmtc/CfdpTmFunnel.cpp +++ b/mission/tmtc/CfdpTmFunnel.cpp @@ -4,8 +4,12 @@ #include "fsfw/tmtcpacket/ccsds/SpacePacketCreator.h" #include "fsfw/tmtcservices/TmTcMessage.h" -CfdpTmFunnel::CfdpTmFunnel(TmFunnelBase::FunnelCfg cfg, uint16_t cfdpInCcsdsApid) - : TmFunnelBase(cfg), cfdpInCcsdsApid(cfdpInCcsdsApid) {} +CfdpTmFunnel::CfdpTmFunnel(TmFunnelBase::FunnelCfg cfg, MessageQueueId_t fileStoreDest, + StorageManagerIF& ramToFileStore, uint16_t cfdpInCcsdsApid) + : TmFunnelBase(cfg), + fileStoreDest(fileStoreDest), + ramToFileStore(ramToFileStore), + cfdpInCcsdsApid(cfdpInCcsdsApid) {} const char* CfdpTmFunnel::getName() const { return "CFDP TM Funnel"; } @@ -76,5 +80,15 @@ ReturnValue_t CfdpTmFunnel::handlePacket(TmTcMessage& msg) { msg.setStorageId(newStoreId); store_address_t origStoreId = newStoreId; // TODO: Also route to persistent TM store + + store_address_t storageId; + result = ramToFileStore.addData(&storageId, newPacketData, packetLen); + TmTcMessage fileMsg(storageId); + if (result != returnvalue::OK) { + sif::error << "PusLiveDemux::handlePacket: Store too full to create data copy" << std::endl; + } else { + tmQueue->sendMessage(fileStoreDest, &fileMsg); + } + return demultiplexLivePackets(origStoreId, newPacketData, packetLen); } diff --git a/mission/tmtc/CfdpTmFunnel.h b/mission/tmtc/CfdpTmFunnel.h index 717573a0..a4d1bc70 100644 --- a/mission/tmtc/CfdpTmFunnel.h +++ b/mission/tmtc/CfdpTmFunnel.h @@ -12,7 +12,8 @@ class CfdpTmFunnel : public TmFunnelBase { public: - CfdpTmFunnel(TmFunnelBase::FunnelCfg cfg, uint16_t cfdpInCcsdsApid); + CfdpTmFunnel(TmFunnelBase::FunnelCfg cfg, MessageQueueId_t fileStoreDest, + StorageManagerIF& ramToFileStore, uint16_t cfdpInCcsdsApid); [[nodiscard]] const char* getName() const override; ReturnValue_t performOperation(uint8_t opCode); ReturnValue_t initialize() override; @@ -20,6 +21,8 @@ class CfdpTmFunnel : public TmFunnelBase { private: ReturnValue_t handlePacket(TmTcMessage& msg); + MessageQueueId_t fileStoreDest; + StorageManagerIF& ramToFileStore; uint16_t sourceSequenceCount = 0; uint16_t cfdpInCcsdsApid; }; diff --git a/mission/tmtc/PusTmFunnel.cpp b/mission/tmtc/PusTmFunnel.cpp index 69d60a52..dbc8f1c4 100644 --- a/mission/tmtc/PusTmFunnel.cpp +++ b/mission/tmtc/PusTmFunnel.cpp @@ -10,9 +10,9 @@ #include "fsfw/tmtcpacket/pus/tm/PusTmZcWriter.h" #include "tmtc/pusIds.h" -PusTmFunnel::PusTmFunnel(TmFunnelBase::FunnelCfg cfg, TimeReaderIF &timeReader, - SdCardMountedIF &sdcMan) - : TmFunnelBase(cfg), timeReader(timeReader), sdcMan(sdcMan) {} +PusTmFunnel::PusTmFunnel(TmFunnelBase::FunnelCfg cfg, StorageManagerIF &ramToFileStore, + TimeReaderIF &timeReader, SdCardMountedIF &sdcMan) + : TmFunnelBase(cfg), ramToFileStore(ramToFileStore), timeReader(timeReader), sdcMan(sdcMan) {} PusTmFunnel::~PusTmFunnel() = default; @@ -66,7 +66,7 @@ ReturnValue_t PusTmFunnel::handleTmPacket(TmTcMessage &message) { MessageQueueId_t destination; if (persistentTmMap.packetMatches(packet, destination)) { store_address_t storageId; - result = tmStore.addData(&storageId, packetData, size); + result = ramToFileStore.addData(&storageId, packetData, size); TmTcMessage msg(storageId); if (result != returnvalue::OK) { sif::error << "PusLiveDemux::handlePacket: Store too full to create data copy" << std::endl; diff --git a/mission/tmtc/PusTmFunnel.h b/mission/tmtc/PusTmFunnel.h index 6c1835d1..ba6e8d3e 100644 --- a/mission/tmtc/PusTmFunnel.h +++ b/mission/tmtc/PusTmFunnel.h @@ -24,7 +24,8 @@ */ class PusTmFunnel : public TmFunnelBase { public: - PusTmFunnel(TmFunnelBase::FunnelCfg cfg, TimeReaderIF &timeReader, SdCardMountedIF &sdcMan); + PusTmFunnel(TmFunnelBase::FunnelCfg cfg, StorageManagerIF &ramToFileStore, + TimeReaderIF &timeReader, SdCardMountedIF &sdcMan); [[nodiscard]] const char *getName() const override; ~PusTmFunnel() override; @@ -36,6 +37,7 @@ class PusTmFunnel : public TmFunnelBase { static constexpr dur_millis_t TV_UPDATE_INTERVAL_SECS = 60 * 5; uint16_t sourceSequenceCount = 0; + StorageManagerIF &ramToFileStore; TimeReaderIF &timeReader; bool storesInitialized = false; SdCardMountedIF &sdcMan; From 97b4db10bf1de27892f6583ec4714621a8f04404 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 10 Mar 2023 16:49:53 +0100 Subject: [PATCH 085/112] remove TODO --- mission/tmtc/CfdpTmFunnel.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/mission/tmtc/CfdpTmFunnel.cpp b/mission/tmtc/CfdpTmFunnel.cpp index 8bbbb3f6..46915b82 100644 --- a/mission/tmtc/CfdpTmFunnel.cpp +++ b/mission/tmtc/CfdpTmFunnel.cpp @@ -79,7 +79,6 @@ ReturnValue_t CfdpTmFunnel::handlePacket(TmTcMessage& msg) { tmStore.deleteData(msg.getStorageId()); msg.setStorageId(newStoreId); store_address_t origStoreId = newStoreId; - // TODO: Also route to persistent TM store store_address_t storageId; result = ramToFileStore.addData(&storageId, newPacketData, packetLen); From bce8df376a9d314734d1968f90e1aa748def3884 Mon Sep 17 00:00:00 2001 From: meggert Date: Fri, 10 Mar 2023 17:21:52 +0100 Subject: [PATCH 086/112] changed antistiction --- CHANGELOG.md | 1 + mission/controller/acs/AcsParameters.h | 6 ++-- mission/controller/acs/control/PtgCtrl.cpp | 39 ++++++++++------------ mission/controller/acs/control/PtgCtrl.h | 25 +++++--------- 4 files changed, 29 insertions(+), 42 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index a6d45d74..3ee2279b 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -47,6 +47,7 @@ will consitute of a breaking change warranting a new major release: - The `detumbleCounter` now does not get hard reset anymore, if the critical rate does not get violated anymore. Instead it is incrementally reset. +- The RW antistiction now only takes the RW speeds in account. # [v1.36.0] 2023-03-08 diff --git a/mission/controller/acs/AcsParameters.h b/mission/controller/acs/AcsParameters.h index 98cbd9ad..822cfabc 100644 --- a/mission/controller/acs/AcsParameters.h +++ b/mission/controller/acs/AcsParameters.h @@ -784,9 +784,9 @@ class AcsParameters : public HasParametersIF { struct RwHandlingParameters { double inertiaWheel = 0.000028198; double maxTrq = 0.0032; // 3.2 [mNm] - int32_t maxRwSpeed = 65000; // 0.1 RPM - int32_t stictionSpeed = 100; // RPM - int32_t stictionReleaseSpeed = 120; // RPM + int32_t maxRwSpeed = 65000; // 0.1 RPM + int32_t stictionSpeed = 1000; // 0.1 RPM + int32_t stictionReleaseSpeed = 1000; // 0.1 RPM double stictionTorque = 0.0006; uint16_t rampTime = 10; diff --git a/mission/controller/acs/control/PtgCtrl.cpp b/mission/controller/acs/control/PtgCtrl.cpp index 01c047db..23f51f9e 100644 --- a/mission/controller/acs/control/PtgCtrl.cpp +++ b/mission/controller/acs/control/PtgCtrl.cpp @@ -154,38 +154,33 @@ void PtgCtrl::ptgNullspace(AcsParameters::PointingLawParameters *pointingLawPara VectorOperations::mulScalar(rwTrqNs, -1, rwTrqNs, 4); } -void PtgCtrl::rwAntistiction(ACS::SensorValues *sensorValues, double *torqueCommand) { +void PtgCtrl::rwAntistiction(ACS::SensorValues *sensorValues, int32_t *rwCmdSpeeds) { bool rwAvailable[4] = { (sensorValues->rw1Set.state.value && sensorValues->rw1Set.state.isValid()), (sensorValues->rw2Set.state.value && sensorValues->rw2Set.state.isValid()), (sensorValues->rw3Set.state.value && sensorValues->rw3Set.state.isValid()), (sensorValues->rw4Set.state.value && sensorValues->rw4Set.state.isValid())}; - int32_t omegaRw[4] = {sensorValues->rw1Set.currSpeed.value, sensorValues->rw2Set.currSpeed.value, - sensorValues->rw3Set.currSpeed.value, sensorValues->rw4Set.currSpeed.value}; + int32_t currRwSpeed[4] = { + sensorValues->rw1Set.currSpeed.value, sensorValues->rw2Set.currSpeed.value, + sensorValues->rw3Set.currSpeed.value, sensorValues->rw4Set.currSpeed.value}; for (uint8_t i = 0; i < 4; i++) { if (rwAvailable[i]) { - if (torqueMemory[i] != 0) { - if ((omegaRw[i] * torqueMemory[i]) > - acsParameters->rwHandlingParameters.stictionReleaseSpeed) { - torqueMemory[i] = 0; - } else { - torqueCommand[i] = torqueMemory[i] * acsParameters->rwHandlingParameters.stictionTorque; - } - } else { - if ((omegaRw[i] < acsParameters->rwHandlingParameters.stictionSpeed) && - (omegaRw[i] > -acsParameters->rwHandlingParameters.stictionSpeed)) { - if (omegaRw[i] < omegaMemory[i]) { - torqueMemory[i] = -1; - } else { - torqueMemory[i] = 1; + if (rwCmdSpeeds[i] != 0) { + if (rwCmdSpeeds[i] > -acsParameters->rwHandlingParameters.stictionSpeed && + rwCmdSpeeds[i] < acsParameters->rwHandlingParameters.stictionSpeed) { + if (currRwSpeed[i] == 0) { + if (rwCmdSpeeds[i] > 0) { + rwCmdSpeeds[i] = acsParameters->rwHandlingParameters.stictionSpeed; + } else if (rwCmdSpeeds[i] < 0) { + rwCmdSpeeds[i] = -acsParameters->rwHandlingParameters.stictionSpeed; + } + } else if (currRwSpeed[i] < -acsParameters->rwHandlingParameters.stictionSpeed) { + rwCmdSpeeds[i] = acsParameters->rwHandlingParameters.stictionSpeed; + } else if (currRwSpeed[i] > acsParameters->rwHandlingParameters.stictionSpeed) { + rwCmdSpeeds[i] = -acsParameters->rwHandlingParameters.stictionSpeed; } - - torqueCommand[i] = torqueMemory[i] * acsParameters->rwHandlingParameters.stictionTorque; } } - } else { - torqueMemory[i] = 0; } - omegaMemory[i] = omegaRw[i]; } } diff --git a/mission/controller/acs/control/PtgCtrl.h b/mission/controller/acs/control/PtgCtrl.h index 87185612..f6c6c345 100644 --- a/mission/controller/acs/control/PtgCtrl.h +++ b/mission/controller/acs/control/PtgCtrl.h @@ -1,16 +1,3 @@ -/* - * PtgCtrl.h - * - * Created on: 17 Jul 2022 - * Author: Robin Marquardt - * - * @brief: This class handles the pointing control mechanism. Calculation of an commanded - * torque for the reaction wheels, and magnetic Field strength for magnetorques for desaturation - * - * @note: A description of the used algorithms can be found in - * https://eive-cloud.irs.uni-stuttgart.de/index.php/apps/files/?dir=/EIVE_Studenten/Marquardt_Robin&openfile=896110 - */ - #ifndef PTGCTRL_H_ #define PTGCTRL_H_ @@ -23,6 +10,13 @@ #include "eive/resultClassIds.h" class PtgCtrl { + /* + * @brief: This class handles the pointing control mechanism. Calculation of an commanded + * torque for the reaction wheels, and magnetic Field strength for magnetorques for desaturation + * + * @note: A description of the used algorithms can be found in + * https://eive-cloud.irs.uni-stuttgart.de/index.php/apps/files/?dir=/EIVE_Studenten/Marquardt_Robin&openfile=896110 + */ public: /* @brief: Constructor * @param: acsParameters_ Pointer to object which defines the ACS configuration parameters @@ -50,13 +44,10 @@ class PtgCtrl { /* @brief: Commands the stiction torque in case wheel speed is to low * torqueCommand modified torque after antistiction */ - void rwAntistiction(ACS::SensorValues *sensorValues, double *torqueCommand); + void rwAntistiction(ACS::SensorValues *sensorValues, int32_t *rwCmdSpeed); private: const AcsParameters *acsParameters; - - double torqueMemory[4] = {0, 0, 0, 0}; - double omegaMemory[4] = {0, 0, 0, 0}; }; #endif /* ACS_CONTROL_PTGCTRL_H_ */ From 342ff62837c148abbc8b80d34b4caa9342bd0bc8 Mon Sep 17 00:00:00 2001 From: meggert Date: Fri, 10 Mar 2023 17:31:12 +0100 Subject: [PATCH 087/112] fixed rw torque scaling --- CHANGELOG.md | 1 + mission/controller/AcsController.cpp | 31 +++++++++++--------------- mission/controller/acs/ActuatorCmd.cpp | 13 +++++------ mission/controller/acs/ActuatorCmd.h | 6 ++--- 4 files changed, 22 insertions(+), 29 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 3ee2279b..5899b136 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -42,6 +42,7 @@ will consitute of a breaking change warranting a new major release: the values of the last step, which would result in undefined behaviour. - Solved naming collision between file used for solar array deployment and confirmation for ACS for solar array deployment. +- Fixed that scaling of RW torque would result in a zero vector unless the maximum value was exceeded. ## Changed diff --git a/mission/controller/AcsController.cpp b/mission/controller/AcsController.cpp index c7bbe0aa..fa0c8898 100644 --- a/mission/controller/AcsController.cpp +++ b/mission/controller/AcsController.cpp @@ -291,13 +291,13 @@ void AcsController::performPointingCtrl() { } else { multipleRwUnavailableCounter = 0; } - double torquePtgRws[4] = {0, 0, 0, 0}, rwTrqNs[4] = {0, 0, 0, 0}; - double torqueRws[4] = {0, 0, 0, 0}, torqueRwsScaled[4] = {0, 0, 0, 0}; - double mgtDpDes[3] = {0, 0, 0}; // Variables required for guidance double targetQuat[4] = {0, 0, 0, 1}, targetSatRotRate[3] = {0, 0, 0}, errorQuat[4] = {0, 0, 0, 1}, errorAngle = 0, errorSatRotRate[3] = {0, 0, 0}; + // Variables required for setting actuators + double torquePtgRws[4] = {0, 0, 0, 0}, rwTrqNs[4] = {0, 0, 0, 0}, torqueRws[4] = {0, 0, 0, 0}, + mgtDpDes[3] = {0, 0, 0}; switch (submode) { case acs::PTG_IDLE: guidance.targetQuatPtgSun(susDataProcessed.sunIjkModel.value, targetQuat, targetSatRotRate); @@ -310,8 +310,7 @@ void AcsController::performPointingCtrl() { &(sensorValues.rw2Set.currSpeed.value), &(sensorValues.rw3Set.currSpeed.value), &(sensorValues.rw4Set.currSpeed.value), rwTrqNs); VectorOperations::add(torquePtgRws, rwTrqNs, torqueRws, 4); - actuatorCmd.scalingTorqueRws(torqueRws, torqueRwsScaled, - acsParameters.rwHandlingParameters.maxTrq); + actuatorCmd.scalingTorqueRws(torqueRws, acsParameters.rwHandlingParameters.maxTrq); ptgCtrl.ptgDesaturation( &acsParameters.idleModeControllerParameters, mgmDataProcessed.mgmVecTot.value, mgmDataProcessed.mgmVecTot.isValid(), mekfData.satRotRateMekf.value, @@ -335,8 +334,7 @@ void AcsController::performPointingCtrl() { &(sensorValues.rw2Set.currSpeed.value), &(sensorValues.rw3Set.currSpeed.value), &(sensorValues.rw4Set.currSpeed.value), rwTrqNs); VectorOperations::add(torquePtgRws, rwTrqNs, torqueRws, 4); - actuatorCmd.scalingTorqueRws(torqueRws, torqueRwsScaled, - acsParameters.rwHandlingParameters.maxTrq); + actuatorCmd.scalingTorqueRws(torqueRws, acsParameters.rwHandlingParameters.maxTrq); ptgCtrl.ptgDesaturation( &acsParameters.targetModeControllerParameters, mgmDataProcessed.mgmVecTot.value, mgmDataProcessed.mgmVecTot.isValid(), mekfData.satRotRateMekf.value, @@ -357,8 +355,7 @@ void AcsController::performPointingCtrl() { &(sensorValues.rw2Set.currSpeed.value), &(sensorValues.rw3Set.currSpeed.value), &(sensorValues.rw4Set.currSpeed.value), rwTrqNs); VectorOperations::add(torquePtgRws, rwTrqNs, torqueRws, 4); - actuatorCmd.scalingTorqueRws(torqueRws, torqueRwsScaled, - acsParameters.rwHandlingParameters.maxTrq); + actuatorCmd.scalingTorqueRws(torqueRws, acsParameters.rwHandlingParameters.maxTrq); ptgCtrl.ptgDesaturation( &acsParameters.gsTargetModeControllerParameters, mgmDataProcessed.mgmVecTot.value, mgmDataProcessed.mgmVecTot.isValid(), mekfData.satRotRateMekf.value, @@ -382,8 +379,7 @@ void AcsController::performPointingCtrl() { &(sensorValues.rw2Set.currSpeed.value), &(sensorValues.rw3Set.currSpeed.value), &(sensorValues.rw4Set.currSpeed.value), rwTrqNs); VectorOperations::add(torquePtgRws, rwTrqNs, torqueRws, 4); - actuatorCmd.scalingTorqueRws(torqueRws, torqueRwsScaled, - acsParameters.rwHandlingParameters.maxTrq); + actuatorCmd.scalingTorqueRws(torqueRws, acsParameters.rwHandlingParameters.maxTrq); ptgCtrl.ptgDesaturation( &acsParameters.nadirModeControllerParameters, mgmDataProcessed.mgmVecTot.value, mgmDataProcessed.mgmVecTot.isValid(), mekfData.satRotRateMekf.value, @@ -406,8 +402,7 @@ void AcsController::performPointingCtrl() { &(sensorValues.rw2Set.currSpeed.value), &(sensorValues.rw3Set.currSpeed.value), &(sensorValues.rw4Set.currSpeed.value), rwTrqNs); VectorOperations::add(torquePtgRws, rwTrqNs, torqueRws, 4); - actuatorCmd.scalingTorqueRws(torqueRws, torqueRwsScaled, - acsParameters.rwHandlingParameters.maxTrq); + actuatorCmd.scalingTorqueRws(torqueRws, acsParameters.rwHandlingParameters.maxTrq); ptgCtrl.ptgDesaturation( &acsParameters.inertialModeControllerParameters, mgmDataProcessed.mgmVecTot.value, mgmDataProcessed.mgmVecTot.isValid(), mekfData.satRotRateMekf.value, @@ -416,22 +411,22 @@ void AcsController::performPointingCtrl() { enableAntiStiction = acsParameters.inertialModeControllerParameters.enableAntiStiction; break; } - if (enableAntiStiction) { - ptgCtrl.rwAntistiction(&sensorValues, torqueRwsScaled); - } actuatorCmd.cmdSpeedToRws( sensorValues.rw1Set.currSpeed.value, sensorValues.rw2Set.currSpeed.value, - sensorValues.rw3Set.currSpeed.value, sensorValues.rw4Set.currSpeed.value, torqueRwsScaled, + sensorValues.rw3Set.currSpeed.value, sensorValues.rw4Set.currSpeed.value, torqueRws, cmdSpeedRws, acsParameters.onBoardParams.sampleTime, acsParameters.rwHandlingParameters.maxRwSpeed, acsParameters.rwHandlingParameters.inertiaWheel); + if (enableAntiStiction) { + ptgCtrl.rwAntistiction(&sensorValues, cmdSpeedRws); + } actuatorCmd.cmdDipolMtq(mgtDpDes, cmdDipolMtqs, *acsParameters.magnetorquerParameter.inverseAlignment, acsParameters.magnetorquerParameter.dipolMax); updateCtrlValData(targetQuat, errorQuat, errorAngle, targetSatRotRate); - updateActuatorCmdData(torqueRwsScaled, cmdSpeedRws, cmdDipolMtqs); + updateActuatorCmdData(torqueRws, cmdSpeedRws, cmdDipolMtqs); // commandActuators(cmdDipolMtqs[0], cmdDipolMtqs[1], cmdDipolMtqs[2], // acsParameters.magnetorquesParameter.torqueDuration, cmdSpeedRws[0], // cmdSpeedRws[1], cmdSpeedRws[2], cmdSpeedRws[3], diff --git a/mission/controller/acs/ActuatorCmd.cpp b/mission/controller/acs/ActuatorCmd.cpp index 592fc69d..f32ce241 100644 --- a/mission/controller/acs/ActuatorCmd.cpp +++ b/mission/controller/acs/ActuatorCmd.cpp @@ -14,17 +14,14 @@ ActuatorCmd::ActuatorCmd() {} ActuatorCmd::~ActuatorCmd() {} -void ActuatorCmd::scalingTorqueRws(const double *rwTrq, double *rwTrqScaled, double maxTorque) { - double maxValue = 0; - for (int i = 0; i < 4; i++) { - if (abs(rwTrq[i]) > maxValue) { - maxValue = abs(rwTrq[i]); - } - } +void ActuatorCmd::scalingTorqueRws(double *rwTrq, double maxTorque) { + uint8_t maxIdx = 0; + VectorOperations::maxAbsValue(rwTrq, 4, &maxIdx); + double maxValue = rwTrq[maxIdx]; if (maxValue > maxTorque) { double scalingFactor = maxTorque / maxValue; - VectorOperations::mulScalar(rwTrq, scalingFactor, rwTrqScaled, 4); + VectorOperations::mulScalar(rwTrq, scalingFactor, rwTrq, 4); } } diff --git a/mission/controller/acs/ActuatorCmd.h b/mission/controller/acs/ActuatorCmd.h index 269e0191..5d5d47f3 100644 --- a/mission/controller/acs/ActuatorCmd.h +++ b/mission/controller/acs/ActuatorCmd.h @@ -13,10 +13,10 @@ class ActuatorCmd { /* * @brief: scalingTorqueRws() scales the torque via maximum part in case this part is * higher then the maximum torque - * @param: rwTrq given torque for reaction wheels - * rwTrqScaled possible scaled torque + * @param: rwTrq given torque for reaction wheels which will be + * scaled if needed to be */ - void scalingTorqueRws(const double *rwTrq, double *rwTrqScaled, double maxTorque); + void scalingTorqueRws(double *rwTrq, double maxTorque); /* * @brief: cmdSpeedToRws() will set the maximum possible torque for the reaction From 4e8e85f45052e4492bff0a2f7d00c346ad61e519 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 10 Mar 2023 17:32:22 +0100 Subject: [PATCH 088/112] some bugfixes --- common/config/eive/definitions.h | 1 + mission/core/GenericFactory.cpp | 7 ++++--- mission/tmtc/PersistentTmStore.cpp | 25 ++++++++++++++++++++----- 3 files changed, 25 insertions(+), 8 deletions(-) diff --git a/common/config/eive/definitions.h b/common/config/eive/definitions.h index cbd66e41..d6a1e757 100644 --- a/common/config/eive/definitions.h +++ b/common/config/eive/definitions.h @@ -54,6 +54,7 @@ static constexpr uint32_t HK_STORE_QUEUE_SIZE = 300; static constexpr uint32_t CFDP_STORE_QUEUE_SIZE = 300; static constexpr uint32_t MAX_PUS_FUNNEL_QUEUE_DEPTH = 100; +static constexpr uint32_t MAX_CFDP_FUNNEL_QUEUE_DEPTH = 80; static constexpr uint32_t MAX_STORED_CMDS_UDP = 120; static constexpr uint32_t MAX_STORED_CMDS_TCP = 150; diff --git a/mission/core/GenericFactory.cpp b/mission/core/GenericFactory.cpp index b6fc5ca1..39eeb582 100644 --- a/mission/core/GenericFactory.cpp +++ b/mission/core/GenericFactory.cpp @@ -149,9 +149,6 @@ void ObjectFactory::produceGenericObjects(HealthTableIF** healthTable_, PusTmFun new CcsdsDistributor(config::EIVE_PUS_APID, objects::CCSDS_PACKET_DISTRIBUTOR); new PusDistributor(config::EIVE_PUS_APID, objects::PUS_PACKET_DISTRIBUTOR, ccsdsDistrib); - PusTmFunnel::FunnelCfg cfdpFunnelCfg(objects::CFDP_TM_FUNNEL, "CfdpTmFunnel", **tmStore, - **ipcStore, 50); - *cfdpFunnel = new CfdpTmFunnel(cfdpFunnelCfg, *ramToFileStore, config::EIVE_CFDP_APID); PusTmFunnel::FunnelCfg pusFunnelCfg(objects::PUS_TM_FUNNEL, "PusTmFunnel", **tmStore, **ipcStore, config::MAX_PUS_FUNNEL_QUEUE_DEPTH); // The PUS funnel routes all live TM to the live destinations and to the TM stores. @@ -213,6 +210,10 @@ void ObjectFactory::produceGenericObjects(HealthTableIF** healthTable_, PusTmFun ->addPersistentTmStoreRouting(filters::cfdpFilter(), stores.cfdpStore->getReportReceptionQueue(0)); } + PusTmFunnel::FunnelCfg cfdpFunnelCfg(objects::CFDP_TM_FUNNEL, "CfdpTmFunnel", **tmStore, + **ipcStore, config::MAX_CFDP_FUNNEL_QUEUE_DEPTH); + *cfdpFunnel = new CfdpTmFunnel(cfdpFunnelCfg, stores.cfdpStore->getReportReceptionQueue(0), + *ramToFileStore, config::EIVE_CFDP_APID); #if OBSW_ADD_TCPIP_SERVERS == 1 #if OBSW_ADD_TMTC_UDP_SERVER == 1 diff --git a/mission/tmtc/PersistentTmStore.cpp b/mission/tmtc/PersistentTmStore.cpp index ccfe8821..9ed0218f 100644 --- a/mission/tmtc/PersistentTmStore.cpp +++ b/mission/tmtc/PersistentTmStore.cpp @@ -92,10 +92,18 @@ ReturnValue_t PersistentTmStore::storePacket(PusTmReader& reader) { bool createNewFile = false; std::optional suffix = std::nullopt; + std::error_code e; + size_t fileSize = file_size(activeFile.value(), e); + if (e) { + sif::error << "PersistentTmStore: Could not retrieve file size, " + "error " + << e.message() << std::endl; + return returnvalue::FAILED; + } if (currentTv.tv_sec > activeFileTv.tv_sec + static_cast(rolloverDiffSeconds)) { createNewFile = true; currentSameSecNumber = 0; - } else if (file_size(activeFile.value()) + reader.getFullPacketLen() > fileBuf.size()) { + } else if (fileSize + reader.getFullPacketLen() > fileBuf.size()) { createNewFile = true; if (currentSameSecNumber >= MAX_FILES_IN_ONE_SECOND) { currentSameSecNumber = 0; @@ -158,7 +166,8 @@ void PersistentTmStore::deleteUpTo(uint32_t unixSeconds) { } time_t fileEpoch = timegm(&fileTime); if (fileEpoch + rolloverDiffSeconds < unixSeconds) { - std::filesystem::remove(file.path()); + std::error_code e; + std::filesystem::remove(file.path(), e); } } } @@ -184,10 +193,15 @@ ReturnValue_t PersistentTmStore::loadNextDumpFile() { using namespace std::filesystem; std::error_code e; for (; dumpParams.dirIter != directory_iterator(); dumpParams.dirIter++) { + dumpParams.dirEntry = *dumpParams.dirIter; if (dumpParams.dirEntry.is_directory(e)) { continue; } - dumpParams.fileSize = std::filesystem::file_size(dumpParams.dirEntry.path()); + dumpParams.fileSize = std::filesystem::file_size(dumpParams.dirEntry.path(), e); + if (e) { + sif::error << "PersistentTmStore: Could not retrieve file size: " << e.message() << std::endl; + continue; + } // Can't even read CCSDS header. if (dumpParams.fileSize <= 6) { continue; @@ -195,7 +209,7 @@ ReturnValue_t PersistentTmStore::loadNextDumpFile() { if (dumpParams.fileSize > fileBuf.size()) { sif::error << "PersistentTmStore: File too large, is deleted" << std::endl; triggerEvent(FILE_TOO_LARGE, dumpParams.fileSize, fileBuf.size()); - std::remove(dumpParams.dirEntry.path().c_str()); + std::filesystem::remove(dumpParams.dirEntry.path(), e); continue; } const path& file = dumpParams.dirEntry.path(); @@ -249,7 +263,8 @@ ReturnValue_t PersistentTmStore::dumpNextPacket(DirectTmSinkIF& tmSink, size_t& // Delete the file and load next. Could use better algorithm to partially // restore the file dump, but for now do not trust the file. dumpedLen = 0; - std::remove(dumpParams.dirEntry.path().c_str()); + std::error_code e; + std::filesystem::remove(dumpParams.dirEntry.path().c_str(), e); fileHasSwapped = true; return loadNextDumpFile(); } From 3c0b8f9e8b5c7973db7b395896b66bd66345526a Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 10 Mar 2023 17:34:52 +0100 Subject: [PATCH 089/112] better error handling --- mission/tmtc/PersistentTmStore.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/mission/tmtc/PersistentTmStore.cpp b/mission/tmtc/PersistentTmStore.cpp index 9ed0218f..81f73751 100644 --- a/mission/tmtc/PersistentTmStore.cpp +++ b/mission/tmtc/PersistentTmStore.cpp @@ -224,6 +224,10 @@ ReturnValue_t PersistentTmStore::loadNextDumpFile() { dumpParams.currentSize = 0; dumpParams.currentFileUnixStamp = fileEpoch; std::ifstream ifile(file, std::ios::binary); + if(ifile.bad()) { + sif::error << "PersistentTmStore: File is bad" << std::endl; + continue; + } ifile.read(reinterpret_cast(fileBuf.data()), static_cast(dumpParams.fileSize)); break; From b6d18ef4d2f6ae598dccb247f17c622d3ca289ed Mon Sep 17 00:00:00 2001 From: meggert Date: Fri, 10 Mar 2023 17:41:18 +0100 Subject: [PATCH 090/112] changelog fix --- CHANGELOG.md | 3 --- 1 file changed, 3 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 82e981ea..79939ff0 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -49,9 +49,6 @@ will consitute of a breaking change warranting a new major release: - The `detumbleCounter` now does not get hard reset anymore, if the critical rate does not get violated anymore. Instead it is incrementally reset. - The RW antistiction now only takes the RW speeds in account. - -## Changed - - ACS CTRL transition to DETUBMLE is now done in CTRL internally. No system level handling necessary anymore. - More fixes and improvements for SD card handling. Extend SD card setup in core controller to From 976235a79f67a2b603b3836f32fafb70da41dd36 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 10 Mar 2023 18:04:04 +0100 Subject: [PATCH 091/112] check busy state --- linux/ipcore/PapbVcInterface.cpp | 5 +++-- linux/ipcore/PapbVcInterface.h | 9 ++++++++- linux/ipcore/Ptme.cpp | 11 +++++++++++ linux/ipcore/Ptme.h | 1 + linux/ipcore/PtmeIF.h | 1 + mission/tmtc/DirectTmSinkIF.h | 2 ++ mission/tmtc/PersistentTmStore.cpp | 9 ++++++--- mission/tmtc/TmStoreTaskBase.cpp | 14 ++++++++------ mission/tmtc/VirtualChannel.cpp | 2 ++ mission/tmtc/VirtualChannel.h | 1 + 10 files changed, 43 insertions(+), 12 deletions(-) diff --git a/linux/ipcore/PapbVcInterface.cpp b/linux/ipcore/PapbVcInterface.cpp index b8b12c7a..51afc15d 100644 --- a/linux/ipcore/PapbVcInterface.cpp +++ b/linux/ipcore/PapbVcInterface.cpp @@ -41,7 +41,7 @@ void PapbVcInterface::startPacketTransfer() { *vcBaseReg = CONFIG_START; } void PapbVcInterface::endPacketTransfer() { *vcBaseReg = CONFIG_END; } -ReturnValue_t PapbVcInterface::pollPapbBusySignal() { +ReturnValue_t PapbVcInterface::pollPapbBusySignal() const { gpio::Levels papbBusyState = gpio::Levels::LOW; ReturnValue_t result = returnvalue::OK; @@ -53,7 +53,6 @@ ReturnValue_t PapbVcInterface::pollPapbBusySignal() { return returnvalue::FAILED; } if (papbBusyState == gpio::Levels::LOW) { - sif::warning << "PapbVcInterface::pollPapbBusySignal: PAPB busy" << std::endl; return PAPB_BUSY; } @@ -80,6 +79,8 @@ void PapbVcInterface::isVcInterfaceBufferEmpty() { return; } +bool PapbVcInterface::isBusy() const { return pollPapbBusySignal() == PAPB_BUSY; } + ReturnValue_t PapbVcInterface::sendTestFrame() { /** Size of one complete transfer frame data field amounts to 1105 bytes */ uint8_t testPacket[1105]; diff --git a/linux/ipcore/PapbVcInterface.h b/linux/ipcore/PapbVcInterface.h index 5fb71340..d4694a62 100644 --- a/linux/ipcore/PapbVcInterface.h +++ b/linux/ipcore/PapbVcInterface.h @@ -32,6 +32,13 @@ class PapbVcInterface : public VirtualChannelIF { std::string uioFile, int mapNum); virtual ~PapbVcInterface(); + bool isBusy() const override; + /** + * + * @param data + * @param size + * @return returnvalue::OK on successfull write, PAPB_BUSY if PAPB is busy. + */ ReturnValue_t write(const uint8_t* data, size_t size) override; ReturnValue_t initialize() override; @@ -95,7 +102,7 @@ class PapbVcInterface : public VirtualChannelIF { * * @return returnvalue::OK when ready to receive data else PAPB_BUSY. */ - ReturnValue_t pollPapbBusySignal(); + ReturnValue_t pollPapbBusySignal() const; /** * @brief This function can be used for debugging to check whether there are packets in diff --git a/linux/ipcore/Ptme.cpp b/linux/ipcore/Ptme.cpp index 714c71be..69d772ff 100644 --- a/linux/ipcore/Ptme.cpp +++ b/linux/ipcore/Ptme.cpp @@ -51,3 +51,14 @@ void Ptme::addVcInterface(VcId_t vcId, VirtualChannelIF* vc) { return; } } + +bool Ptme::isBusy(uint8_t vcId) const { + const auto& vcInterfaceMapIter = vcInterfaceMap.find(vcId); + if (vcInterfaceMapIter == vcInterfaceMap.end()) { + sif::warning << "Ptme::writeToVc: No virtual channel interface found for the virtual " + "channel with id " + << static_cast(vcId) << std::endl; + return UNKNOWN_VC_ID; + } + return vcInterfaceMapIter->second->isBusy(); +} diff --git a/linux/ipcore/Ptme.h b/linux/ipcore/Ptme.h index aec7bcb4..3c076085 100644 --- a/linux/ipcore/Ptme.h +++ b/linux/ipcore/Ptme.h @@ -35,6 +35,7 @@ class Ptme : public PtmeIF, public SystemObject { ReturnValue_t initialize() override; ReturnValue_t writeToVc(uint8_t vcId, const uint8_t* data, size_t size) override; + bool isBusy(uint8_t vcId) const override; /** * @brief This function adds the reference to a virtual channel interface to the vcInterface diff --git a/linux/ipcore/PtmeIF.h b/linux/ipcore/PtmeIF.h index 44aa39f2..06b1cbe7 100644 --- a/linux/ipcore/PtmeIF.h +++ b/linux/ipcore/PtmeIF.h @@ -22,6 +22,7 @@ class PtmeIF { * @param size Number of bytes to write */ virtual ReturnValue_t writeToVc(uint8_t vcId, const uint8_t* data, size_t size) = 0; + virtual bool isBusy(uint8_t vcId) const = 0; }; #endif /* LINUX_OBC_PTMEIF_H_ */ diff --git a/mission/tmtc/DirectTmSinkIF.h b/mission/tmtc/DirectTmSinkIF.h index ca055ea9..ae7997ca 100644 --- a/mission/tmtc/DirectTmSinkIF.h +++ b/mission/tmtc/DirectTmSinkIF.h @@ -16,6 +16,8 @@ class DirectTmSinkIF { * @param size Number of bytes to write */ virtual ReturnValue_t write(const uint8_t* data, size_t size) = 0; + + virtual bool isBusy() const = 0; }; #endif /* MISSION_TMTC_DIRECTTMSINKIF_H_ */ diff --git a/mission/tmtc/PersistentTmStore.cpp b/mission/tmtc/PersistentTmStore.cpp index 81f73751..931102fc 100644 --- a/mission/tmtc/PersistentTmStore.cpp +++ b/mission/tmtc/PersistentTmStore.cpp @@ -191,12 +191,15 @@ ReturnValue_t PersistentTmStore::startDumpFromUpTo(uint32_t fromUnixSeconds, ReturnValue_t PersistentTmStore::loadNextDumpFile() { using namespace std::filesystem; + dumpParams.currentSize = 0; std::error_code e; for (; dumpParams.dirIter != directory_iterator(); dumpParams.dirIter++) { dumpParams.dirEntry = *dumpParams.dirIter; if (dumpParams.dirEntry.is_directory(e)) { continue; } + sif::debug << "handling file " << dumpParams.dirEntry << std::endl; + dumpParams.fileSize = std::filesystem::file_size(dumpParams.dirEntry.path(), e); if (e) { sif::error << "PersistentTmStore: Could not retrieve file size: " << e.message() << std::endl; @@ -221,10 +224,9 @@ ReturnValue_t PersistentTmStore::loadNextDumpFile() { auto fileEpoch = static_cast(timegm(&fileTime)); if ((fileEpoch > dumpParams.fromUnixTime) and (fileEpoch + rolloverDiffSeconds <= dumpParams.untilUnixTime)) { - dumpParams.currentSize = 0; dumpParams.currentFileUnixStamp = fileEpoch; std::ifstream ifile(file, std::ios::binary); - if(ifile.bad()) { + if (ifile.bad()) { sif::error << "PersistentTmStore: File is bad" << std::endl; continue; } @@ -245,6 +247,7 @@ ReturnValue_t PersistentTmStore::dumpNextPacket(DirectTmSinkIF& tmSink, size_t& if (state == State::IDLE) { return returnvalue::FAILED; } + sif::debug << "Current file idx: " << dumpParams.currentSize << std::endl; PusTmReader reader(&timeReader, fileBuf.data() + dumpParams.currentSize, fileBuf.size() - dumpParams.currentSize); // CRC check to fully ensure this is a valid TM @@ -262,7 +265,7 @@ ReturnValue_t PersistentTmStore::dumpNextPacket(DirectTmSinkIF& tmSink, size_t& return loadNextDumpFile(); } } else { - sif::error << "Parsing of PUS TM failed with code " << result << std::endl; + sif::error << "PersistentTmStore: Parsing of PUS TM failed with code " << result << std::endl; triggerEvent(POSSIBLE_FILE_CORRUPTION, result, dumpParams.currentFileUnixStamp); // Delete the file and load next. Could use better algorithm to partially // restore the file dump, but for now do not trust the file. diff --git a/mission/tmtc/TmStoreTaskBase.cpp b/mission/tmtc/TmStoreTaskBase.cpp index e234af1e..6fcbd7fc 100644 --- a/mission/tmtc/TmStoreTaskBase.cpp +++ b/mission/tmtc/TmStoreTaskBase.cpp @@ -21,12 +21,14 @@ bool TmStoreTaskBase::handleOneStore(PersistentTmStoreWithTmQueue& store, Countd if (store.getState() == PersistentTmStore::State::DUMPING) { size_t dumpedLen; bool fileHasSwapped; - // TODO: Maybe do a bit of a delay every 100-200 packets? - // TODO: We could continously dump until a file swap during active downlink.. - // TODO: handle returnvalue? - result = store.dumpNextPacket(channel, dumpedLen, fileHasSwapped); - if (result == returnvalue::OK) { - dumpsPerformed = true; + if (not channel.isBusy()) { + // TODO: Maybe do a bit of a delay every 100-200 packets? + // TODO: We could continously dump until a file swap during active downlink.. + // TODO: handle returnvalue? + result = store.dumpNextPacket(channel, dumpedLen, fileHasSwapped); + if (result == returnvalue::OK) { + dumpsPerformed = true; + } } } else { // Handle TC requests, for example deletion or retrieval requests. diff --git a/mission/tmtc/VirtualChannel.cpp b/mission/tmtc/VirtualChannel.cpp index 0c41ad86..da6ce13f 100644 --- a/mission/tmtc/VirtualChannel.cpp +++ b/mission/tmtc/VirtualChannel.cpp @@ -24,3 +24,5 @@ ReturnValue_t VirtualChannel::write(const uint8_t* data, size_t size) { uint8_t VirtualChannel::getVcid() const { return vcId; } const char* VirtualChannel::getName() const { return vcName.c_str(); } + +bool VirtualChannel::isBusy() const { return ptme.isBusy(vcId); } diff --git a/mission/tmtc/VirtualChannel.h b/mission/tmtc/VirtualChannel.h index b46c099e..983fa448 100644 --- a/mission/tmtc/VirtualChannel.h +++ b/mission/tmtc/VirtualChannel.h @@ -26,6 +26,7 @@ class VirtualChannel : public SystemObject, public VirtualChannelIF { ReturnValue_t initialize() override; ReturnValue_t sendNextTm(const uint8_t* data, size_t size); + bool isBusy() const override; ReturnValue_t write(const uint8_t* data, size_t size) override; uint8_t getVcid() const; From 5f9e0bf80a580ef7a1d2370e57144d60c33e6d03 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 10 Mar 2023 18:17:04 +0100 Subject: [PATCH 092/112] tweaks and CHANGELOG --- CHANGELOG.md | 16 ++++++++-------- bsp_q7s/core/CoreController.cpp | 22 ++++++++++++---------- mission/core/GenericFactory.cpp | 2 +- 3 files changed, 21 insertions(+), 19 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 0244af92..03560147 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -16,14 +16,6 @@ will consitute of a breaking change warranting a new major release: # [unreleased] -## Changed - -- Refactored TM pipeline to optimize usage of the PTME and communication downlink bandwidth. - This was done by moving the dumping of TMs to the VCs into separate threads with permanent loops. - These threads are then able to process high TM loads on demand. The PUS TM funnel will route - PUS packets to the approrpiate persisten TM stores and then demultiplex the TM to all registered - TM destinations as before. - ## Fixed - `PAPB_EMPTY_SIGNAL_VC1` GPIO was not set up properly. @@ -31,6 +23,14 @@ will consitute of a breaking change warranting a new major release: ## Changed +- Refactored TM pipeline to optimize usage of the PTME and communication downlink bandwidth. + This was done by moving the dumping of TMs to the VCs into separate threads with permanent loops. + These threads are then able to process high TM loads on demand. The PUS TM funnel will route + PUS packets to the approrpiate persisten TM stores and then demultiplex the TM to all registered + TM destinations as before. +- Service 5 now handles 40 events per cycle instead of 15 +- Remove periodic SD card check. The file system is not mounted read-only anymore when using an + ext4 filesystem - More fixes and improvements for SD card handling. Extend SD card setup in core controller to create full initial state for SD card manager are core controller as early as possible, turn execution of setup file update blocking. This might solve the issue with the SD card manager diff --git a/bsp_q7s/core/CoreController.cpp b/bsp_q7s/core/CoreController.cpp index 7eb0fe5f..b9e000d7 100644 --- a/bsp_q7s/core/CoreController.cpp +++ b/bsp_q7s/core/CoreController.cpp @@ -99,16 +99,18 @@ void CoreController::performControlOperation() { } sdStateMachine(); performMountedSdCardOperations(); - if (sdCardCheckCd.hasTimedOut()) { - if (shortSdCardCdCounter < 2) { - shortSdCardCdCounter++; - } - if (shortSdCardCdCounter == 2) { - sdCardCheckCd.setTimeout(DEFAULT_SD_CARD_CHECK_TIMEOUT); - } - performSdCardCheck(); - sdCardCheckCd.resetTimer(); - } + // TODO: Remove if not required. The filesystem is not re-mounted read-only + // when using ext4 +// if (sdCardCheckCd.hasTimedOut()) { +// if (shortSdCardCdCounter < 2) { +// shortSdCardCdCounter++; +// } +// if (shortSdCardCdCounter == 2) { +// sdCardCheckCd.setTimeout(DEFAULT_SD_CARD_CHECK_TIMEOUT); +// } +// performSdCardCheck(); +// sdCardCheckCd.resetTimer(); +// } readHkData(); opDivider5.checkAndIncrement(); opDivider10.checkAndIncrement(); diff --git a/mission/core/GenericFactory.cpp b/mission/core/GenericFactory.cpp index 39eeb582..35554f5d 100644 --- a/mission/core/GenericFactory.cpp +++ b/mission/core/GenericFactory.cpp @@ -235,7 +235,7 @@ void ObjectFactory::produceGenericObjects(HealthTableIF** healthTable_, PusTmFun pus::PUS_SERVICE_3); new Service5EventReporting( PsbParams(objects::PUS_SERVICE_5_EVENT_REPORTING, config::EIVE_PUS_APID, pus::PUS_SERVICE_5), - 15, 120); + 40, 120); new Service8FunctionManagement(objects::PUS_SERVICE_8_FUNCTION_MGMT, config::EIVE_PUS_APID, pus::PUS_SERVICE_8, 16, 60); new Service9TimeManagement( From 127a8e6124b615c3c5a0050e07c983c6f59f716e Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 10 Mar 2023 18:27:10 +0100 Subject: [PATCH 093/112] iterator was not incremented --- mission/tmtc/PersistentTmStore.cpp | 4 ++++ mission/tmtc/TmStoreTaskBase.cpp | 1 - 2 files changed, 4 insertions(+), 1 deletion(-) diff --git a/mission/tmtc/PersistentTmStore.cpp b/mission/tmtc/PersistentTmStore.cpp index 931102fc..ddd53b93 100644 --- a/mission/tmtc/PersistentTmStore.cpp +++ b/mission/tmtc/PersistentTmStore.cpp @@ -179,6 +179,9 @@ ReturnValue_t PersistentTmStore::startDumpFromUpTo(uint32_t fromUnixSeconds, return returnvalue::FAILED; } dumpParams.dirIter = directory_iterator(basePath); + if(dumpParams.dirIter == directory_iterator()) { + return returnvalue::FAILED; + } dumpParams.fromUnixTime = fromUnixSeconds; dumpParams.untilUnixTime = upToUnixSeconds; state = State::DUMPING; @@ -193,6 +196,7 @@ ReturnValue_t PersistentTmStore::loadNextDumpFile() { using namespace std::filesystem; dumpParams.currentSize = 0; std::error_code e; + dumpParams.dirIter++; for (; dumpParams.dirIter != directory_iterator(); dumpParams.dirIter++) { dumpParams.dirEntry = *dumpParams.dirIter; if (dumpParams.dirEntry.is_directory(e)) { diff --git a/mission/tmtc/TmStoreTaskBase.cpp b/mission/tmtc/TmStoreTaskBase.cpp index 6fcbd7fc..008735c4 100644 --- a/mission/tmtc/TmStoreTaskBase.cpp +++ b/mission/tmtc/TmStoreTaskBase.cpp @@ -24,7 +24,6 @@ bool TmStoreTaskBase::handleOneStore(PersistentTmStoreWithTmQueue& store, Countd if (not channel.isBusy()) { // TODO: Maybe do a bit of a delay every 100-200 packets? // TODO: We could continously dump until a file swap during active downlink.. - // TODO: handle returnvalue? result = store.dumpNextPacket(channel, dumpedLen, fileHasSwapped); if (result == returnvalue::OK) { dumpsPerformed = true; From 4257e1d9184b0e8a0c6b4b6c143d63103c1c5654 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 10 Mar 2023 19:01:31 +0100 Subject: [PATCH 094/112] events when dump is done --- bsp_q7s/core/CoreController.cpp | 12 ------ bsp_q7s/core/ObjectFactory.cpp | 6 ++- common/config/eive/resultClassIds.h | 1 + mission/core/GenericFactory.cpp | 3 ++ mission/core/GenericFactory.h | 11 ++---- mission/persistentTmStoreDefs.h | 41 ++++++++++++++++++++ mission/tmtc/DirectTmSinkIF.h | 9 ++++- mission/tmtc/PersistentLogTmStoreTask.cpp | 6 +-- mission/tmtc/PersistentSingleTmStoreTask.cpp | 14 +++---- mission/tmtc/PersistentSingleTmStoreTask.h | 3 +- mission/tmtc/PersistentTmStore.cpp | 20 +++++++--- mission/tmtc/PersistentTmStore.h | 21 +++++----- mission/tmtc/TmStoreTaskBase.cpp | 11 ++++-- mission/tmtc/TmStoreTaskBase.h | 2 +- 14 files changed, 105 insertions(+), 55 deletions(-) create mode 100644 mission/persistentTmStoreDefs.h diff --git a/bsp_q7s/core/CoreController.cpp b/bsp_q7s/core/CoreController.cpp index b9e000d7..5c4710d4 100644 --- a/bsp_q7s/core/CoreController.cpp +++ b/bsp_q7s/core/CoreController.cpp @@ -99,18 +99,6 @@ void CoreController::performControlOperation() { } sdStateMachine(); performMountedSdCardOperations(); - // TODO: Remove if not required. The filesystem is not re-mounted read-only - // when using ext4 -// if (sdCardCheckCd.hasTimedOut()) { -// if (shortSdCardCdCounter < 2) { -// shortSdCardCdCounter++; -// } -// if (shortSdCardCdCounter == 2) { -// sdCardCheckCd.setTimeout(DEFAULT_SD_CARD_CHECK_TIMEOUT); -// } -// performSdCardCheck(); -// sdCardCheckCd.resetTimer(); -// } readHkData(); opDivider5.checkAndIncrement(); opDivider10.checkAndIncrement(); diff --git a/bsp_q7s/core/ObjectFactory.cpp b/bsp_q7s/core/ObjectFactory.cpp index b3a9e751..3092e69d 100644 --- a/bsp_q7s/core/ObjectFactory.cpp +++ b/bsp_q7s/core/ObjectFactory.cpp @@ -785,13 +785,15 @@ ReturnValue_t ObjectFactory::createCcsdsComponents(CcsdsComponentArgs& args) { vc = new VirtualChannel(objects::PTME_VC2_HK_TM, ccsds::VC2, "PTME VC2 HK TM", *ptme, LINK_STATE); // Core task which handles the HK store and takes care of dumping it as TM using a VC directly new PersistentSingleTmStoreTask(objects::HK_STORE_AND_TM_TASK, args.ipcStore, - *args.stores.hkStore, *vc, *SdCardManager::instance()); + *args.stores.hkStore, *vc, persTmStore::DUMP_HK_STORE_DONE, + *SdCardManager::instance()); vc = new VirtualChannel(objects::PTME_VC3_CFDP_TM, ccsds::VC3, "PTME VC3 CFDP TM", *ptme, LINK_STATE); // Core task which handles the CFDP store and takes care of dumping it as TM using a VC directly new PersistentSingleTmStoreTask(objects::CFDP_STORE_AND_TM_TASK, args.ipcStore, - *args.stores.cfdpStore, *vc, *SdCardManager::instance()); + *args.stores.cfdpStore, *vc, persTmStore::DUMP_CFDP_STORE_DONE, + *SdCardManager::instance()); ReturnValue_t result = (*args.ipCoreHandler)->connectModeTreeParent(satsystem::com::SUBSYSTEM); if (result != returnvalue::OK) { diff --git a/common/config/eive/resultClassIds.h b/common/config/eive/resultClassIds.h index 125dd79a..9bad9ae3 100644 --- a/common/config/eive/resultClassIds.h +++ b/common/config/eive/resultClassIds.h @@ -43,6 +43,7 @@ enum commonClassIds : uint8_t { SD_CARD_MANAGER, // SDMA LOCAL_PARAM_HANDLER, // LPH PERSISTENT_TM_STORE, // PTM + TM_SINK, // TMS COMMON_CLASS_ID_END // [EXPORT] : [END] }; } diff --git a/mission/core/GenericFactory.cpp b/mission/core/GenericFactory.cpp index 35554f5d..76024784 100644 --- a/mission/core/GenericFactory.cpp +++ b/mission/core/GenericFactory.cpp @@ -28,6 +28,7 @@ #include #include #include +#include #include #include #include @@ -52,6 +53,8 @@ #include "objects/systemObjectList.h" #include "tmtc/pusIds.h" +using persTmStore::PersistentTmStores; + #if OBSW_ADD_TCPIP_SERVERS == 1 #if OBSW_ADD_TMTC_UDP_SERVER == 1 // UDP server includes diff --git a/mission/core/GenericFactory.h b/mission/core/GenericFactory.h index 6fb5d73d..1c5e9ce6 100644 --- a/mission/core/GenericFactory.h +++ b/mission/core/GenericFactory.h @@ -3,6 +3,7 @@ #include #include +#include #include #include "fsfw/objectmanager/SystemObjectIF.h" @@ -10,6 +11,8 @@ #include "fsfw_hal/common/gpio/GpioIF.h" #include "mission/devices/devicedefinitions/Max31865Definitions.h" +using persTmStore::PersistentTmStores; + class HeaterHandler; class HealthTableIF; class PusTmFunnel; @@ -36,14 +39,6 @@ const std::array, EiveMax31855::NUM_RTDS> RT {objects::RTD_15_IC18_IMTQ, "RTD_15_IMTQ"}, }}; -struct PersistentTmStores { - PersistentTmStoreWithTmQueue* okStore; - PersistentTmStoreWithTmQueue* notOkStore; - PersistentTmStoreWithTmQueue* miscStore; - PersistentTmStoreWithTmQueue* hkStore; - PersistentTmStoreWithTmQueue* cfdpStore; -}; - namespace ObjectFactory { void produceGenericObjects(HealthTableIF** healthTable, PusTmFunnel** pusFunnel, diff --git a/mission/persistentTmStoreDefs.h b/mission/persistentTmStoreDefs.h new file mode 100644 index 00000000..021f6f89 --- /dev/null +++ b/mission/persistentTmStoreDefs.h @@ -0,0 +1,41 @@ +#ifndef MISSION_PERSISTENTTMSTOREDEFS_H_ +#define MISSION_PERSISTENTTMSTOREDEFS_H_ + +#include + +#include "eive/eventSubsystemIds.h" + +namespace persTmStore { + +struct PersistentTmStores { + PersistentTmStoreWithTmQueue* okStore; + PersistentTmStoreWithTmQueue* notOkStore; + PersistentTmStoreWithTmQueue* miscStore; + PersistentTmStoreWithTmQueue* hkStore; + PersistentTmStoreWithTmQueue* cfdpStore; +}; + +static constexpr uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::PERSISTENT_TM_STORE; + +//! [EXPORT] : [COMMENT] +//! P1: Result code of TM packet parser. +//! P2: Timestamp of possibly corrupt file as a unix timestamp. +static constexpr Event POSSIBLE_FILE_CORRUPTION = event::makeEvent(SUBSYSTEM_ID, 0, severity::LOW); +//! [EXPORT] : [COMMENT] File in store too large. P1: Detected file size +//! P2: Allowed file size +static constexpr Event FILE_TOO_LARGE = event::makeEvent(SUBSYSTEM_ID, 1, severity::LOW); +static constexpr Event BUSY_DUMPING_EVENT = event::makeEvent(SUBSYSTEM_ID, 2, severity::INFO); + +//! [EXPORT] : [COMMENT] P1: Start time as UNIX seconds. P2: End time as UNIX seconds. +static constexpr Event DUMP_OK_STORE_DONE = event::makeEvent(SUBSYSTEM_ID, 3, severity::INFO); +//! [EXPORT] : [COMMENT] P1: Start time as UNIX seconds. P2: End time as UNIX seconds. +static constexpr Event DUMP_NOK_STORE_DONE = event::makeEvent(SUBSYSTEM_ID, 4, severity::INFO); +//! [EXPORT] : [COMMENT] P1: Start time as UNIX seconds. P2: End time as UNIX seconds. +static constexpr Event DUMP_MISC_STORE_DONE = event::makeEvent(SUBSYSTEM_ID, 5, severity::INFO); +//! [EXPORT] : [COMMENT] P1: Start time as UNIX seconds. P2: End time as UNIX seconds. +static constexpr Event DUMP_HK_STORE_DONE = event::makeEvent(SUBSYSTEM_ID, 6, severity::INFO); +//! [EXPORT] : [COMMENT] P1: Start time as UNIX seconds. P2: End time as UNIX seconds. +static constexpr Event DUMP_CFDP_STORE_DONE = event::makeEvent(SUBSYSTEM_ID, 7, severity::INFO); +}; // namespace persTmStore + +#endif /* MISSION_PERSISTENTTMSTOREDEFS_H_ */ diff --git a/mission/tmtc/DirectTmSinkIF.h b/mission/tmtc/DirectTmSinkIF.h index ae7997ca..11a17c79 100644 --- a/mission/tmtc/DirectTmSinkIF.h +++ b/mission/tmtc/DirectTmSinkIF.h @@ -3,17 +3,24 @@ #include +#include "eive/resultClassIds.h" #include "fsfw/retval.h" class DirectTmSinkIF { public: virtual ~DirectTmSinkIF() = default; + static constexpr uint8_t CLASS_ID = CLASS_ID::TM_SINK; + + static constexpr ReturnValue_t IS_BUSY = returnvalue::makeCode(CLASS_ID, 0); + /** - * @brief Implememts the functionality to write to a TM sink directly + * @brief Implements the functionality to write to a TM sink directly * * @param data Pointer to buffer holding the data to write * @param size Number of bytes to write + * @return returnvalue::OK on success, returnvalue::FAILED on failure, IS_BUSY + * if the TM sink is busy. */ virtual ReturnValue_t write(const uint8_t* data, size_t size) = 0; diff --git a/mission/tmtc/PersistentLogTmStoreTask.cpp b/mission/tmtc/PersistentLogTmStoreTask.cpp index 75bea255..3d0d99ee 100644 --- a/mission/tmtc/PersistentLogTmStoreTask.cpp +++ b/mission/tmtc/PersistentLogTmStoreTask.cpp @@ -15,15 +15,15 @@ ReturnValue_t PersistentLogTmStoreTask::performOperation(uint8_t opCode) { } bool someonesBusy = false; bool busy = false; - busy = handleOneStore(stores.okStore, tcHandlingCd); + busy = handleOneStore(stores.okStore, persTmStore::DUMP_OK_STORE_DONE); if (busy) { someonesBusy = true; } - busy = handleOneStore(stores.notOkStore, tcHandlingCd); + busy = handleOneStore(stores.notOkStore, persTmStore::DUMP_NOK_STORE_DONE); if (busy) { someonesBusy = true; } - busy = handleOneStore(stores.miscStore, tcHandlingCd); + busy = handleOneStore(stores.miscStore, persTmStore::DUMP_MISC_STORE_DONE); if (busy) { someonesBusy = true; } diff --git a/mission/tmtc/PersistentSingleTmStoreTask.cpp b/mission/tmtc/PersistentSingleTmStoreTask.cpp index 3cd8da37..e3e1688e 100644 --- a/mission/tmtc/PersistentSingleTmStoreTask.cpp +++ b/mission/tmtc/PersistentSingleTmStoreTask.cpp @@ -2,12 +2,12 @@ #include #include -PersistentSingleTmStoreTask::PersistentSingleTmStoreTask(object_id_t objectId, - StorageManagerIF& ipcStore, - PersistentTmStoreWithTmQueue& tmStore, - VirtualChannel& channel, - SdCardMountedIF& sdcMan) - : TmStoreTaskBase(objectId, ipcStore, channel, sdcMan), storeWithQueue(tmStore) {} +PersistentSingleTmStoreTask::PersistentSingleTmStoreTask( + object_id_t objectId, StorageManagerIF& ipcStore, PersistentTmStoreWithTmQueue& tmStore, + VirtualChannel& channel, Event eventIfDumpDone, SdCardMountedIF& sdcMan) + : TmStoreTaskBase(objectId, ipcStore, channel, sdcMan), + storeWithQueue(tmStore), + eventIfDumpDone(eventIfDumpDone) {} ReturnValue_t PersistentSingleTmStoreTask::performOperation(uint8_t opCode) { while (true) { @@ -15,7 +15,7 @@ ReturnValue_t PersistentSingleTmStoreTask::performOperation(uint8_t opCode) { if (not cyclicStoreCheck()) { continue; } - bool busy = handleOneStore(storeWithQueue, tcHandlingCd); + bool busy = handleOneStore(storeWithQueue, eventIfDumpDone); if (not busy) { TaskFactory::delayTask(40); } diff --git a/mission/tmtc/PersistentSingleTmStoreTask.h b/mission/tmtc/PersistentSingleTmStoreTask.h index d7a021d1..2fc9ece1 100644 --- a/mission/tmtc/PersistentSingleTmStoreTask.h +++ b/mission/tmtc/PersistentSingleTmStoreTask.h @@ -11,12 +11,13 @@ class PersistentSingleTmStoreTask : public TmStoreTaskBase, public ExecutableObj public: PersistentSingleTmStoreTask(object_id_t objectId, StorageManagerIF& ipcStore, PersistentTmStoreWithTmQueue& storeWithQueue, VirtualChannel& channel, - SdCardMountedIF& sdcMan); + Event eventIfDumpDone, SdCardMountedIF& sdcMan); ReturnValue_t performOperation(uint8_t opCode) override; private: PersistentTmStoreWithTmQueue& storeWithQueue; + Event eventIfDumpDone; Countdown tcHandlingCd = Countdown(400); bool initStoresIfPossible(); diff --git a/mission/tmtc/PersistentTmStore.cpp b/mission/tmtc/PersistentTmStore.cpp index ddd53b93..795957a6 100644 --- a/mission/tmtc/PersistentTmStore.cpp +++ b/mission/tmtc/PersistentTmStore.cpp @@ -12,6 +12,7 @@ #include "fsfw/ipc/CommandMessage.h" #include "fsfw/ipc/QueueFactory.h" #include "fsfw/tmstorage/TmStoreMessage.h" +#include "mission/persistentTmStoreDefs.h" using namespace returnvalue; @@ -65,7 +66,7 @@ ReturnValue_t PersistentTmStore::handleCommandQueue(StorageManagerIF& ipcStore) SerializeIF::Endianness::NETWORK); result = startDumpFromUpTo(dumpFromUnixSeconds, dumpUntilUnixSeconds); if (result != returnvalue::OK and result == BUSY_DUMPING) { - triggerEvent(BUSY_DUMPING_EVENT); + triggerEvent(persTmStore::BUSY_DUMPING_EVENT); } } } @@ -179,7 +180,7 @@ ReturnValue_t PersistentTmStore::startDumpFromUpTo(uint32_t fromUnixSeconds, return returnvalue::FAILED; } dumpParams.dirIter = directory_iterator(basePath); - if(dumpParams.dirIter == directory_iterator()) { + if (dumpParams.dirIter == directory_iterator()) { return returnvalue::FAILED; } dumpParams.fromUnixTime = fromUnixSeconds; @@ -215,7 +216,7 @@ ReturnValue_t PersistentTmStore::loadNextDumpFile() { } if (dumpParams.fileSize > fileBuf.size()) { sif::error << "PersistentTmStore: File too large, is deleted" << std::endl; - triggerEvent(FILE_TOO_LARGE, dumpParams.fileSize, fileBuf.size()); + triggerEvent(persTmStore::FILE_TOO_LARGE, dumpParams.fileSize, fileBuf.size()); std::filesystem::remove(dumpParams.dirEntry.path(), e); continue; } @@ -258,9 +259,12 @@ ReturnValue_t PersistentTmStore::dumpNextPacket(DirectTmSinkIF& tmSink, size_t& ReturnValue_t result = reader.parseDataWithCrcCheck(); if (result == returnvalue::OK) { result = tmSink.write(fileBuf.data() + dumpParams.currentSize, reader.getFullPacketLen()); - if (result != returnvalue::OK) { + if (result == DirectTmSinkIF::IS_BUSY) { + return result; + } else if (result != returnvalue::OK) { // TODO: Event? sif::error << "PersistentTmStore: Writing to TM sink failed" << std::endl; + return result; } dumpParams.currentSize += reader.getFullPacketLen(); dumpedLen = reader.getFullPacketLen(); @@ -270,7 +274,7 @@ ReturnValue_t PersistentTmStore::dumpNextPacket(DirectTmSinkIF& tmSink, size_t& } } else { sif::error << "PersistentTmStore: Parsing of PUS TM failed with code " << result << std::endl; - triggerEvent(POSSIBLE_FILE_CORRUPTION, result, dumpParams.currentFileUnixStamp); + triggerEvent(persTmStore::POSSIBLE_FILE_CORRUPTION, result, dumpParams.currentFileUnixStamp); // Delete the file and load next. Could use better algorithm to partially // restore the file dump, but for now do not trust the file. dumpedLen = 0; @@ -338,3 +342,9 @@ ReturnValue_t PersistentTmStore::initializeTmStore() { } PersistentTmStore::State PersistentTmStore::getState() const { return state; } + +void PersistentTmStore::getStartAndEndTimeCurrentOrLastDump(uint32_t& startTime, + uint32_t& endTime) const { + startTime = dumpParams.fromUnixTime; + endTime = dumpParams.untilUnixTime; +} diff --git a/mission/tmtc/PersistentTmStore.h b/mission/tmtc/PersistentTmStore.h index 3274a64c..994b7d30 100644 --- a/mission/tmtc/PersistentTmStore.h +++ b/mission/tmtc/PersistentTmStore.h @@ -45,18 +45,6 @@ class PersistentTmStore : public TmStoreFrontendSimpleIF, public SystemObject { static constexpr ReturnValue_t DUMP_DONE = returnvalue::makeCode(INTERFACE_ID, 0); static constexpr ReturnValue_t BUSY_DUMPING = returnvalue::makeCode(INTERFACE_ID, 1); - static constexpr uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::PERSISTENT_TM_STORE; - - //! [EXPORT] : [COMMENT] - //! P1: Result code of TM packet parser. - //! P2: Timestamp of possibly corrupt file as a unix timestamp. - static constexpr Event POSSIBLE_FILE_CORRUPTION = - event::makeEvent(SUBSYSTEM_ID, 0, severity::LOW); - //! [EXPORT] : [COMMENT] File in store too large. P1: Detected file size - //! P2: Allowed file size - static constexpr Event FILE_TOO_LARGE = event::makeEvent(SUBSYSTEM_ID, 1, severity::LOW); - static constexpr Event BUSY_DUMPING_EVENT = event::makeEvent(SUBSYSTEM_ID, 2, severity::INFO); - PersistentTmStore(PersistentTmStoreArgs args); ReturnValue_t initializeTmStore(); @@ -66,8 +54,17 @@ class PersistentTmStore : public TmStoreFrontendSimpleIF, public SystemObject { void deleteUpTo(uint32_t unixSeconds); ReturnValue_t startDumpFrom(uint32_t fromUnixSeconds); ReturnValue_t startDumpFromUpTo(uint32_t fromUnixSeconds, uint32_t upToUnixSeconds); + /** + * + * @param tmSink + * @param dumpedLen + * @param fileHasSwapped + * @return DUMP_DONE if dump is finished, returnvalue::OK if dump of next packet was a success, + * and DirectTmSinkIF::IS_BUSY is TM sink is busy. + */ ReturnValue_t dumpNextPacket(DirectTmSinkIF& tmSink, size_t& dumpedLen, bool& fileHasSwapped); + void getStartAndEndTimeCurrentOrLastDump(uint32_t& startTime, uint32_t& endTime) const; ReturnValue_t storePacket(PusTmReader& reader); protected: diff --git a/mission/tmtc/TmStoreTaskBase.cpp b/mission/tmtc/TmStoreTaskBase.cpp index 008735c4..1bd34ce0 100644 --- a/mission/tmtc/TmStoreTaskBase.cpp +++ b/mission/tmtc/TmStoreTaskBase.cpp @@ -7,7 +7,7 @@ TmStoreTaskBase::TmStoreTaskBase(object_id_t objectId, StorageManagerIF& ipcStor VirtualChannel& channel, SdCardMountedIF& sdcMan) : SystemObject(objectId), ipcStore(ipcStore), channel(channel), sdcMan(sdcMan) {} -bool TmStoreTaskBase::handleOneStore(PersistentTmStoreWithTmQueue& store, Countdown& tcHandlingCd) { +bool TmStoreTaskBase::handleOneStore(PersistentTmStoreWithTmQueue& store, Event eventIfDone) { ReturnValue_t result; bool tmToStoreReceived = true; bool tcRequestReceived = true; @@ -22,10 +22,15 @@ bool TmStoreTaskBase::handleOneStore(PersistentTmStoreWithTmQueue& store, Countd size_t dumpedLen; bool fileHasSwapped; if (not channel.isBusy()) { - // TODO: Maybe do a bit of a delay every 100-200 packets? // TODO: We could continously dump until a file swap during active downlink.. result = store.dumpNextPacket(channel, dumpedLen, fileHasSwapped); - if (result == returnvalue::OK) { + if (result == PersistentTmStore::DUMP_DONE) { + uint32_t startTime; + uint32_t endTime; + store.getStartAndEndTimeCurrentOrLastDump(startTime, endTime); + triggerEvent(eventIfDone, startTime, endTime); + dumpsPerformed = true; + } else if (result == returnvalue::OK) { dumpsPerformed = true; } } diff --git a/mission/tmtc/TmStoreTaskBase.h b/mission/tmtc/TmStoreTaskBase.h index 16042de6..aa308590 100644 --- a/mission/tmtc/TmStoreTaskBase.h +++ b/mission/tmtc/TmStoreTaskBase.h @@ -16,7 +16,7 @@ class TmStoreTaskBase : public SystemObject { * @param store * @return */ - bool handleOneStore(PersistentTmStoreWithTmQueue& store, Countdown& tcHandlingCd); + bool handleOneStore(PersistentTmStoreWithTmQueue& store, Event eventIfDone); /** * Occasionally check whether SD card is okay to be used. If not, poll whether it is ready to From 9413f723cfe8e21f986f2ca75eacc33fe5ac34f2 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 10 Mar 2023 19:06:52 +0100 Subject: [PATCH 095/112] re-run generators --- .../fsfwconfig/events/translateEvents.cpp | 25 +++++++++++-- .../fsfwconfig/objects/translateObjects.cpp | 35 ++++++++++++++++--- generators/bsp_hosted_events.csv | 9 ++++- generators/bsp_hosted_objects.csv | 11 +++++- generators/bsp_hosted_returnvalues.csv | 3 ++ generators/bsp_q7s_events.csv | 9 ++++- generators/bsp_q7s_objects.csv | 11 +++++- generators/bsp_q7s_returnvalues.csv | 5 ++- generators/events/translateEvents.cpp | 25 +++++++++++-- generators/objects/translateObjects.cpp | 35 ++++++++++++++++--- linux/fsfwconfig/events/translateEvents.cpp | 25 +++++++++++-- linux/fsfwconfig/objects/translateObjects.cpp | 35 ++++++++++++++++--- tmtc | 2 +- 13 files changed, 206 insertions(+), 24 deletions(-) diff --git a/bsp_hosted/fsfwconfig/events/translateEvents.cpp b/bsp_hosted/fsfwconfig/events/translateEvents.cpp index ed1436e0..44c3914f 100644 --- a/bsp_hosted/fsfwconfig/events/translateEvents.cpp +++ b/bsp_hosted/fsfwconfig/events/translateEvents.cpp @@ -1,7 +1,7 @@ /** - * @brief Auto-generated event translation file. Contains 269 translations. + * @brief Auto-generated event translation file. Contains 276 translations. * @details - * Generated on: 2023-03-08 16:44:32 + * Generated on: 2023-03-10 19:05:58 */ #include "translateEvents.h" @@ -269,6 +269,13 @@ const char *PLPCDU_OVERHEATING_STRING = "PLPCDU_OVERHEATING"; const char *TX_TIMER_EXPIRED_STRING = "TX_TIMER_EXPIRED"; const char *BIT_LOCK_TX_ON_STRING = "BIT_LOCK_TX_ON"; const char *POSSIBLE_FILE_CORRUPTION_STRING = "POSSIBLE_FILE_CORRUPTION"; +const char *FILE_TOO_LARGE_STRING = "FILE_TOO_LARGE"; +const char *BUSY_DUMPING_EVENT_STRING = "BUSY_DUMPING_EVENT"; +const char *DUMP_OK_STORE_DONE_STRING = "DUMP_OK_STORE_DONE"; +const char *DUMP_NOK_STORE_DONE_STRING = "DUMP_NOK_STORE_DONE"; +const char *DUMP_MISC_STORE_DONE_STRING = "DUMP_MISC_STORE_DONE"; +const char *DUMP_HK_STORE_DONE_STRING = "DUMP_HK_STORE_DONE"; +const char *DUMP_CFDP_STORE_DONE_STRING = "DUMP_CFDP_STORE_DONE"; const char *translateEvents(Event event) { switch ((event & 0xFFFF)) { @@ -800,6 +807,20 @@ const char *translateEvents(Event event) { return BIT_LOCK_TX_ON_STRING; case (14300): return POSSIBLE_FILE_CORRUPTION_STRING; + case (14301): + return FILE_TOO_LARGE_STRING; + case (14302): + return BUSY_DUMPING_EVENT_STRING; + case (14303): + return DUMP_OK_STORE_DONE_STRING; + case (14304): + return DUMP_NOK_STORE_DONE_STRING; + case (14305): + return DUMP_MISC_STORE_DONE_STRING; + case (14306): + return DUMP_HK_STORE_DONE_STRING; + case (14307): + return DUMP_CFDP_STORE_DONE_STRING; default: return "UNKNOWN_EVENT"; } diff --git a/bsp_hosted/fsfwconfig/objects/translateObjects.cpp b/bsp_hosted/fsfwconfig/objects/translateObjects.cpp index ad419fa0..65d7a92c 100644 --- a/bsp_hosted/fsfwconfig/objects/translateObjects.cpp +++ b/bsp_hosted/fsfwconfig/objects/translateObjects.cpp @@ -1,8 +1,8 @@ /** * @brief Auto-generated object translation file. * @details - * Contains 160 translations. - * Generated on: 2023-03-08 16:44:32 + * Contains 169 translations. + * Generated on: 2023-03-10 19:05:58 */ #include "translateObjects.h" @@ -54,6 +54,10 @@ const char *STR_HELPER_STRING = "STR_HELPER"; const char *PLOC_MPSOC_HELPER_STRING = "PLOC_MPSOC_HELPER"; const char *AXI_PTME_CONFIG_STRING = "AXI_PTME_CONFIG"; const char *PTME_CONFIG_STRING = "PTME_CONFIG"; +const char *PTME_VC0_LIVE_TM_STRING = "PTME_VC0_LIVE_TM"; +const char *PTME_VC1_LOG_TM_STRING = "PTME_VC1_LOG_TM"; +const char *PTME_VC2_HK_TM_STRING = "PTME_VC2_HK_TM"; +const char *PTME_VC3_CFDP_TM_STRING = "PTME_VC3_CFDP_TM"; const char *PLOC_MPSOC_HANDLER_STRING = "PLOC_MPSOC_HANDLER"; const char *PLOC_SUPERVISOR_HANDLER_STRING = "PLOC_SUPERVISOR_HANDLER"; const char *PLOC_SUPERVISOR_HELPER_STRING = "PLOC_SUPERVISOR_HELPER"; @@ -138,7 +142,7 @@ const char *HEATER_3_OBC_BRD_STRING = "HEATER_3_OBC_BRD"; const char *HEATER_4_CAMERA_STRING = "HEATER_4_CAMERA"; const char *HEATER_5_STR_STRING = "HEATER_5_STR"; const char *HEATER_6_DRO_STRING = "HEATER_6_DRO"; -const char *HEATER_7_HPA_STRING = "HEATER_7_HPA"; +const char *HEATER_7_SYRLINKS_STRING = "HEATER_7_SYRLINKS"; const char *ACS_BOARD_ASS_STRING = "ACS_BOARD_ASS"; const char *SUS_BOARD_ASS_STRING = "SUS_BOARD_ASS"; const char *TCS_BOARD_ASS_STRING = "TCS_BOARD_ASS"; @@ -162,6 +166,11 @@ const char *OK_TM_STORE_STRING = "OK_TM_STORE"; const char *NOT_OK_TM_STORE_STRING = "NOT_OK_TM_STORE"; const char *HK_TM_STORE_STRING = "HK_TM_STORE"; const char *CFDP_TM_STORE_STRING = "CFDP_TM_STORE"; +const char *LIVE_TM_TASK_STRING = "LIVE_TM_TASK"; +const char *LOG_STORE_AND_TM_TASK_STRING = "LOG_STORE_AND_TM_TASK"; +const char *HK_STORE_AND_TM_TASK_STRING = "HK_STORE_AND_TM_TASK"; +const char *CFDP_STORE_AND_TM_TASK_STRING = "CFDP_STORE_AND_TM_TASK"; +const char *DOWNLINK_RAM_STORE_STRING = "DOWNLINK_RAM_STORE"; const char *CCSDS_IP_CORE_BRIDGE_STRING = "CCSDS_IP_CORE_BRIDGE"; const char *THERMAL_TEMP_INSERTER_STRING = "THERMAL_TEMP_INSERTER"; const char *DUMMY_INTERFACE_STRING = "DUMMY_INTERFACE"; @@ -265,6 +274,14 @@ const char *translateObject(object_id_t object) { return AXI_PTME_CONFIG_STRING; case 0x44330005: return PTME_CONFIG_STRING; + case 0x44330006: + return PTME_VC0_LIVE_TM_STRING; + case 0x44330007: + return PTME_VC1_LOG_TM_STRING; + case 0x44330008: + return PTME_VC2_HK_TM_STRING; + case 0x44330009: + return PTME_VC3_CFDP_TM_STRING; case 0x44330015: return PLOC_MPSOC_HANDLER_STRING; case 0x44330016: @@ -434,7 +451,7 @@ const char *translateObject(object_id_t object) { case 0x60000006: return HEATER_6_DRO_STRING; case 0x60000007: - return HEATER_7_HPA_STRING; + return HEATER_7_SYRLINKS_STRING; case 0x73000001: return ACS_BOARD_ASS_STRING; case 0x73000002: @@ -481,6 +498,16 @@ const char *translateObject(object_id_t object) { return HK_TM_STORE_STRING; case 0x73030000: return CFDP_TM_STORE_STRING; + case 0x73040000: + return LIVE_TM_TASK_STRING; + case 0x73040001: + return LOG_STORE_AND_TM_TASK_STRING; + case 0x73040002: + return HK_STORE_AND_TM_TASK_STRING; + case 0x73040003: + return CFDP_STORE_AND_TM_TASK_STRING; + case 0x73040004: + return DOWNLINK_RAM_STORE_STRING; case 0x73500000: return CCSDS_IP_CORE_BRIDGE_STRING; case 0x90000003: diff --git a/generators/bsp_hosted_events.csv b/generators/bsp_hosted_events.csv index 77f53078..fa3a02c5 100644 --- a/generators/bsp_hosted_events.csv +++ b/generators/bsp_hosted_events.csv @@ -267,4 +267,11 @@ Event ID (dec); Event ID (hex); Name; Severity; Description; File Path 14106;0x371a;PLPCDU_OVERHEATING;HIGH;No description;mission/controller/ThermalController.h 14201;0x3779;TX_TIMER_EXPIRED;INFO;The transmit timer to protect the Syrlinks expired P1: The current timer value;mission/system/objects/ComSubsystem.h 14202;0x377a;BIT_LOCK_TX_ON;INFO;Transmitter will be turned on due to detection of bitlock;mission/system/objects/ComSubsystem.h -14300;0x37dc;POSSIBLE_FILE_CORRUPTION;LOW;P1: Result code of TM packet parser. P2: Timestamp of possibly corrupt file as a unix timestamp.;mission/tmtc/PersistentTmStore.h +14300;0x37dc;POSSIBLE_FILE_CORRUPTION;LOW;P1: Result code of TM packet parser. P2: Timestamp of possibly corrupt file as a unix timestamp.;mission/persistentTmStoreDefs.h +14301;0x37dd;FILE_TOO_LARGE;LOW;File in store too large. P1: Detected file size P2: Allowed file size;mission/persistentTmStoreDefs.h +14302;0x37de;BUSY_DUMPING_EVENT;INFO;No description;mission/persistentTmStoreDefs.h +14303;0x37df;DUMP_OK_STORE_DONE;INFO;P1: Start time as UNIX seconds. P2: End time as UNIX seconds.;mission/persistentTmStoreDefs.h +14304;0x37e0;DUMP_NOK_STORE_DONE;INFO;P1: Start time as UNIX seconds. P2: End time as UNIX seconds.;mission/persistentTmStoreDefs.h +14305;0x37e1;DUMP_MISC_STORE_DONE;INFO;P1: Start time as UNIX seconds. P2: End time as UNIX seconds.;mission/persistentTmStoreDefs.h +14306;0x37e2;DUMP_HK_STORE_DONE;INFO;P1: Start time as UNIX seconds. P2: End time as UNIX seconds.;mission/persistentTmStoreDefs.h +14307;0x37e3;DUMP_CFDP_STORE_DONE;INFO;P1: Start time as UNIX seconds. P2: End time as UNIX seconds.;mission/persistentTmStoreDefs.h diff --git a/generators/bsp_hosted_objects.csv b/generators/bsp_hosted_objects.csv index 254ebe87..12a9ffb1 100644 --- a/generators/bsp_hosted_objects.csv +++ b/generators/bsp_hosted_objects.csv @@ -46,6 +46,10 @@ 0x44330003;PLOC_MPSOC_HELPER 0x44330004;AXI_PTME_CONFIG 0x44330005;PTME_CONFIG +0x44330006;PTME_VC0_LIVE_TM +0x44330007;PTME_VC1_LOG_TM +0x44330008;PTME_VC2_HK_TM +0x44330009;PTME_VC3_CFDP_TM 0x44330015;PLOC_MPSOC_HANDLER 0x44330016;PLOC_SUPERVISOR_HANDLER 0x44330017;PLOC_SUPERVISOR_HELPER @@ -130,7 +134,7 @@ 0x60000004;HEATER_4_CAMERA 0x60000005;HEATER_5_STR 0x60000006;HEATER_6_DRO -0x60000007;HEATER_7_HPA +0x60000007;HEATER_7_SYRLINKS 0x73000001;ACS_BOARD_ASS 0x73000002;SUS_BOARD_ASS 0x73000003;TCS_BOARD_ASS @@ -154,6 +158,11 @@ 0x73020003;NOT_OK_TM_STORE 0x73020004;HK_TM_STORE 0x73030000;CFDP_TM_STORE +0x73040000;LIVE_TM_TASK +0x73040001;LOG_STORE_AND_TM_TASK +0x73040002;HK_STORE_AND_TM_TASK +0x73040003;CFDP_STORE_AND_TM_TASK +0x73040004;DOWNLINK_RAM_STORE 0x73500000;CCSDS_IP_CORE_BRIDGE 0x90000003;THERMAL_TEMP_INSERTER 0xCAFECAFE;DUMMY_INTERFACE diff --git a/generators/bsp_hosted_returnvalues.csv b/generators/bsp_hosted_returnvalues.csv index 041fd8e9..498fb417 100644 --- a/generators/bsp_hosted_returnvalues.csv +++ b/generators/bsp_hosted_returnvalues.csv @@ -49,6 +49,9 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path 0x4fa4;HEATER_MainSwitchSetTimeout;No description;164;HEATER_HANDLER;mission/devices/HeaterHandler.h 0x4fa5;HEATER_CommandAlreadyWaiting;No description;165;HEATER_HANDLER;mission/devices/HeaterHandler.h 0x60a0;CCSDS_CommandNotImplemented;Received action message with unknown action id;160;CCSDS_HANDLER;mission/tmtc/CcsdsIpCoreHandler.h +0x7100;TMS_IsBusy;No description;0;TM_SINK;mission/tmtc/DirectTmSinkIF.h +0x7000;PTM_DumpDone;No description;0;PERSISTENT_TM_STORE;mission/tmtc/PersistentTmStore.h +0x7001;PTM_BusyDumping;No description;1;PERSISTENT_TM_STORE;mission/tmtc/PersistentTmStore.h 0x6b01;ACSSAF_SafectrlMekfInputInvalid;No description;1;ACS_SAFE;mission/controller/acs/control/SafeCtrl.h 0x6c01;ACSPTG_PtgctrlMekfInputInvalid;No description;1;ACS_PTG;mission/controller/acs/control/PtgCtrl.h 0x6d01;ACSDTB_DetumbleNoSensordata;No description;1;ACS_DETUMBLE;mission/controller/acs/control/Detumble.h diff --git a/generators/bsp_q7s_events.csv b/generators/bsp_q7s_events.csv index 77f53078..fa3a02c5 100644 --- a/generators/bsp_q7s_events.csv +++ b/generators/bsp_q7s_events.csv @@ -267,4 +267,11 @@ Event ID (dec); Event ID (hex); Name; Severity; Description; File Path 14106;0x371a;PLPCDU_OVERHEATING;HIGH;No description;mission/controller/ThermalController.h 14201;0x3779;TX_TIMER_EXPIRED;INFO;The transmit timer to protect the Syrlinks expired P1: The current timer value;mission/system/objects/ComSubsystem.h 14202;0x377a;BIT_LOCK_TX_ON;INFO;Transmitter will be turned on due to detection of bitlock;mission/system/objects/ComSubsystem.h -14300;0x37dc;POSSIBLE_FILE_CORRUPTION;LOW;P1: Result code of TM packet parser. P2: Timestamp of possibly corrupt file as a unix timestamp.;mission/tmtc/PersistentTmStore.h +14300;0x37dc;POSSIBLE_FILE_CORRUPTION;LOW;P1: Result code of TM packet parser. P2: Timestamp of possibly corrupt file as a unix timestamp.;mission/persistentTmStoreDefs.h +14301;0x37dd;FILE_TOO_LARGE;LOW;File in store too large. P1: Detected file size P2: Allowed file size;mission/persistentTmStoreDefs.h +14302;0x37de;BUSY_DUMPING_EVENT;INFO;No description;mission/persistentTmStoreDefs.h +14303;0x37df;DUMP_OK_STORE_DONE;INFO;P1: Start time as UNIX seconds. P2: End time as UNIX seconds.;mission/persistentTmStoreDefs.h +14304;0x37e0;DUMP_NOK_STORE_DONE;INFO;P1: Start time as UNIX seconds. P2: End time as UNIX seconds.;mission/persistentTmStoreDefs.h +14305;0x37e1;DUMP_MISC_STORE_DONE;INFO;P1: Start time as UNIX seconds. P2: End time as UNIX seconds.;mission/persistentTmStoreDefs.h +14306;0x37e2;DUMP_HK_STORE_DONE;INFO;P1: Start time as UNIX seconds. P2: End time as UNIX seconds.;mission/persistentTmStoreDefs.h +14307;0x37e3;DUMP_CFDP_STORE_DONE;INFO;P1: Start time as UNIX seconds. P2: End time as UNIX seconds.;mission/persistentTmStoreDefs.h diff --git a/generators/bsp_q7s_objects.csv b/generators/bsp_q7s_objects.csv index c1171c16..c90f83ee 100644 --- a/generators/bsp_q7s_objects.csv +++ b/generators/bsp_q7s_objects.csv @@ -45,6 +45,10 @@ 0x44330003;PLOC_MPSOC_HELPER 0x44330004;AXI_PTME_CONFIG 0x44330005;PTME_CONFIG +0x44330006;PTME_VC0_LIVE_TM +0x44330007;PTME_VC1_LOG_TM +0x44330008;PTME_VC2_HK_TM +0x44330009;PTME_VC3_CFDP_TM 0x44330015;PLOC_MPSOC_HANDLER 0x44330016;PLOC_SUPERVISOR_HANDLER 0x44330017;PLOC_SUPERVISOR_HELPER @@ -135,7 +139,7 @@ 0x60000004;HEATER_4_CAMERA 0x60000005;HEATER_5_STR 0x60000006;HEATER_6_DRO -0x60000007;HEATER_7_HPA +0x60000007;HEATER_7_SYRLINKS 0x73000001;ACS_BOARD_ASS 0x73000002;SUS_BOARD_ASS 0x73000003;TCS_BOARD_ASS @@ -159,6 +163,11 @@ 0x73020003;NOT_OK_TM_STORE 0x73020004;HK_TM_STORE 0x73030000;CFDP_TM_STORE +0x73040000;LIVE_TM_TASK +0x73040001;LOG_STORE_AND_TM_TASK +0x73040002;HK_STORE_AND_TM_TASK +0x73040003;CFDP_STORE_AND_TM_TASK +0x73040004;DOWNLINK_RAM_STORE 0x73500000;CCSDS_IP_CORE_BRIDGE 0x90000003;THERMAL_TEMP_INSERTER 0xFFFFFFFF;NO_OBJECT diff --git a/generators/bsp_q7s_returnvalues.csv b/generators/bsp_q7s_returnvalues.csv index a289a768..55cd3697 100644 --- a/generators/bsp_q7s_returnvalues.csv +++ b/generators/bsp_q7s_returnvalues.csv @@ -49,6 +49,9 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path 0x4fa4;HEATER_MainSwitchSetTimeout;No description;164;HEATER_HANDLER;mission/devices/HeaterHandler.h 0x4fa5;HEATER_CommandAlreadyWaiting;No description;165;HEATER_HANDLER;mission/devices/HeaterHandler.h 0x60a0;CCSDS_CommandNotImplemented;Received action message with unknown action id;160;CCSDS_HANDLER;mission/tmtc/CcsdsIpCoreHandler.h +0x7100;TMS_IsBusy;No description;0;TM_SINK;mission/tmtc/DirectTmSinkIF.h +0x7000;PTM_DumpDone;No description;0;PERSISTENT_TM_STORE;mission/tmtc/PersistentTmStore.h +0x7001;PTM_BusyDumping;No description;1;PERSISTENT_TM_STORE;mission/tmtc/PersistentTmStore.h 0x6b01;ACSSAF_SafectrlMekfInputInvalid;No description;1;ACS_SAFE;mission/controller/acs/control/SafeCtrl.h 0x6c01;ACSPTG_PtgctrlMekfInputInvalid;No description;1;ACS_PTG;mission/controller/acs/control/PtgCtrl.h 0x6d01;ACSDTB_DetumbleNoSensordata;No description;1;ACS_DETUMBLE;mission/controller/acs/control/Detumble.h @@ -474,7 +477,7 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path 0x1d03;ATC_IllegalApplicationData;No description;3;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h 0x1d04;ATC_SendTmFailed;No description;4;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h 0x1d05;ATC_Timeout;No description;5;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h -0x7100;SCBU_KeyNotFound;No description;0;SCRATCH_BUFFER;bsp_q7s/memory/scratchApi.h +0x7300;SCBU_KeyNotFound;No description;0;SCRATCH_BUFFER;bsp_q7s/memory/scratchApi.h 0x6f00;LPH_SdNotReady;No description;0;LOCAL_PARAM_HANDLER;bsp_q7s/memory/LocalParameterHandler.h 0x64a0;FSHLP_SdNotMounted;SD card specified with path string not mounted;160;FILE_SYSTEM_HELPER;bsp_q7s/fs/FilesystemHelper.h 0x64a1;FSHLP_FileNotExists;Specified file does not exist on filesystem;161;FILE_SYSTEM_HELPER;bsp_q7s/fs/FilesystemHelper.h diff --git a/generators/events/translateEvents.cpp b/generators/events/translateEvents.cpp index ed1436e0..44c3914f 100644 --- a/generators/events/translateEvents.cpp +++ b/generators/events/translateEvents.cpp @@ -1,7 +1,7 @@ /** - * @brief Auto-generated event translation file. Contains 269 translations. + * @brief Auto-generated event translation file. Contains 276 translations. * @details - * Generated on: 2023-03-08 16:44:32 + * Generated on: 2023-03-10 19:05:58 */ #include "translateEvents.h" @@ -269,6 +269,13 @@ const char *PLPCDU_OVERHEATING_STRING = "PLPCDU_OVERHEATING"; const char *TX_TIMER_EXPIRED_STRING = "TX_TIMER_EXPIRED"; const char *BIT_LOCK_TX_ON_STRING = "BIT_LOCK_TX_ON"; const char *POSSIBLE_FILE_CORRUPTION_STRING = "POSSIBLE_FILE_CORRUPTION"; +const char *FILE_TOO_LARGE_STRING = "FILE_TOO_LARGE"; +const char *BUSY_DUMPING_EVENT_STRING = "BUSY_DUMPING_EVENT"; +const char *DUMP_OK_STORE_DONE_STRING = "DUMP_OK_STORE_DONE"; +const char *DUMP_NOK_STORE_DONE_STRING = "DUMP_NOK_STORE_DONE"; +const char *DUMP_MISC_STORE_DONE_STRING = "DUMP_MISC_STORE_DONE"; +const char *DUMP_HK_STORE_DONE_STRING = "DUMP_HK_STORE_DONE"; +const char *DUMP_CFDP_STORE_DONE_STRING = "DUMP_CFDP_STORE_DONE"; const char *translateEvents(Event event) { switch ((event & 0xFFFF)) { @@ -800,6 +807,20 @@ const char *translateEvents(Event event) { return BIT_LOCK_TX_ON_STRING; case (14300): return POSSIBLE_FILE_CORRUPTION_STRING; + case (14301): + return FILE_TOO_LARGE_STRING; + case (14302): + return BUSY_DUMPING_EVENT_STRING; + case (14303): + return DUMP_OK_STORE_DONE_STRING; + case (14304): + return DUMP_NOK_STORE_DONE_STRING; + case (14305): + return DUMP_MISC_STORE_DONE_STRING; + case (14306): + return DUMP_HK_STORE_DONE_STRING; + case (14307): + return DUMP_CFDP_STORE_DONE_STRING; default: return "UNKNOWN_EVENT"; } diff --git a/generators/objects/translateObjects.cpp b/generators/objects/translateObjects.cpp index 4950a981..ce898894 100644 --- a/generators/objects/translateObjects.cpp +++ b/generators/objects/translateObjects.cpp @@ -1,8 +1,8 @@ /** * @brief Auto-generated object translation file. * @details - * Contains 164 translations. - * Generated on: 2023-03-08 16:44:32 + * Contains 173 translations. + * Generated on: 2023-03-10 19:05:58 */ #include "translateObjects.h" @@ -53,6 +53,10 @@ const char *STR_HELPER_STRING = "STR_HELPER"; const char *PLOC_MPSOC_HELPER_STRING = "PLOC_MPSOC_HELPER"; const char *AXI_PTME_CONFIG_STRING = "AXI_PTME_CONFIG"; const char *PTME_CONFIG_STRING = "PTME_CONFIG"; +const char *PTME_VC0_LIVE_TM_STRING = "PTME_VC0_LIVE_TM"; +const char *PTME_VC1_LOG_TM_STRING = "PTME_VC1_LOG_TM"; +const char *PTME_VC2_HK_TM_STRING = "PTME_VC2_HK_TM"; +const char *PTME_VC3_CFDP_TM_STRING = "PTME_VC3_CFDP_TM"; const char *PLOC_MPSOC_HANDLER_STRING = "PLOC_MPSOC_HANDLER"; const char *PLOC_SUPERVISOR_HANDLER_STRING = "PLOC_SUPERVISOR_HANDLER"; const char *PLOC_SUPERVISOR_HELPER_STRING = "PLOC_SUPERVISOR_HELPER"; @@ -143,7 +147,7 @@ const char *HEATER_3_OBC_BRD_STRING = "HEATER_3_OBC_BRD"; const char *HEATER_4_CAMERA_STRING = "HEATER_4_CAMERA"; const char *HEATER_5_STR_STRING = "HEATER_5_STR"; const char *HEATER_6_DRO_STRING = "HEATER_6_DRO"; -const char *HEATER_7_HPA_STRING = "HEATER_7_HPA"; +const char *HEATER_7_SYRLINKS_STRING = "HEATER_7_SYRLINKS"; const char *ACS_BOARD_ASS_STRING = "ACS_BOARD_ASS"; const char *SUS_BOARD_ASS_STRING = "SUS_BOARD_ASS"; const char *TCS_BOARD_ASS_STRING = "TCS_BOARD_ASS"; @@ -167,6 +171,11 @@ const char *OK_TM_STORE_STRING = "OK_TM_STORE"; const char *NOT_OK_TM_STORE_STRING = "NOT_OK_TM_STORE"; const char *HK_TM_STORE_STRING = "HK_TM_STORE"; const char *CFDP_TM_STORE_STRING = "CFDP_TM_STORE"; +const char *LIVE_TM_TASK_STRING = "LIVE_TM_TASK"; +const char *LOG_STORE_AND_TM_TASK_STRING = "LOG_STORE_AND_TM_TASK"; +const char *HK_STORE_AND_TM_TASK_STRING = "HK_STORE_AND_TM_TASK"; +const char *CFDP_STORE_AND_TM_TASK_STRING = "CFDP_STORE_AND_TM_TASK"; +const char *DOWNLINK_RAM_STORE_STRING = "DOWNLINK_RAM_STORE"; const char *CCSDS_IP_CORE_BRIDGE_STRING = "CCSDS_IP_CORE_BRIDGE"; const char *THERMAL_TEMP_INSERTER_STRING = "THERMAL_TEMP_INSERTER"; const char *NO_OBJECT_STRING = "NO_OBJECT"; @@ -267,6 +276,14 @@ const char *translateObject(object_id_t object) { return AXI_PTME_CONFIG_STRING; case 0x44330005: return PTME_CONFIG_STRING; + case 0x44330006: + return PTME_VC0_LIVE_TM_STRING; + case 0x44330007: + return PTME_VC1_LOG_TM_STRING; + case 0x44330008: + return PTME_VC2_HK_TM_STRING; + case 0x44330009: + return PTME_VC3_CFDP_TM_STRING; case 0x44330015: return PLOC_MPSOC_HANDLER_STRING; case 0x44330016: @@ -448,7 +465,7 @@ const char *translateObject(object_id_t object) { case 0x60000006: return HEATER_6_DRO_STRING; case 0x60000007: - return HEATER_7_HPA_STRING; + return HEATER_7_SYRLINKS_STRING; case 0x73000001: return ACS_BOARD_ASS_STRING; case 0x73000002: @@ -495,6 +512,16 @@ const char *translateObject(object_id_t object) { return HK_TM_STORE_STRING; case 0x73030000: return CFDP_TM_STORE_STRING; + case 0x73040000: + return LIVE_TM_TASK_STRING; + case 0x73040001: + return LOG_STORE_AND_TM_TASK_STRING; + case 0x73040002: + return HK_STORE_AND_TM_TASK_STRING; + case 0x73040003: + return CFDP_STORE_AND_TM_TASK_STRING; + case 0x73040004: + return DOWNLINK_RAM_STORE_STRING; case 0x73500000: return CCSDS_IP_CORE_BRIDGE_STRING; case 0x90000003: diff --git a/linux/fsfwconfig/events/translateEvents.cpp b/linux/fsfwconfig/events/translateEvents.cpp index ed1436e0..44c3914f 100644 --- a/linux/fsfwconfig/events/translateEvents.cpp +++ b/linux/fsfwconfig/events/translateEvents.cpp @@ -1,7 +1,7 @@ /** - * @brief Auto-generated event translation file. Contains 269 translations. + * @brief Auto-generated event translation file. Contains 276 translations. * @details - * Generated on: 2023-03-08 16:44:32 + * Generated on: 2023-03-10 19:05:58 */ #include "translateEvents.h" @@ -269,6 +269,13 @@ const char *PLPCDU_OVERHEATING_STRING = "PLPCDU_OVERHEATING"; const char *TX_TIMER_EXPIRED_STRING = "TX_TIMER_EXPIRED"; const char *BIT_LOCK_TX_ON_STRING = "BIT_LOCK_TX_ON"; const char *POSSIBLE_FILE_CORRUPTION_STRING = "POSSIBLE_FILE_CORRUPTION"; +const char *FILE_TOO_LARGE_STRING = "FILE_TOO_LARGE"; +const char *BUSY_DUMPING_EVENT_STRING = "BUSY_DUMPING_EVENT"; +const char *DUMP_OK_STORE_DONE_STRING = "DUMP_OK_STORE_DONE"; +const char *DUMP_NOK_STORE_DONE_STRING = "DUMP_NOK_STORE_DONE"; +const char *DUMP_MISC_STORE_DONE_STRING = "DUMP_MISC_STORE_DONE"; +const char *DUMP_HK_STORE_DONE_STRING = "DUMP_HK_STORE_DONE"; +const char *DUMP_CFDP_STORE_DONE_STRING = "DUMP_CFDP_STORE_DONE"; const char *translateEvents(Event event) { switch ((event & 0xFFFF)) { @@ -800,6 +807,20 @@ const char *translateEvents(Event event) { return BIT_LOCK_TX_ON_STRING; case (14300): return POSSIBLE_FILE_CORRUPTION_STRING; + case (14301): + return FILE_TOO_LARGE_STRING; + case (14302): + return BUSY_DUMPING_EVENT_STRING; + case (14303): + return DUMP_OK_STORE_DONE_STRING; + case (14304): + return DUMP_NOK_STORE_DONE_STRING; + case (14305): + return DUMP_MISC_STORE_DONE_STRING; + case (14306): + return DUMP_HK_STORE_DONE_STRING; + case (14307): + return DUMP_CFDP_STORE_DONE_STRING; default: return "UNKNOWN_EVENT"; } diff --git a/linux/fsfwconfig/objects/translateObjects.cpp b/linux/fsfwconfig/objects/translateObjects.cpp index 4950a981..ce898894 100644 --- a/linux/fsfwconfig/objects/translateObjects.cpp +++ b/linux/fsfwconfig/objects/translateObjects.cpp @@ -1,8 +1,8 @@ /** * @brief Auto-generated object translation file. * @details - * Contains 164 translations. - * Generated on: 2023-03-08 16:44:32 + * Contains 173 translations. + * Generated on: 2023-03-10 19:05:58 */ #include "translateObjects.h" @@ -53,6 +53,10 @@ const char *STR_HELPER_STRING = "STR_HELPER"; const char *PLOC_MPSOC_HELPER_STRING = "PLOC_MPSOC_HELPER"; const char *AXI_PTME_CONFIG_STRING = "AXI_PTME_CONFIG"; const char *PTME_CONFIG_STRING = "PTME_CONFIG"; +const char *PTME_VC0_LIVE_TM_STRING = "PTME_VC0_LIVE_TM"; +const char *PTME_VC1_LOG_TM_STRING = "PTME_VC1_LOG_TM"; +const char *PTME_VC2_HK_TM_STRING = "PTME_VC2_HK_TM"; +const char *PTME_VC3_CFDP_TM_STRING = "PTME_VC3_CFDP_TM"; const char *PLOC_MPSOC_HANDLER_STRING = "PLOC_MPSOC_HANDLER"; const char *PLOC_SUPERVISOR_HANDLER_STRING = "PLOC_SUPERVISOR_HANDLER"; const char *PLOC_SUPERVISOR_HELPER_STRING = "PLOC_SUPERVISOR_HELPER"; @@ -143,7 +147,7 @@ const char *HEATER_3_OBC_BRD_STRING = "HEATER_3_OBC_BRD"; const char *HEATER_4_CAMERA_STRING = "HEATER_4_CAMERA"; const char *HEATER_5_STR_STRING = "HEATER_5_STR"; const char *HEATER_6_DRO_STRING = "HEATER_6_DRO"; -const char *HEATER_7_HPA_STRING = "HEATER_7_HPA"; +const char *HEATER_7_SYRLINKS_STRING = "HEATER_7_SYRLINKS"; const char *ACS_BOARD_ASS_STRING = "ACS_BOARD_ASS"; const char *SUS_BOARD_ASS_STRING = "SUS_BOARD_ASS"; const char *TCS_BOARD_ASS_STRING = "TCS_BOARD_ASS"; @@ -167,6 +171,11 @@ const char *OK_TM_STORE_STRING = "OK_TM_STORE"; const char *NOT_OK_TM_STORE_STRING = "NOT_OK_TM_STORE"; const char *HK_TM_STORE_STRING = "HK_TM_STORE"; const char *CFDP_TM_STORE_STRING = "CFDP_TM_STORE"; +const char *LIVE_TM_TASK_STRING = "LIVE_TM_TASK"; +const char *LOG_STORE_AND_TM_TASK_STRING = "LOG_STORE_AND_TM_TASK"; +const char *HK_STORE_AND_TM_TASK_STRING = "HK_STORE_AND_TM_TASK"; +const char *CFDP_STORE_AND_TM_TASK_STRING = "CFDP_STORE_AND_TM_TASK"; +const char *DOWNLINK_RAM_STORE_STRING = "DOWNLINK_RAM_STORE"; const char *CCSDS_IP_CORE_BRIDGE_STRING = "CCSDS_IP_CORE_BRIDGE"; const char *THERMAL_TEMP_INSERTER_STRING = "THERMAL_TEMP_INSERTER"; const char *NO_OBJECT_STRING = "NO_OBJECT"; @@ -267,6 +276,14 @@ const char *translateObject(object_id_t object) { return AXI_PTME_CONFIG_STRING; case 0x44330005: return PTME_CONFIG_STRING; + case 0x44330006: + return PTME_VC0_LIVE_TM_STRING; + case 0x44330007: + return PTME_VC1_LOG_TM_STRING; + case 0x44330008: + return PTME_VC2_HK_TM_STRING; + case 0x44330009: + return PTME_VC3_CFDP_TM_STRING; case 0x44330015: return PLOC_MPSOC_HANDLER_STRING; case 0x44330016: @@ -448,7 +465,7 @@ const char *translateObject(object_id_t object) { case 0x60000006: return HEATER_6_DRO_STRING; case 0x60000007: - return HEATER_7_HPA_STRING; + return HEATER_7_SYRLINKS_STRING; case 0x73000001: return ACS_BOARD_ASS_STRING; case 0x73000002: @@ -495,6 +512,16 @@ const char *translateObject(object_id_t object) { return HK_TM_STORE_STRING; case 0x73030000: return CFDP_TM_STORE_STRING; + case 0x73040000: + return LIVE_TM_TASK_STRING; + case 0x73040001: + return LOG_STORE_AND_TM_TASK_STRING; + case 0x73040002: + return HK_STORE_AND_TM_TASK_STRING; + case 0x73040003: + return CFDP_STORE_AND_TM_TASK_STRING; + case 0x73040004: + return DOWNLINK_RAM_STORE_STRING; case 0x73500000: return CCSDS_IP_CORE_BRIDGE_STRING; case 0x90000003: diff --git a/tmtc b/tmtc index e32a6ded..26cd265e 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit e32a6ded6661d450dbc75a7ab0194e8048af3d5c +Subproject commit 26cd265e19b8077432ae670760e92fee27e438c4 From 2a84ebba574838d91901c92fbb5039f625779a79 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 10 Mar 2023 19:13:01 +0100 Subject: [PATCH 096/112] fix for unittest --- unittest/mocks/EventManagerMock.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/unittest/mocks/EventManagerMock.cpp b/unittest/mocks/EventManagerMock.cpp index 383c755b..acbf1a0b 100644 --- a/unittest/mocks/EventManagerMock.cpp +++ b/unittest/mocks/EventManagerMock.cpp @@ -2,7 +2,7 @@ #include -EventManagerMock::EventManagerMock() : EventManager(objects::EVENT_MANAGER) {} +EventManagerMock::EventManagerMock() : EventManager(objects::EVENT_MANAGER, 80) {} ReturnValue_t EventManagerMock::performOperation(uint8_t opCode) { ReturnValue_t result = returnvalue::OK; @@ -60,4 +60,4 @@ bool EventManagerMock::isEventInEventList(object_id_t object, EventId_t eventId, } } return false; -} \ No newline at end of file +} From 5ea2767662391baf89be27c2e1459a353111423b Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 10 Mar 2023 19:34:32 +0100 Subject: [PATCH 097/112] bugfixes for iterator handling --- mission/tmtc/PersistentTmStore.cpp | 8 +++----- 1 file changed, 3 insertions(+), 5 deletions(-) diff --git a/mission/tmtc/PersistentTmStore.cpp b/mission/tmtc/PersistentTmStore.cpp index 795957a6..79b7384b 100644 --- a/mission/tmtc/PersistentTmStore.cpp +++ b/mission/tmtc/PersistentTmStore.cpp @@ -65,7 +65,7 @@ ReturnValue_t PersistentTmStore::handleCommandQueue(StorageManagerIF& ipcStore) SerializeAdapter::deSerialize(&dumpUntilUnixSeconds, accessor.second.data() + 4, &size, SerializeIF::Endianness::NETWORK); result = startDumpFromUpTo(dumpFromUnixSeconds, dumpUntilUnixSeconds); - if (result != returnvalue::OK and result == BUSY_DUMPING) { + if (result == BUSY_DUMPING) { triggerEvent(persTmStore::BUSY_DUMPING_EVENT); } } @@ -197,14 +197,11 @@ ReturnValue_t PersistentTmStore::loadNextDumpFile() { using namespace std::filesystem; dumpParams.currentSize = 0; std::error_code e; - dumpParams.dirIter++; for (; dumpParams.dirIter != directory_iterator(); dumpParams.dirIter++) { dumpParams.dirEntry = *dumpParams.dirIter; if (dumpParams.dirEntry.is_directory(e)) { continue; } - sif::debug << "handling file " << dumpParams.dirEntry << std::endl; - dumpParams.fileSize = std::filesystem::file_size(dumpParams.dirEntry.path(), e); if (e) { sif::error << "PersistentTmStore: Could not retrieve file size: " << e.message() << std::endl; @@ -237,6 +234,8 @@ ReturnValue_t PersistentTmStore::loadNextDumpFile() { } ifile.read(reinterpret_cast(fileBuf.data()), static_cast(dumpParams.fileSize)); + // Increment iterator for next cycle. + dumpParams.dirIter++; break; } } @@ -252,7 +251,6 @@ ReturnValue_t PersistentTmStore::dumpNextPacket(DirectTmSinkIF& tmSink, size_t& if (state == State::IDLE) { return returnvalue::FAILED; } - sif::debug << "Current file idx: " << dumpParams.currentSize << std::endl; PusTmReader reader(&timeReader, fileBuf.data() + dumpParams.currentSize, fileBuf.size() - dumpParams.currentSize); // CRC check to fully ensure this is a valid TM From 68ed3fa232853e92ea3b4a05d6c2a400d56376a0 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 10 Mar 2023 19:42:36 +0100 Subject: [PATCH 098/112] tweak priorities --- bsp_q7s/core/scheduling.cpp | 12 ++++-------- 1 file changed, 4 insertions(+), 8 deletions(-) diff --git a/bsp_q7s/core/scheduling.cpp b/bsp_q7s/core/scheduling.cpp index 20885541..99bb90d2 100644 --- a/bsp_q7s/core/scheduling.cpp +++ b/bsp_q7s/core/scheduling.cpp @@ -116,10 +116,6 @@ void scheduling::initTasks() { if (result != returnvalue::OK) { scheduling::printAddObjectError("CFDP_DISTRIBUTOR", objects::CFDP_DISTRIBUTOR); } - // result = tmTcDistributor->addComponent(objects::TM_FUNNEL); - // if (result != returnvalue::OK) { - // scheduling::printAddObjectError("TM_FUNNEL", objects::TM_FUNNEL); - // } #if OBSW_ADD_TCPIP_SERVERS == 1 #if OBSW_ADD_TMTC_UDP_SERVER == 1 @@ -184,25 +180,25 @@ void scheduling::initTasks() { #endif /* OBSW_ADD_CCSDS_IP_CORE == 1 */ // All the TM store tasks run in permanent loops, frequency does not matter PeriodicTaskIF* liveTmTask = - factory->createPeriodicTask("LIVE_TM", 60, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.0, nullptr); + factory->createPeriodicTask("LIVE_TM", 55, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.0, nullptr); result = liveTmTask->addComponent(objects::LIVE_TM_TASK); if (result != returnvalue::OK) { scheduling::printAddObjectError("LIVE_TM", objects::LIVE_TM_TASK); } PeriodicTaskIF* logTmTask = factory->createPeriodicTask( - "LOG_STORE_AND_TM", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.0, nullptr); + "LOG_STORE_AND_TM", 45, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.0, nullptr); result = logTmTask->addComponent(objects::LOG_STORE_AND_TM_TASK); if (result != returnvalue::OK) { scheduling::printAddObjectError("LOG_STORE_AND_TM", objects::LOG_STORE_AND_TM_TASK); } PeriodicTaskIF* hkTmTask = factory->createPeriodicTask( - "HK_STORE_AND_TM", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.0, nullptr); + "HK_STORE_AND_TM", 45, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.0, nullptr); result = hkTmTask->addComponent(objects::HK_STORE_AND_TM_TASK); if (result != returnvalue::OK) { scheduling::printAddObjectError("HK_STORE_AND_TM", objects::HK_STORE_AND_TM_TASK); } PeriodicTaskIF* cfdpTmTask = factory->createPeriodicTask( - "CFDP_STORE_AND_TM", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.0, nullptr); + "CFDP_STORE_AND_TM", 45, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.0, nullptr); result = cfdpTmTask->addComponent(objects::CFDP_STORE_AND_TM_TASK); if (result != returnvalue::OK) { scheduling::printAddObjectError("CFDP_STORE_AND_TM", objects::CFDP_STORE_AND_TM_TASK); From f9c03af5381c34d8ddbcc8dd8bee9ec1fb6991ec Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 10 Mar 2023 20:13:36 +0100 Subject: [PATCH 099/112] logic errors --- mission/tmtc/TmStoreTaskBase.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/mission/tmtc/TmStoreTaskBase.cpp b/mission/tmtc/TmStoreTaskBase.cpp index 1bd34ce0..fc79439b 100644 --- a/mission/tmtc/TmStoreTaskBase.cpp +++ b/mission/tmtc/TmStoreTaskBase.cpp @@ -9,13 +9,13 @@ TmStoreTaskBase::TmStoreTaskBase(object_id_t objectId, StorageManagerIF& ipcStor bool TmStoreTaskBase::handleOneStore(PersistentTmStoreWithTmQueue& store, Event eventIfDone) { ReturnValue_t result; - bool tmToStoreReceived = true; - bool tcRequestReceived = true; + bool tmToStoreReceived = false; + bool tcRequestReceived = false; bool dumpsPerformed = false; // Store TM persistently result = store.handleNextTm(); - if (result == MessageQueueIF::EMPTY) { - tmToStoreReceived = false; + if (result == returnvalue::OK) { + tmToStoreReceived = true; } // Dump TMs when applicable if (store.getState() == PersistentTmStore::State::DUMPING) { @@ -37,8 +37,8 @@ bool TmStoreTaskBase::handleOneStore(PersistentTmStoreWithTmQueue& store, Event } else { // Handle TC requests, for example deletion or retrieval requests. result = store.handleCommandQueue(ipcStore); - if (result == MessageQueueIF::EMPTY) { - tcRequestReceived = false; + if (result == returnvalue::OK) { + tcRequestReceived = true; } } if (tcRequestReceived or tmToStoreReceived or dumpsPerformed) { From bbd27eca7630f98c65b5e3815403663ff1450901 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 10 Mar 2023 20:32:11 +0100 Subject: [PATCH 100/112] basic FDIR if dump takes too long --- .../controller/acs/MultiplicativeKalmanFilter.h | 2 +- mission/persistentTmStoreDefs.h | 12 +++++++----- mission/tmtc/PersistentTmStore.cpp | 13 +++++++++++-- mission/tmtc/PersistentTmStore.h | 4 +++- mission/tmtc/TmStoreTaskBase.cpp | 16 +++++++++++++++- mission/tmtc/TmStoreTaskBase.h | 4 ++++ 6 files changed, 41 insertions(+), 10 deletions(-) diff --git a/mission/controller/acs/MultiplicativeKalmanFilter.h b/mission/controller/acs/MultiplicativeKalmanFilter.h index 3e9bfa49..ceb98339 100644 --- a/mission/controller/acs/MultiplicativeKalmanFilter.h +++ b/mission/controller/acs/MultiplicativeKalmanFilter.h @@ -86,7 +86,7 @@ class MultiplicativeKalmanFilter { double initialCovarianceMatrix[6][6] = {{0, 0, 0, 0, 0, 0}, {0, 0, 0, 0, 0, 0}, {0, 0, 0, 0, 0, 0}, {0, 0, 0, 0, 0, 0}, {0, 0, 0, 0, 0, 0}, {0, 0, 0, 0, 0, 0}}; - double propagatedQuaternion[4]; /*Filter Quaternion for next step*/ + double propagatedQuaternion[4]; /*Filter Quaternion for next step*/ uint8_t sensorsAvail = 0; /*Outputs*/ diff --git a/mission/persistentTmStoreDefs.h b/mission/persistentTmStoreDefs.h index 021f6f89..e84f12c1 100644 --- a/mission/persistentTmStoreDefs.h +++ b/mission/persistentTmStoreDefs.h @@ -25,17 +25,19 @@ static constexpr Event POSSIBLE_FILE_CORRUPTION = event::makeEvent(SUBSYSTEM_ID, //! P2: Allowed file size static constexpr Event FILE_TOO_LARGE = event::makeEvent(SUBSYSTEM_ID, 1, severity::LOW); static constexpr Event BUSY_DUMPING_EVENT = event::makeEvent(SUBSYSTEM_ID, 2, severity::INFO); +//! [EXPORT] : [COMMENT] Dump was cancelled. P1: Object ID of store. +static constexpr Event DUMP_WAS_CANCELLED = event::makeEvent(SUBSYSTEM_ID, 3, severity::LOW); //! [EXPORT] : [COMMENT] P1: Start time as UNIX seconds. P2: End time as UNIX seconds. -static constexpr Event DUMP_OK_STORE_DONE = event::makeEvent(SUBSYSTEM_ID, 3, severity::INFO); +static constexpr Event DUMP_OK_STORE_DONE = event::makeEvent(SUBSYSTEM_ID, 5, severity::INFO); //! [EXPORT] : [COMMENT] P1: Start time as UNIX seconds. P2: End time as UNIX seconds. -static constexpr Event DUMP_NOK_STORE_DONE = event::makeEvent(SUBSYSTEM_ID, 4, severity::INFO); +static constexpr Event DUMP_NOK_STORE_DONE = event::makeEvent(SUBSYSTEM_ID, 6, severity::INFO); //! [EXPORT] : [COMMENT] P1: Start time as UNIX seconds. P2: End time as UNIX seconds. -static constexpr Event DUMP_MISC_STORE_DONE = event::makeEvent(SUBSYSTEM_ID, 5, severity::INFO); +static constexpr Event DUMP_MISC_STORE_DONE = event::makeEvent(SUBSYSTEM_ID, 7, severity::INFO); //! [EXPORT] : [COMMENT] P1: Start time as UNIX seconds. P2: End time as UNIX seconds. -static constexpr Event DUMP_HK_STORE_DONE = event::makeEvent(SUBSYSTEM_ID, 6, severity::INFO); +static constexpr Event DUMP_HK_STORE_DONE = event::makeEvent(SUBSYSTEM_ID, 8, severity::INFO); //! [EXPORT] : [COMMENT] P1: Start time as UNIX seconds. P2: End time as UNIX seconds. -static constexpr Event DUMP_CFDP_STORE_DONE = event::makeEvent(SUBSYSTEM_ID, 7, severity::INFO); +static constexpr Event DUMP_CFDP_STORE_DONE = event::makeEvent(SUBSYSTEM_ID, 9, severity::INFO); }; // namespace persTmStore #endif /* MISSION_PERSISTENTTMSTOREDEFS_H_ */ diff --git a/mission/tmtc/PersistentTmStore.cpp b/mission/tmtc/PersistentTmStore.cpp index 79b7384b..2599a42f 100644 --- a/mission/tmtc/PersistentTmStore.cpp +++ b/mission/tmtc/PersistentTmStore.cpp @@ -26,6 +26,11 @@ PersistentTmStore::PersistentTmStore(PersistentTmStoreArgs args) calcDiffSeconds(args.intervalUnit, args.intervalCount); } +ReturnValue_t PersistentTmStore::cancelDump() { + state = State::IDLE; + return returnvalue::OK; +} + ReturnValue_t PersistentTmStore::assignAndOrCreateMostRecentFile() { if (not activeFile.has_value()) { return createMostRecentFile(std::nullopt); @@ -33,7 +38,8 @@ ReturnValue_t PersistentTmStore::assignAndOrCreateMostRecentFile() { return returnvalue::OK; } -ReturnValue_t PersistentTmStore::handleCommandQueue(StorageManagerIF& ipcStore) { +ReturnValue_t PersistentTmStore::handleCommandQueue(StorageManagerIF& ipcStore, + Command_t& execCmd) { CommandMessage cmdMessage; ReturnValue_t result = tcQueue->receiveMessage(&cmdMessage); if (result != returnvalue::OK) { @@ -49,6 +55,7 @@ ReturnValue_t PersistentTmStore::handleCommandQueue(StorageManagerIF& ipcStore) size_t size = accessor.second.size(); SerializeAdapter::deSerialize(&deleteUpToUnixSeconds, accessor.second.data(), &size, SerializeIF::Endianness::NETWORK); + execCmd = cmd; deleteUpTo(deleteUpToUnixSeconds); } else if (cmd == TmStoreMessage::DOWNLINK_STORE_CONTENT_TIME) { Clock::getClock_timeval(¤tTv); @@ -67,10 +74,12 @@ ReturnValue_t PersistentTmStore::handleCommandQueue(StorageManagerIF& ipcStore) result = startDumpFromUpTo(dumpFromUnixSeconds, dumpUntilUnixSeconds); if (result == BUSY_DUMPING) { triggerEvent(persTmStore::BUSY_DUMPING_EVENT); + } else { + execCmd = cmd; } } } - return returnvalue::OK; + return result; } ReturnValue_t PersistentTmStore::startDumpFrom(uint32_t fromUnixSeconds) { diff --git a/mission/tmtc/PersistentTmStore.h b/mission/tmtc/PersistentTmStore.h index 994b7d30..a0910026 100644 --- a/mission/tmtc/PersistentTmStore.h +++ b/mission/tmtc/PersistentTmStore.h @@ -1,6 +1,7 @@ #ifndef MISSION_TMTC_TMSTOREBACKEND_H_ #define MISSION_TMTC_TMSTOREBACKEND_H_ +#include #include #include #include @@ -49,7 +50,7 @@ class PersistentTmStore : public TmStoreFrontendSimpleIF, public SystemObject { ReturnValue_t initializeTmStore(); State getState() const; - ReturnValue_t handleCommandQueue(StorageManagerIF& ipcStore); + ReturnValue_t handleCommandQueue(StorageManagerIF& ipcStore, Command_t& execCmd); void deleteUpTo(uint32_t unixSeconds); ReturnValue_t startDumpFrom(uint32_t fromUnixSeconds); @@ -66,6 +67,7 @@ class PersistentTmStore : public TmStoreFrontendSimpleIF, public SystemObject { void getStartAndEndTimeCurrentOrLastDump(uint32_t& startTime, uint32_t& endTime) const; ReturnValue_t storePacket(PusTmReader& reader); + ReturnValue_t cancelDump(); protected: StorageManagerIF& tmStore; diff --git a/mission/tmtc/TmStoreTaskBase.cpp b/mission/tmtc/TmStoreTaskBase.cpp index fc79439b..ba0197fd 100644 --- a/mission/tmtc/TmStoreTaskBase.cpp +++ b/mission/tmtc/TmStoreTaskBase.cpp @@ -1,7 +1,11 @@ #include "TmStoreTaskBase.h" +#include #include #include +#include + +#include "mission/persistentTmStoreDefs.h" TmStoreTaskBase::TmStoreTaskBase(object_id_t objectId, StorageManagerIF& ipcStore, VirtualChannel& channel, SdCardMountedIF& sdcMan) @@ -22,6 +26,7 @@ bool TmStoreTaskBase::handleOneStore(PersistentTmStoreWithTmQueue& store, Event size_t dumpedLen; bool fileHasSwapped; if (not channel.isBusy()) { + tmSinkBusyCd.resetTimer(); // TODO: We could continously dump until a file swap during active downlink.. result = store.dumpNextPacket(channel, dumpedLen, fileHasSwapped); if (result == PersistentTmStore::DUMP_DONE) { @@ -34,10 +39,19 @@ bool TmStoreTaskBase::handleOneStore(PersistentTmStoreWithTmQueue& store, Event dumpsPerformed = true; } } + if (cancelDumpCd.hasTimedOut() or tmSinkBusyCd.hasTimedOut()) { + triggerEvent(persTmStore::DUMP_WAS_CANCELLED, store.getObjectId()); + store.cancelDump(); + } } else { + Command_t execCmd; // Handle TC requests, for example deletion or retrieval requests. - result = store.handleCommandQueue(ipcStore); + result = store.handleCommandQueue(ipcStore, execCmd); if (result == returnvalue::OK) { + if (execCmd == TmStoreMessage::DOWNLINK_STORE_CONTENT_TIME) { + cancelDumpCd.resetTimer(); + tmSinkBusyCd.resetTimer(); + } tcRequestReceived = true; } } diff --git a/mission/tmtc/TmStoreTaskBase.h b/mission/tmtc/TmStoreTaskBase.h index aa308590..c29db8bf 100644 --- a/mission/tmtc/TmStoreTaskBase.h +++ b/mission/tmtc/TmStoreTaskBase.h @@ -28,6 +28,10 @@ class TmStoreTaskBase : public SystemObject { StorageManagerIF& ipcStore; Countdown sdCardCheckCd = Countdown(800); + // 20 minutes are allowed as maximum dump time. + Countdown cancelDumpCd = Countdown(60 * 20 * 1000); + // If the TM sink is busy for 1 minute for whatever reason, cancel the dump. + Countdown tmSinkBusyCd = Countdown(60 * 1000); VirtualChannel& channel; bool storesInitialized = false; SdCardMountedIF& sdcMan; From b603554a807660843eee65ad942856d1080452b0 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 10 Mar 2023 21:01:32 +0100 Subject: [PATCH 101/112] new events --- .../fsfwconfig/events/translateEvents.cpp | 17 ++++++++++------- .../fsfwconfig/objects/translateObjects.cpp | 2 +- generators/bsp_hosted_events.csv | 11 ++++++----- generators/bsp_q7s_events.csv | 11 ++++++----- generators/events/translateEvents.cpp | 17 ++++++++++------- generators/objects/translateObjects.cpp | 2 +- linux/fsfwconfig/events/translateEvents.cpp | 17 ++++++++++------- linux/fsfwconfig/objects/translateObjects.cpp | 2 +- tmtc | 2 +- 9 files changed, 46 insertions(+), 35 deletions(-) diff --git a/bsp_hosted/fsfwconfig/events/translateEvents.cpp b/bsp_hosted/fsfwconfig/events/translateEvents.cpp index c6e45d49..b48b3958 100644 --- a/bsp_hosted/fsfwconfig/events/translateEvents.cpp +++ b/bsp_hosted/fsfwconfig/events/translateEvents.cpp @@ -1,7 +1,7 @@ /** - * @brief Auto-generated event translation file. Contains 276 translations. + * @brief Auto-generated event translation file. Contains 277 translations. * @details - * Generated on: 2023-03-10 19:14:19 + * Generated on: 2023-03-10 21:01:11 */ #include "translateEvents.h" @@ -271,6 +271,7 @@ const char *BIT_LOCK_TX_ON_STRING = "BIT_LOCK_TX_ON"; const char *POSSIBLE_FILE_CORRUPTION_STRING = "POSSIBLE_FILE_CORRUPTION"; const char *FILE_TOO_LARGE_STRING = "FILE_TOO_LARGE"; const char *BUSY_DUMPING_EVENT_STRING = "BUSY_DUMPING_EVENT"; +const char *DUMP_WAS_CANCELLED_STRING = "DUMP_WAS_CANCELLED"; const char *DUMP_OK_STORE_DONE_STRING = "DUMP_OK_STORE_DONE"; const char *DUMP_NOK_STORE_DONE_STRING = "DUMP_NOK_STORE_DONE"; const char *DUMP_MISC_STORE_DONE_STRING = "DUMP_MISC_STORE_DONE"; @@ -812,14 +813,16 @@ const char *translateEvents(Event event) { case (14302): return BUSY_DUMPING_EVENT_STRING; case (14303): - return DUMP_OK_STORE_DONE_STRING; - case (14304): - return DUMP_NOK_STORE_DONE_STRING; + return DUMP_WAS_CANCELLED_STRING; case (14305): - return DUMP_MISC_STORE_DONE_STRING; + return DUMP_OK_STORE_DONE_STRING; case (14306): - return DUMP_HK_STORE_DONE_STRING; + return DUMP_NOK_STORE_DONE_STRING; case (14307): + return DUMP_MISC_STORE_DONE_STRING; + case (14308): + return DUMP_HK_STORE_DONE_STRING; + case (14309): return DUMP_CFDP_STORE_DONE_STRING; default: return "UNKNOWN_EVENT"; diff --git a/bsp_hosted/fsfwconfig/objects/translateObjects.cpp b/bsp_hosted/fsfwconfig/objects/translateObjects.cpp index 82b361ce..4352ad47 100644 --- a/bsp_hosted/fsfwconfig/objects/translateObjects.cpp +++ b/bsp_hosted/fsfwconfig/objects/translateObjects.cpp @@ -2,7 +2,7 @@ * @brief Auto-generated object translation file. * @details * Contains 169 translations. - * Generated on: 2023-03-10 19:14:19 + * Generated on: 2023-03-10 21:01:11 */ #include "translateObjects.h" diff --git a/generators/bsp_hosted_events.csv b/generators/bsp_hosted_events.csv index fa3a02c5..c1b0559d 100644 --- a/generators/bsp_hosted_events.csv +++ b/generators/bsp_hosted_events.csv @@ -270,8 +270,9 @@ Event ID (dec); Event ID (hex); Name; Severity; Description; File Path 14300;0x37dc;POSSIBLE_FILE_CORRUPTION;LOW;P1: Result code of TM packet parser. P2: Timestamp of possibly corrupt file as a unix timestamp.;mission/persistentTmStoreDefs.h 14301;0x37dd;FILE_TOO_LARGE;LOW;File in store too large. P1: Detected file size P2: Allowed file size;mission/persistentTmStoreDefs.h 14302;0x37de;BUSY_DUMPING_EVENT;INFO;No description;mission/persistentTmStoreDefs.h -14303;0x37df;DUMP_OK_STORE_DONE;INFO;P1: Start time as UNIX seconds. P2: End time as UNIX seconds.;mission/persistentTmStoreDefs.h -14304;0x37e0;DUMP_NOK_STORE_DONE;INFO;P1: Start time as UNIX seconds. P2: End time as UNIX seconds.;mission/persistentTmStoreDefs.h -14305;0x37e1;DUMP_MISC_STORE_DONE;INFO;P1: Start time as UNIX seconds. P2: End time as UNIX seconds.;mission/persistentTmStoreDefs.h -14306;0x37e2;DUMP_HK_STORE_DONE;INFO;P1: Start time as UNIX seconds. P2: End time as UNIX seconds.;mission/persistentTmStoreDefs.h -14307;0x37e3;DUMP_CFDP_STORE_DONE;INFO;P1: Start time as UNIX seconds. P2: End time as UNIX seconds.;mission/persistentTmStoreDefs.h +14303;0x37df;DUMP_WAS_CANCELLED;LOW;Dump was cancelled. P1: Object ID of store.;mission/persistentTmStoreDefs.h +14305;0x37e1;DUMP_OK_STORE_DONE;INFO;P1: Start time as UNIX seconds. P2: End time as UNIX seconds.;mission/persistentTmStoreDefs.h +14306;0x37e2;DUMP_NOK_STORE_DONE;INFO;P1: Start time as UNIX seconds. P2: End time as UNIX seconds.;mission/persistentTmStoreDefs.h +14307;0x37e3;DUMP_MISC_STORE_DONE;INFO;P1: Start time as UNIX seconds. P2: End time as UNIX seconds.;mission/persistentTmStoreDefs.h +14308;0x37e4;DUMP_HK_STORE_DONE;INFO;P1: Start time as UNIX seconds. P2: End time as UNIX seconds.;mission/persistentTmStoreDefs.h +14309;0x37e5;DUMP_CFDP_STORE_DONE;INFO;P1: Start time as UNIX seconds. P2: End time as UNIX seconds.;mission/persistentTmStoreDefs.h diff --git a/generators/bsp_q7s_events.csv b/generators/bsp_q7s_events.csv index fa3a02c5..c1b0559d 100644 --- a/generators/bsp_q7s_events.csv +++ b/generators/bsp_q7s_events.csv @@ -270,8 +270,9 @@ Event ID (dec); Event ID (hex); Name; Severity; Description; File Path 14300;0x37dc;POSSIBLE_FILE_CORRUPTION;LOW;P1: Result code of TM packet parser. P2: Timestamp of possibly corrupt file as a unix timestamp.;mission/persistentTmStoreDefs.h 14301;0x37dd;FILE_TOO_LARGE;LOW;File in store too large. P1: Detected file size P2: Allowed file size;mission/persistentTmStoreDefs.h 14302;0x37de;BUSY_DUMPING_EVENT;INFO;No description;mission/persistentTmStoreDefs.h -14303;0x37df;DUMP_OK_STORE_DONE;INFO;P1: Start time as UNIX seconds. P2: End time as UNIX seconds.;mission/persistentTmStoreDefs.h -14304;0x37e0;DUMP_NOK_STORE_DONE;INFO;P1: Start time as UNIX seconds. P2: End time as UNIX seconds.;mission/persistentTmStoreDefs.h -14305;0x37e1;DUMP_MISC_STORE_DONE;INFO;P1: Start time as UNIX seconds. P2: End time as UNIX seconds.;mission/persistentTmStoreDefs.h -14306;0x37e2;DUMP_HK_STORE_DONE;INFO;P1: Start time as UNIX seconds. P2: End time as UNIX seconds.;mission/persistentTmStoreDefs.h -14307;0x37e3;DUMP_CFDP_STORE_DONE;INFO;P1: Start time as UNIX seconds. P2: End time as UNIX seconds.;mission/persistentTmStoreDefs.h +14303;0x37df;DUMP_WAS_CANCELLED;LOW;Dump was cancelled. P1: Object ID of store.;mission/persistentTmStoreDefs.h +14305;0x37e1;DUMP_OK_STORE_DONE;INFO;P1: Start time as UNIX seconds. P2: End time as UNIX seconds.;mission/persistentTmStoreDefs.h +14306;0x37e2;DUMP_NOK_STORE_DONE;INFO;P1: Start time as UNIX seconds. P2: End time as UNIX seconds.;mission/persistentTmStoreDefs.h +14307;0x37e3;DUMP_MISC_STORE_DONE;INFO;P1: Start time as UNIX seconds. P2: End time as UNIX seconds.;mission/persistentTmStoreDefs.h +14308;0x37e4;DUMP_HK_STORE_DONE;INFO;P1: Start time as UNIX seconds. P2: End time as UNIX seconds.;mission/persistentTmStoreDefs.h +14309;0x37e5;DUMP_CFDP_STORE_DONE;INFO;P1: Start time as UNIX seconds. P2: End time as UNIX seconds.;mission/persistentTmStoreDefs.h diff --git a/generators/events/translateEvents.cpp b/generators/events/translateEvents.cpp index c6e45d49..b48b3958 100644 --- a/generators/events/translateEvents.cpp +++ b/generators/events/translateEvents.cpp @@ -1,7 +1,7 @@ /** - * @brief Auto-generated event translation file. Contains 276 translations. + * @brief Auto-generated event translation file. Contains 277 translations. * @details - * Generated on: 2023-03-10 19:14:19 + * Generated on: 2023-03-10 21:01:11 */ #include "translateEvents.h" @@ -271,6 +271,7 @@ const char *BIT_LOCK_TX_ON_STRING = "BIT_LOCK_TX_ON"; const char *POSSIBLE_FILE_CORRUPTION_STRING = "POSSIBLE_FILE_CORRUPTION"; const char *FILE_TOO_LARGE_STRING = "FILE_TOO_LARGE"; const char *BUSY_DUMPING_EVENT_STRING = "BUSY_DUMPING_EVENT"; +const char *DUMP_WAS_CANCELLED_STRING = "DUMP_WAS_CANCELLED"; const char *DUMP_OK_STORE_DONE_STRING = "DUMP_OK_STORE_DONE"; const char *DUMP_NOK_STORE_DONE_STRING = "DUMP_NOK_STORE_DONE"; const char *DUMP_MISC_STORE_DONE_STRING = "DUMP_MISC_STORE_DONE"; @@ -812,14 +813,16 @@ const char *translateEvents(Event event) { case (14302): return BUSY_DUMPING_EVENT_STRING; case (14303): - return DUMP_OK_STORE_DONE_STRING; - case (14304): - return DUMP_NOK_STORE_DONE_STRING; + return DUMP_WAS_CANCELLED_STRING; case (14305): - return DUMP_MISC_STORE_DONE_STRING; + return DUMP_OK_STORE_DONE_STRING; case (14306): - return DUMP_HK_STORE_DONE_STRING; + return DUMP_NOK_STORE_DONE_STRING; case (14307): + return DUMP_MISC_STORE_DONE_STRING; + case (14308): + return DUMP_HK_STORE_DONE_STRING; + case (14309): return DUMP_CFDP_STORE_DONE_STRING; default: return "UNKNOWN_EVENT"; diff --git a/generators/objects/translateObjects.cpp b/generators/objects/translateObjects.cpp index c491e7b0..5e772262 100644 --- a/generators/objects/translateObjects.cpp +++ b/generators/objects/translateObjects.cpp @@ -2,7 +2,7 @@ * @brief Auto-generated object translation file. * @details * Contains 173 translations. - * Generated on: 2023-03-10 19:14:19 + * Generated on: 2023-03-10 21:01:11 */ #include "translateObjects.h" diff --git a/linux/fsfwconfig/events/translateEvents.cpp b/linux/fsfwconfig/events/translateEvents.cpp index c6e45d49..b48b3958 100644 --- a/linux/fsfwconfig/events/translateEvents.cpp +++ b/linux/fsfwconfig/events/translateEvents.cpp @@ -1,7 +1,7 @@ /** - * @brief Auto-generated event translation file. Contains 276 translations. + * @brief Auto-generated event translation file. Contains 277 translations. * @details - * Generated on: 2023-03-10 19:14:19 + * Generated on: 2023-03-10 21:01:11 */ #include "translateEvents.h" @@ -271,6 +271,7 @@ const char *BIT_LOCK_TX_ON_STRING = "BIT_LOCK_TX_ON"; const char *POSSIBLE_FILE_CORRUPTION_STRING = "POSSIBLE_FILE_CORRUPTION"; const char *FILE_TOO_LARGE_STRING = "FILE_TOO_LARGE"; const char *BUSY_DUMPING_EVENT_STRING = "BUSY_DUMPING_EVENT"; +const char *DUMP_WAS_CANCELLED_STRING = "DUMP_WAS_CANCELLED"; const char *DUMP_OK_STORE_DONE_STRING = "DUMP_OK_STORE_DONE"; const char *DUMP_NOK_STORE_DONE_STRING = "DUMP_NOK_STORE_DONE"; const char *DUMP_MISC_STORE_DONE_STRING = "DUMP_MISC_STORE_DONE"; @@ -812,14 +813,16 @@ const char *translateEvents(Event event) { case (14302): return BUSY_DUMPING_EVENT_STRING; case (14303): - return DUMP_OK_STORE_DONE_STRING; - case (14304): - return DUMP_NOK_STORE_DONE_STRING; + return DUMP_WAS_CANCELLED_STRING; case (14305): - return DUMP_MISC_STORE_DONE_STRING; + return DUMP_OK_STORE_DONE_STRING; case (14306): - return DUMP_HK_STORE_DONE_STRING; + return DUMP_NOK_STORE_DONE_STRING; case (14307): + return DUMP_MISC_STORE_DONE_STRING; + case (14308): + return DUMP_HK_STORE_DONE_STRING; + case (14309): return DUMP_CFDP_STORE_DONE_STRING; default: return "UNKNOWN_EVENT"; diff --git a/linux/fsfwconfig/objects/translateObjects.cpp b/linux/fsfwconfig/objects/translateObjects.cpp index c491e7b0..5e772262 100644 --- a/linux/fsfwconfig/objects/translateObjects.cpp +++ b/linux/fsfwconfig/objects/translateObjects.cpp @@ -2,7 +2,7 @@ * @brief Auto-generated object translation file. * @details * Contains 173 translations. - * Generated on: 2023-03-10 19:14:19 + * Generated on: 2023-03-10 21:01:11 */ #include "translateObjects.h" diff --git a/tmtc b/tmtc index 26cd265e..cd0fd4d5 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 26cd265e19b8077432ae670760e92fee27e438c4 +Subproject commit cd0fd4d5a7142554c95d90574b5539931adcd5ff From 97698a08d55db9cd35c8b6ae3689fed327e4f1cb Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 10 Mar 2023 21:13:11 +0100 Subject: [PATCH 102/112] tweak events.. comntinue later --- mission/persistentTmStoreDefs.h | 10 +++++----- mission/tmtc/PersistentSingleTmStoreTask.h | 1 + mission/tmtc/PersistentTmStore.cpp | 2 ++ mission/tmtc/TmStoreTaskBase.cpp | 5 +++-- 4 files changed, 11 insertions(+), 7 deletions(-) diff --git a/mission/persistentTmStoreDefs.h b/mission/persistentTmStoreDefs.h index e84f12c1..01fe6781 100644 --- a/mission/persistentTmStoreDefs.h +++ b/mission/persistentTmStoreDefs.h @@ -28,15 +28,15 @@ static constexpr Event BUSY_DUMPING_EVENT = event::makeEvent(SUBSYSTEM_ID, 2, se //! [EXPORT] : [COMMENT] Dump was cancelled. P1: Object ID of store. static constexpr Event DUMP_WAS_CANCELLED = event::makeEvent(SUBSYSTEM_ID, 3, severity::LOW); -//! [EXPORT] : [COMMENT] P1: Start time as UNIX seconds. P2: End time as UNIX seconds. +//! [EXPORT] : [COMMENT] P1: Number of dumped packets. static constexpr Event DUMP_OK_STORE_DONE = event::makeEvent(SUBSYSTEM_ID, 5, severity::INFO); -//! [EXPORT] : [COMMENT] P1: Start time as UNIX seconds. P2: End time as UNIX seconds. +//! [EXPORT] : [COMMENT] P1: Number of dumped packets. static constexpr Event DUMP_NOK_STORE_DONE = event::makeEvent(SUBSYSTEM_ID, 6, severity::INFO); -//! [EXPORT] : [COMMENT] P1: Start time as UNIX seconds. P2: End time as UNIX seconds. +//! [EXPORT] : [COMMENT] P1: Number of dumped packets. static constexpr Event DUMP_MISC_STORE_DONE = event::makeEvent(SUBSYSTEM_ID, 7, severity::INFO); -//! [EXPORT] : [COMMENT] P1: Start time as UNIX seconds. P2: End time as UNIX seconds. +//! [EXPORT] : [COMMENT] P1: Number of dumped packets. static constexpr Event DUMP_HK_STORE_DONE = event::makeEvent(SUBSYSTEM_ID, 8, severity::INFO); -//! [EXPORT] : [COMMENT] P1: Start time as UNIX seconds. P2: End time as UNIX seconds. +//! [EXPORT] : [COMMENT] P1: Number of dumped packets. static constexpr Event DUMP_CFDP_STORE_DONE = event::makeEvent(SUBSYSTEM_ID, 9, severity::INFO); }; // namespace persTmStore diff --git a/mission/tmtc/PersistentSingleTmStoreTask.h b/mission/tmtc/PersistentSingleTmStoreTask.h index 2fc9ece1..08ec8b17 100644 --- a/mission/tmtc/PersistentSingleTmStoreTask.h +++ b/mission/tmtc/PersistentSingleTmStoreTask.h @@ -18,6 +18,7 @@ class PersistentSingleTmStoreTask : public TmStoreTaskBase, public ExecutableObj private: PersistentTmStoreWithTmQueue& storeWithQueue; Event eventIfDumpDone; + uint32_t numberOfDumpedPackets = 0; Countdown tcHandlingCd = Countdown(400); bool initStoresIfPossible(); diff --git a/mission/tmtc/PersistentTmStore.cpp b/mission/tmtc/PersistentTmStore.cpp index 2599a42f..445eee9d 100644 --- a/mission/tmtc/PersistentTmStore.cpp +++ b/mission/tmtc/PersistentTmStore.cpp @@ -216,6 +216,8 @@ ReturnValue_t PersistentTmStore::loadNextDumpFile() { sif::error << "PersistentTmStore: Could not retrieve file size: " << e.message() << std::endl; continue; } + sif::debug << "Path: " << dumpParams.dirEntry.path() << std::endl; + // Can't even read CCSDS header. if (dumpParams.fileSize <= 6) { continue; diff --git a/mission/tmtc/TmStoreTaskBase.cpp b/mission/tmtc/TmStoreTaskBase.cpp index ba0197fd..5c0402fe 100644 --- a/mission/tmtc/TmStoreTaskBase.cpp +++ b/mission/tmtc/TmStoreTaskBase.cpp @@ -11,7 +11,8 @@ TmStoreTaskBase::TmStoreTaskBase(object_id_t objectId, StorageManagerIF& ipcStor VirtualChannel& channel, SdCardMountedIF& sdcMan) : SystemObject(objectId), ipcStore(ipcStore), channel(channel), sdcMan(sdcMan) {} -bool TmStoreTaskBase::handleOneStore(PersistentTmStoreWithTmQueue& store, Event eventIfDone) { +bool TmStoreTaskBase::handleOneStore(PersistentTmStoreWithTmQueue& store, Event eventIfDone, + uint32_t& numberOfDumpedPackets) { ReturnValue_t result; bool tmToStoreReceived = false; bool tcRequestReceived = false; @@ -33,7 +34,7 @@ bool TmStoreTaskBase::handleOneStore(PersistentTmStoreWithTmQueue& store, Event uint32_t startTime; uint32_t endTime; store.getStartAndEndTimeCurrentOrLastDump(startTime, endTime); - triggerEvent(eventIfDone, startTime, endTime); + triggerEvent(eventIfDone, numberOfDumpedPackets); dumpsPerformed = true; } else if (result == returnvalue::OK) { dumpsPerformed = true; From 989293860140c8d24f780b21d942dfc1a7077fc6 Mon Sep 17 00:00:00 2001 From: meggert Date: Sat, 11 Mar 2023 10:21:09 +0100 Subject: [PATCH 103/112] fixed bias substraction --- mission/controller/acs/SensorProcessing.cpp | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/mission/controller/acs/SensorProcessing.cpp b/mission/controller/acs/SensorProcessing.cpp index b3423367..b2812f55 100644 --- a/mission/controller/acs/SensorProcessing.cpp +++ b/mission/controller/acs/SensorProcessing.cpp @@ -470,10 +470,10 @@ void SensorProcessing::processGyr( float sensorFusionNumerator[3] = {0, 0, 0}, sensorFusionDenominator[3] = {0, 0, 0}; if (gyr0valid) { - const double gyr0Value[3] = {gyr0axXvalue, gyr0axYvalue, gyr0axZvalue}; + double gyr0Value[3] = {gyr0axXvalue, gyr0axYvalue, gyr0axZvalue}; + VectorOperations::subtract(gyr0Value, gyrParameters->gyr0bias, gyr0Value, 3); MatrixOperations::multiply(gyrParameters->gyr0orientationMatrix[0], gyr0Value, gyr0ValueBody, 3, 3, 1); - VectorOperations::subtract(gyr0ValueBody, gyrParameters->gyr0bias, gyr0ValueBody, 3); VectorOperations::mulScalar(gyr0ValueBody, M_PI / 180, gyr0ValueBody, 3); for (uint8_t i = 0; i < 3; i++) { sensorFusionNumerator[i] += gyr0ValueBody[i] / gyrParameters->gyr02variance[i]; @@ -481,10 +481,10 @@ void SensorProcessing::processGyr( } } if (gyr1valid) { - const double gyr1Value[3] = {gyr1axXvalue, gyr1axYvalue, gyr1axZvalue}; + double gyr1Value[3] = {gyr1axXvalue, gyr1axYvalue, gyr1axZvalue}; + VectorOperations::subtract(gyr1Value, gyrParameters->gyr1bias, gyr1Value, 3); MatrixOperations::multiply(gyrParameters->gyr1orientationMatrix[0], gyr1Value, gyr1ValueBody, 3, 3, 1); - VectorOperations::subtract(gyr1ValueBody, gyrParameters->gyr1bias, gyr1ValueBody, 3); VectorOperations::mulScalar(gyr1ValueBody, M_PI / 180, gyr1ValueBody, 3); for (uint8_t i = 0; i < 3; i++) { sensorFusionNumerator[i] += gyr1ValueBody[i] / gyrParameters->gyr13variance[i]; @@ -492,10 +492,10 @@ void SensorProcessing::processGyr( } } if (gyr2valid) { - const double gyr2Value[3] = {gyr2axXvalue, gyr2axYvalue, gyr2axZvalue}; + double gyr2Value[3] = {gyr2axXvalue, gyr2axYvalue, gyr2axZvalue}; + VectorOperations::subtract(gyr2Value, gyrParameters->gyr2bias, gyr2Value, 3); MatrixOperations::multiply(gyrParameters->gyr2orientationMatrix[0], gyr2Value, gyr2ValueBody, 3, 3, 1); - VectorOperations::subtract(gyr2ValueBody, gyrParameters->gyr2bias, gyr2ValueBody, 3); VectorOperations::mulScalar(gyr2ValueBody, M_PI / 180, gyr2ValueBody, 3); for (uint8_t i = 0; i < 3; i++) { sensorFusionNumerator[i] += gyr2ValueBody[i] / gyrParameters->gyr02variance[i]; @@ -503,10 +503,10 @@ void SensorProcessing::processGyr( } } if (gyr3valid) { - const double gyr3Value[3] = {gyr3axXvalue, gyr3axYvalue, gyr3axZvalue}; + double gyr3Value[3] = {gyr3axXvalue, gyr3axYvalue, gyr3axZvalue}; + VectorOperations::subtract(gyr3Value, gyrParameters->gyr3bias, gyr3Value, 3); MatrixOperations::multiply(gyrParameters->gyr3orientationMatrix[0], gyr3Value, gyr3ValueBody, 3, 3, 1); - VectorOperations::subtract(gyr3ValueBody, gyrParameters->gyr3bias, gyr3ValueBody, 3); VectorOperations::mulScalar(gyr3ValueBody, M_PI / 180, gyr3ValueBody, 3); for (uint8_t i = 0; i < 3; i++) { sensorFusionNumerator[i] += gyr3ValueBody[i] / gyrParameters->gyr13variance[i]; From 0f7fd39d72f509592da5c900216f9f5b5d442cf2 Mon Sep 17 00:00:00 2001 From: meggert Date: Sat, 11 Mar 2023 10:22:21 +0100 Subject: [PATCH 104/112] changelog --- CHANGELOG.md | 1 + 1 file changed, 1 insertion(+) diff --git a/CHANGELOG.md b/CHANGELOG.md index 79939ff0..35a14d84 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -43,6 +43,7 @@ will consitute of a breaking change warranting a new major release: - Solved naming collision between file used for solar array deployment and confirmation for ACS for solar array deployment. - Fixed that scaling of RW torque would result in a zero vector unless the maximum value was exceeded. +- Bias for the GYR data was substracted within the wrong rf (sensor rf vs body rf). ## Changed From a4e6d877ff568d49a0c9a22d2c0bbf8eaca79f4c Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Sat, 11 Mar 2023 14:59:55 +0100 Subject: [PATCH 105/112] this is more useful information --- mission/persistentTmStoreDefs.h | 10 +++++----- mission/tmtc/PersistentLogTmStoreTask.cpp | 11 +++++++---- mission/tmtc/PersistentLogTmStoreTask.h | 3 +++ mission/tmtc/PersistentSingleTmStoreTask.cpp | 4 ++-- mission/tmtc/PersistentSingleTmStoreTask.h | 3 +-- mission/tmtc/TmStoreTaskBase.cpp | 15 ++++++++++----- mission/tmtc/TmStoreTaskBase.h | 13 ++++++++++++- tmtc | 2 +- 8 files changed, 41 insertions(+), 20 deletions(-) diff --git a/mission/persistentTmStoreDefs.h b/mission/persistentTmStoreDefs.h index 01fe6781..2498536d 100644 --- a/mission/persistentTmStoreDefs.h +++ b/mission/persistentTmStoreDefs.h @@ -28,15 +28,15 @@ static constexpr Event BUSY_DUMPING_EVENT = event::makeEvent(SUBSYSTEM_ID, 2, se //! [EXPORT] : [COMMENT] Dump was cancelled. P1: Object ID of store. static constexpr Event DUMP_WAS_CANCELLED = event::makeEvent(SUBSYSTEM_ID, 3, severity::LOW); -//! [EXPORT] : [COMMENT] P1: Number of dumped packets. +//! [EXPORT] : [COMMENT] P1: Number of dumped packets. P2: Total dumped bytes. static constexpr Event DUMP_OK_STORE_DONE = event::makeEvent(SUBSYSTEM_ID, 5, severity::INFO); -//! [EXPORT] : [COMMENT] P1: Number of dumped packets. +//! [EXPORT] : [COMMENT] P1: Number of dumped packets. P2: Total dumped bytes. static constexpr Event DUMP_NOK_STORE_DONE = event::makeEvent(SUBSYSTEM_ID, 6, severity::INFO); -//! [EXPORT] : [COMMENT] P1: Number of dumped packets. +//! [EXPORT] : [COMMENT] P1: Number of dumped packets. P2: Total dumped bytes. static constexpr Event DUMP_MISC_STORE_DONE = event::makeEvent(SUBSYSTEM_ID, 7, severity::INFO); -//! [EXPORT] : [COMMENT] P1: Number of dumped packets. +//! [EXPORT] : [COMMENT] P1: Number of dumped packets. P2: Total dumped bytes. static constexpr Event DUMP_HK_STORE_DONE = event::makeEvent(SUBSYSTEM_ID, 8, severity::INFO); -//! [EXPORT] : [COMMENT] P1: Number of dumped packets. +//! [EXPORT] : [COMMENT] P1: Number of dumped packets. P2: Total dumped bytes. static constexpr Event DUMP_CFDP_STORE_DONE = event::makeEvent(SUBSYSTEM_ID, 9, severity::INFO); }; // namespace persTmStore diff --git a/mission/tmtc/PersistentLogTmStoreTask.cpp b/mission/tmtc/PersistentLogTmStoreTask.cpp index 3d0d99ee..aac51c55 100644 --- a/mission/tmtc/PersistentLogTmStoreTask.cpp +++ b/mission/tmtc/PersistentLogTmStoreTask.cpp @@ -6,7 +6,10 @@ PersistentLogTmStoreTask::PersistentLogTmStoreTask(object_id_t objectId, StorageManagerIF& ipcStore, LogStores stores, VirtualChannel& channel, SdCardMountedIF& sdcMan) - : TmStoreTaskBase(objectId, ipcStore, channel, sdcMan), stores(stores) {} + : TmStoreTaskBase(objectId, ipcStore, channel, sdcMan), stores(stores), + okStoreContext(persTmStore::DUMP_OK_STORE_DONE), + notOkStoreContext(persTmStore::DUMP_NOK_STORE_DONE), + miscStoreContext(persTmStore::DUMP_MISC_STORE_DONE) {} ReturnValue_t PersistentLogTmStoreTask::performOperation(uint8_t opCode) { while (true) { @@ -15,15 +18,15 @@ ReturnValue_t PersistentLogTmStoreTask::performOperation(uint8_t opCode) { } bool someonesBusy = false; bool busy = false; - busy = handleOneStore(stores.okStore, persTmStore::DUMP_OK_STORE_DONE); + busy = handleOneStore(stores.okStore, okStoreContext); if (busy) { someonesBusy = true; } - busy = handleOneStore(stores.notOkStore, persTmStore::DUMP_NOK_STORE_DONE); + busy = handleOneStore(stores.notOkStore, notOkStoreContext); if (busy) { someonesBusy = true; } - busy = handleOneStore(stores.miscStore, persTmStore::DUMP_MISC_STORE_DONE); + busy = handleOneStore(stores.miscStore, miscStoreContext); if (busy) { someonesBusy = true; } diff --git a/mission/tmtc/PersistentLogTmStoreTask.h b/mission/tmtc/PersistentLogTmStoreTask.h index fc4242db..8cd74f20 100644 --- a/mission/tmtc/PersistentLogTmStoreTask.h +++ b/mission/tmtc/PersistentLogTmStoreTask.h @@ -28,6 +28,9 @@ class PersistentLogTmStoreTask : public TmStoreTaskBase, public ExecutableObject private: LogStores stores; + DumpContext okStoreContext; + DumpContext notOkStoreContext; + DumpContext miscStoreContext; Countdown tcHandlingCd = Countdown(400); bool initStoresIfPossible(); diff --git a/mission/tmtc/PersistentSingleTmStoreTask.cpp b/mission/tmtc/PersistentSingleTmStoreTask.cpp index e3e1688e..3588b9fd 100644 --- a/mission/tmtc/PersistentSingleTmStoreTask.cpp +++ b/mission/tmtc/PersistentSingleTmStoreTask.cpp @@ -7,7 +7,7 @@ PersistentSingleTmStoreTask::PersistentSingleTmStoreTask( VirtualChannel& channel, Event eventIfDumpDone, SdCardMountedIF& sdcMan) : TmStoreTaskBase(objectId, ipcStore, channel, sdcMan), storeWithQueue(tmStore), - eventIfDumpDone(eventIfDumpDone) {} + dumpContext(eventIfDumpDone) {} ReturnValue_t PersistentSingleTmStoreTask::performOperation(uint8_t opCode) { while (true) { @@ -15,7 +15,7 @@ ReturnValue_t PersistentSingleTmStoreTask::performOperation(uint8_t opCode) { if (not cyclicStoreCheck()) { continue; } - bool busy = handleOneStore(storeWithQueue, eventIfDumpDone); + bool busy = handleOneStore(storeWithQueue, dumpContext); if (not busy) { TaskFactory::delayTask(40); } diff --git a/mission/tmtc/PersistentSingleTmStoreTask.h b/mission/tmtc/PersistentSingleTmStoreTask.h index 08ec8b17..b21ddf1d 100644 --- a/mission/tmtc/PersistentSingleTmStoreTask.h +++ b/mission/tmtc/PersistentSingleTmStoreTask.h @@ -17,8 +17,7 @@ class PersistentSingleTmStoreTask : public TmStoreTaskBase, public ExecutableObj private: PersistentTmStoreWithTmQueue& storeWithQueue; - Event eventIfDumpDone; - uint32_t numberOfDumpedPackets = 0; + DumpContext dumpContext; Countdown tcHandlingCd = Countdown(400); bool initStoresIfPossible(); diff --git a/mission/tmtc/TmStoreTaskBase.cpp b/mission/tmtc/TmStoreTaskBase.cpp index 5c0402fe..d8b6bdcb 100644 --- a/mission/tmtc/TmStoreTaskBase.cpp +++ b/mission/tmtc/TmStoreTaskBase.cpp @@ -11,8 +11,8 @@ TmStoreTaskBase::TmStoreTaskBase(object_id_t objectId, StorageManagerIF& ipcStor VirtualChannel& channel, SdCardMountedIF& sdcMan) : SystemObject(objectId), ipcStore(ipcStore), channel(channel), sdcMan(sdcMan) {} -bool TmStoreTaskBase::handleOneStore(PersistentTmStoreWithTmQueue& store, Event eventIfDone, - uint32_t& numberOfDumpedPackets) { +bool TmStoreTaskBase::handleOneStore(PersistentTmStoreWithTmQueue& store, + DumpContext& dumpContext) { ReturnValue_t result; bool tmToStoreReceived = false; bool tcRequestReceived = false; @@ -24,17 +24,21 @@ bool TmStoreTaskBase::handleOneStore(PersistentTmStoreWithTmQueue& store, Event } // Dump TMs when applicable if (store.getState() == PersistentTmStore::State::DUMPING) { - size_t dumpedLen; + size_t dumpedLen = 0; bool fileHasSwapped; if (not channel.isBusy()) { tmSinkBusyCd.resetTimer(); - // TODO: We could continously dump until a file swap during active downlink.. result = store.dumpNextPacket(channel, dumpedLen, fileHasSwapped); + if ((result == PersistentTmStore::DUMP_DONE or result == returnvalue::OK) and dumpedLen > 0) { + dumpContext.dumpedBytes += dumpedLen; + dumpContext.numberOfDumpedPackets += 1; + } if (result == PersistentTmStore::DUMP_DONE) { uint32_t startTime; uint32_t endTime; store.getStartAndEndTimeCurrentOrLastDump(startTime, endTime); - triggerEvent(eventIfDone, numberOfDumpedPackets); + triggerEvent(dumpContext.eventIfDone, dumpContext.numberOfDumpedPackets, + dumpContext.dumpedBytes); dumpsPerformed = true; } else if (result == returnvalue::OK) { dumpsPerformed = true; @@ -52,6 +56,7 @@ bool TmStoreTaskBase::handleOneStore(PersistentTmStoreWithTmQueue& store, Event if (execCmd == TmStoreMessage::DOWNLINK_STORE_CONTENT_TIME) { cancelDumpCd.resetTimer(); tmSinkBusyCd.resetTimer(); + dumpContext.reset(); } tcRequestReceived = true; } diff --git a/mission/tmtc/TmStoreTaskBase.h b/mission/tmtc/TmStoreTaskBase.h index c29db8bf..2d899be3 100644 --- a/mission/tmtc/TmStoreTaskBase.h +++ b/mission/tmtc/TmStoreTaskBase.h @@ -7,6 +7,17 @@ class TmStoreTaskBase : public SystemObject { public: + struct DumpContext { + DumpContext(Event eventIfDone) : eventIfDone(eventIfDone) {} + void reset() { + numberOfDumpedPackets = 0; + dumpedBytes = 0; + } + const Event eventIfDone; + uint32_t numberOfDumpedPackets = 0; + uint32_t dumpedBytes = 0; + }; + TmStoreTaskBase(object_id_t objectId, StorageManagerIF& ipcStore, VirtualChannel& channel, SdCardMountedIF& sdcMan); @@ -16,7 +27,7 @@ class TmStoreTaskBase : public SystemObject { * @param store * @return */ - bool handleOneStore(PersistentTmStoreWithTmQueue& store, Event eventIfDone); + bool handleOneStore(PersistentTmStoreWithTmQueue& store, DumpContext& dumpContext); /** * Occasionally check whether SD card is okay to be used. If not, poll whether it is ready to diff --git a/tmtc b/tmtc index cd0fd4d5..4686550e 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit cd0fd4d5a7142554c95d90574b5539931adcd5ff +Subproject commit 4686550eb9455175227559dc36902469255e36b7 From 16ea033fd2a57794f307a6c964cc2a3d504023c0 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Sat, 11 Mar 2023 15:01:38 +0100 Subject: [PATCH 106/112] re-generate files --- .../fsfwconfig/events/translateEvents.cpp | 2 +- .../fsfwconfig/objects/translateObjects.cpp | 2 +- generators/bsp_hosted_events.csv | 10 +- generators/bsp_hosted_returnvalues.csv | 653 +++++++-------- generators/bsp_q7s_events.csv | 10 +- generators/bsp_q7s_returnvalues.csv | 763 +++++++++--------- generators/events/translateEvents.cpp | 2 +- generators/objects/translateObjects.cpp | 2 +- linux/fsfwconfig/events/translateEvents.cpp | 2 +- linux/fsfwconfig/objects/translateObjects.cpp | 2 +- tmtc | 2 +- 11 files changed, 730 insertions(+), 720 deletions(-) diff --git a/bsp_hosted/fsfwconfig/events/translateEvents.cpp b/bsp_hosted/fsfwconfig/events/translateEvents.cpp index b48b3958..94d829fe 100644 --- a/bsp_hosted/fsfwconfig/events/translateEvents.cpp +++ b/bsp_hosted/fsfwconfig/events/translateEvents.cpp @@ -1,7 +1,7 @@ /** * @brief Auto-generated event translation file. Contains 277 translations. * @details - * Generated on: 2023-03-10 21:01:11 + * Generated on: 2023-03-11 15:01:05 */ #include "translateEvents.h" diff --git a/bsp_hosted/fsfwconfig/objects/translateObjects.cpp b/bsp_hosted/fsfwconfig/objects/translateObjects.cpp index 4352ad47..54802800 100644 --- a/bsp_hosted/fsfwconfig/objects/translateObjects.cpp +++ b/bsp_hosted/fsfwconfig/objects/translateObjects.cpp @@ -2,7 +2,7 @@ * @brief Auto-generated object translation file. * @details * Contains 169 translations. - * Generated on: 2023-03-10 21:01:11 + * Generated on: 2023-03-11 15:01:05 */ #include "translateObjects.h" diff --git a/generators/bsp_hosted_events.csv b/generators/bsp_hosted_events.csv index c1b0559d..b2c6c28f 100644 --- a/generators/bsp_hosted_events.csv +++ b/generators/bsp_hosted_events.csv @@ -271,8 +271,8 @@ Event ID (dec); Event ID (hex); Name; Severity; Description; File Path 14301;0x37dd;FILE_TOO_LARGE;LOW;File in store too large. P1: Detected file size P2: Allowed file size;mission/persistentTmStoreDefs.h 14302;0x37de;BUSY_DUMPING_EVENT;INFO;No description;mission/persistentTmStoreDefs.h 14303;0x37df;DUMP_WAS_CANCELLED;LOW;Dump was cancelled. P1: Object ID of store.;mission/persistentTmStoreDefs.h -14305;0x37e1;DUMP_OK_STORE_DONE;INFO;P1: Start time as UNIX seconds. P2: End time as UNIX seconds.;mission/persistentTmStoreDefs.h -14306;0x37e2;DUMP_NOK_STORE_DONE;INFO;P1: Start time as UNIX seconds. P2: End time as UNIX seconds.;mission/persistentTmStoreDefs.h -14307;0x37e3;DUMP_MISC_STORE_DONE;INFO;P1: Start time as UNIX seconds. P2: End time as UNIX seconds.;mission/persistentTmStoreDefs.h -14308;0x37e4;DUMP_HK_STORE_DONE;INFO;P1: Start time as UNIX seconds. P2: End time as UNIX seconds.;mission/persistentTmStoreDefs.h -14309;0x37e5;DUMP_CFDP_STORE_DONE;INFO;P1: Start time as UNIX seconds. P2: End time as UNIX seconds.;mission/persistentTmStoreDefs.h +14305;0x37e1;DUMP_OK_STORE_DONE;INFO;P1: Number of dumped packets. P2: Total dumped bytes.;mission/persistentTmStoreDefs.h +14306;0x37e2;DUMP_NOK_STORE_DONE;INFO;P1: Number of dumped packets. P2: Total dumped bytes.;mission/persistentTmStoreDefs.h +14307;0x37e3;DUMP_MISC_STORE_DONE;INFO;P1: Number of dumped packets. P2: Total dumped bytes.;mission/persistentTmStoreDefs.h +14308;0x37e4;DUMP_HK_STORE_DONE;INFO;P1: Number of dumped packets. P2: Total dumped bytes.;mission/persistentTmStoreDefs.h +14309;0x37e5;DUMP_CFDP_STORE_DONE;INFO;P1: Number of dumped packets. P2: Total dumped bytes.;mission/persistentTmStoreDefs.h diff --git a/generators/bsp_hosted_returnvalues.csv b/generators/bsp_hosted_returnvalues.csv index 498fb417..50041e42 100644 --- a/generators/bsp_hosted_returnvalues.csv +++ b/generators/bsp_hosted_returnvalues.csv @@ -1,7 +1,10 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path 0x0000;OK;System-wide code for ok.;0;HasReturnvaluesIF;fsfw/returnvalues/returnvalue.h 0x0001;Failed;Unspecified system-wide code for failed.;1;HasReturnvaluesIF;fsfw/returnvalues/returnvalue.h -0x63a0;NVMB_KeyNotExists;Specified key does not exist in json file;160;NVM_PARAM_BASE;mission/memory/NvmParameterBase.h +0x7000;PTM_DumpDone;No description;0;PERSISTENT_TM_STORE;mission/tmtc/PersistentTmStore.h +0x7001;PTM_BusyDumping;No description;1;PERSISTENT_TM_STORE;mission/tmtc/PersistentTmStore.h +0x60a0;CCSDS_CommandNotImplemented;Received action message with unknown action id;160;CCSDS_HANDLER;mission/tmtc/CcsdsIpCoreHandler.h +0x7100;TMS_IsBusy;No description;0;TM_SINK;mission/tmtc/DirectTmSinkIF.h 0x5100;IMTQ_InvalidCommandCode;No description;0;IMTQ_HANDLER;mission/devices/devicedefinitions/imtqHelpers.h 0x5101;IMTQ_MgmMeasurementLowLevelError;No description;1;IMTQ_HANDLER;mission/devices/devicedefinitions/imtqHelpers.h 0x5102;IMTQ_ActuateCmdLowLevelError;No description;2;IMTQ_HANDLER;mission/devices/devicedefinitions/imtqHelpers.h @@ -22,12 +25,23 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path 0x52b7;RWHA_SpiReadTimeout;Timeout when reading reply;183;RW_HANDLER;mission/devices/devicedefinitions/rwHelpers.h 0x58a0;SUSS_ErrorUnlockMutex;No description;160;SUS_HANDLER;mission/devices/LegacySusHandler.h 0x58a1;SUSS_ErrorLockMutex;No description;161;SUS_HANDLER;mission/devices/LegacySusHandler.h -0x66a0;SADPL_InvalidSpeed;Action Message with invalid speed was received. Valid speeds must be in the range of [-65000, 1000] or [1000, 65000];160;SA_DEPL_HANDLER;mission/devices/RwHandler.h -0x66a1;SADPL_InvalidRampTime;Action Message with invalid ramp time was received.;161;SA_DEPL_HANDLER;mission/devices/RwHandler.h -0x66a2;SADPL_SetSpeedCommandInvalidLength;Received set speed command has invalid length. Should be 6.;162;SA_DEPL_HANDLER;mission/devices/RwHandler.h -0x66a3;SADPL_ExecutionFailed;Command execution failed;163;SA_DEPL_HANDLER;mission/devices/RwHandler.h -0x66a4;SADPL_CrcError;Reaction wheel reply has invalid crc;164;SA_DEPL_HANDLER;mission/devices/RwHandler.h -0x66a5;SADPL_ValueNotRead;No description;165;SA_DEPL_HANDLER;mission/devices/RwHandler.h +0x5d00;GOMS_PacketTooLong;No description;0;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h +0x5d01;GOMS_InvalidTableId;No description;1;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h +0x5d02;GOMS_InvalidAddress;No description;2;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h +0x5d03;GOMS_InvalidParamSize;No description;3;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h +0x5d04;GOMS_InvalidPayloadSize;No description;4;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h +0x5d05;GOMS_UnknownReplyId;No description;5;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h +0x5da0;GOMS_InvalidSpeed;Action Message with invalid speed was received. Valid speeds must be in the range of [-65000, 1000] or [1000, 65000];160;GOM_SPACE_HANDLER;mission/devices/RwHandler.h +0x5da1;GOMS_InvalidRampTime;Action Message with invalid ramp time was received.;161;GOM_SPACE_HANDLER;mission/devices/RwHandler.h +0x5da2;GOMS_SetSpeedCommandInvalidLength;Received set speed command has invalid length. Should be 6.;162;GOM_SPACE_HANDLER;mission/devices/RwHandler.h +0x5da3;GOMS_ExecutionFailed;Command execution failed;163;GOM_SPACE_HANDLER;mission/devices/RwHandler.h +0x5da4;GOMS_CrcError;Reaction wheel reply has invalid crc;164;GOM_SPACE_HANDLER;mission/devices/RwHandler.h +0x5da5;GOMS_ValueNotRead;No description;165;GOM_SPACE_HANDLER;mission/devices/RwHandler.h +0x4fa1;HEATER_CommandNotSupported;No description;161;HEATER_HANDLER;mission/devices/HeaterHandler.h +0x4fa2;HEATER_InitFailed;No description;162;HEATER_HANDLER;mission/devices/HeaterHandler.h +0x4fa3;HEATER_InvalidSwitchNr;No description;163;HEATER_HANDLER;mission/devices/HeaterHandler.h +0x4fa4;HEATER_MainSwitchSetTimeout;No description;164;HEATER_HANDLER;mission/devices/HeaterHandler.h +0x4fa5;HEATER_CommandAlreadyWaiting;No description;165;HEATER_HANDLER;mission/devices/HeaterHandler.h 0x50a0;SYRLINKS_CrcFailure;No description;160;SYRLINKS_HANDLER;mission/devices/SyrlinksHandler.h 0x50a1;SYRLINKS_UartFraminOrParityErrorAck;No description;161;SYRLINKS_HANDLER;mission/devices/SyrlinksHandler.h 0x50a2;SYRLINKS_BadCharacterAck;No description;162;SYRLINKS_HANDLER;mission/devices/SyrlinksHandler.h @@ -37,23 +51,13 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path 0x50a6;SYRLINKS_BadCrcAck;No description;166;SYRLINKS_HANDLER;mission/devices/SyrlinksHandler.h 0x50a7;SYRLINKS_ReplyWrongSize;No description;167;SYRLINKS_HANDLER;mission/devices/SyrlinksHandler.h 0x50a8;SYRLINKS_MissingStartFrameCharacter;No description;168;SYRLINKS_HANDLER;mission/devices/SyrlinksHandler.h -0x5d00;GOMS_PacketTooLong;No description;0;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h -0x5d01;GOMS_InvalidTableId;No description;1;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h -0x5d02;GOMS_InvalidAddress;No description;2;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h -0x5d03;GOMS_InvalidParamSize;No description;3;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h -0x5d04;GOMS_InvalidPayloadSize;No description;4;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h -0x5d05;GOMS_UnknownReplyId;No description;5;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h -0x4fa1;HEATER_CommandNotSupported;No description;161;HEATER_HANDLER;mission/devices/HeaterHandler.h -0x4fa2;HEATER_InitFailed;No description;162;HEATER_HANDLER;mission/devices/HeaterHandler.h -0x4fa3;HEATER_InvalidSwitchNr;No description;163;HEATER_HANDLER;mission/devices/HeaterHandler.h -0x4fa4;HEATER_MainSwitchSetTimeout;No description;164;HEATER_HANDLER;mission/devices/HeaterHandler.h -0x4fa5;HEATER_CommandAlreadyWaiting;No description;165;HEATER_HANDLER;mission/devices/HeaterHandler.h -0x60a0;CCSDS_CommandNotImplemented;Received action message with unknown action id;160;CCSDS_HANDLER;mission/tmtc/CcsdsIpCoreHandler.h -0x7100;TMS_IsBusy;No description;0;TM_SINK;mission/tmtc/DirectTmSinkIF.h -0x7000;PTM_DumpDone;No description;0;PERSISTENT_TM_STORE;mission/tmtc/PersistentTmStore.h -0x7001;PTM_BusyDumping;No description;1;PERSISTENT_TM_STORE;mission/tmtc/PersistentTmStore.h -0x6b01;ACSSAF_SafectrlMekfInputInvalid;No description;1;ACS_SAFE;mission/controller/acs/control/SafeCtrl.h +0x66a0;SADPL_CommandNotSupported;No description;160;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h +0x66a1;SADPL_DeploymentAlreadyExecuting;No description;161;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h +0x66a2;SADPL_MainSwitchTimeoutFailure;No description;162;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h +0x66a3;SADPL_SwitchingDeplSa1Failed;No description;163;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h +0x66a4;SADPL_SwitchingDeplSa2Failed;No description;164;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h 0x6c01;ACSPTG_PtgctrlMekfInputInvalid;No description;1;ACS_PTG;mission/controller/acs/control/PtgCtrl.h +0x6b01;ACSSAF_SafectrlMekfInputInvalid;No description;1;ACS_SAFE;mission/controller/acs/control/SafeCtrl.h 0x6d01;ACSDTB_DetumbleNoSensordata;No description;1;ACS_DETUMBLE;mission/controller/acs/control/Detumble.h 0x6a02;ACSMEKF_MekfUninitialized;No description;2;ACS_MEKF;mission/controller/acs/MultiplicativeKalmanFilter.h 0x6a03;ACSMEKF_MekfNoGyrData;No description;3;ACS_MEKF;mission/controller/acs/MultiplicativeKalmanFilter.h @@ -63,105 +67,125 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path 0x6a07;ACSMEKF_MekfInitialized;No description;7;ACS_MEKF;mission/controller/acs/MultiplicativeKalmanFilter.h 0x6a08;ACSMEKF_MekfRunning;No description;8;ACS_MEKF;mission/controller/acs/MultiplicativeKalmanFilter.h 0x6900;ACSCTRL_FileDeletionFailed;No description;0;ACS_CTRL;mission/controller/AcsController.h -0x4500;HSPI_OpeningFileFailed;No description;0;HAL_SPI;fsfw/src/fsfw_hal/linux/spi/SpiComIF.h -0x4501;HSPI_FullDuplexTransferFailed;No description;1;HAL_SPI;fsfw/src/fsfw_hal/linux/spi/SpiComIF.h -0x4502;HSPI_HalfDuplexTransferFailed;No description;2;HAL_SPI;fsfw/src/fsfw_hal/linux/spi/SpiComIF.h -0x4801;HGIO_UnknownGpioId;No description;1;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h -0x4802;HGIO_DriveGpioFailure;No description;2;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h -0x4803;HGIO_GpioTypeFailure;No description;3;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h -0x4804;HGIO_GpioInvalidInstance;No description;4;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h -0x4805;HGIO_GpioDuplicateDetected;No description;5;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h -0x4806;HGIO_GpioInitFailed;No description;6;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h -0x4807;HGIO_GpioGetValueFailed;No description;7;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h -0x4601;HURT_UartReadFailure;No description;1;HAL_UART;fsfw/src/fsfw_hal/linux/serial/SerialComIF.h -0x4602;HURT_UartReadSizeMissmatch;No description;2;HAL_UART;fsfw/src/fsfw_hal/linux/serial/SerialComIF.h -0x4603;HURT_UartRxBufferTooSmall;No description;3;HAL_UART;fsfw/src/fsfw_hal/linux/serial/SerialComIF.h -0x4400;UXOS_ExecutionFinished;Execution of the current command has finished;0;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h -0x4401;UXOS_CommandPending;Command is pending. This will also be returned if the user tries to load another command but a command is still pending;1;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h -0x4402;UXOS_BytesRead;Some bytes have been read from the executing process;2;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h -0x4403;UXOS_CommandError;Command execution failed;3;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h -0x4404;UXOS_NoCommandLoadedOrPending;;4;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h -0x4406;UXOS_PcloseCallError;No description;6;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h -0x2801;SM_DataTooLarge;No description;1;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h -0x2802;SM_DataStorageFull;No description;2;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h -0x2803;SM_IllegalStorageId;No description;3;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h -0x2804;SM_DataDoesNotExist;No description;4;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h -0x2805;SM_IllegalAddress;No description;5;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h -0x2806;SM_PoolTooLarge;No description;6;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h -0x0601;PP_DoItMyself;No description;1;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h -0x0602;PP_PointsToVariable;No description;2;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h -0x0603;PP_PointsToMemory;No description;3;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h -0x0604;PP_ActivityCompleted;No description;4;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h -0x0605;PP_PointsToVectorUint8;No description;5;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h -0x0606;PP_PointsToVectorUint16;No description;6;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h -0x0607;PP_PointsToVectorUint32;No description;7;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h -0x0608;PP_PointsToVectorFloat;No description;8;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h -0x06a0;PP_DumpNotSupported;No description;160;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h -0x06e0;PP_InvalidSize;No description;224;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h -0x06e1;PP_InvalidAddress;No description;225;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h -0x06e2;PP_InvalidContent;No description;226;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h -0x06e3;PP_UnalignedAccess;No description;227;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h -0x06e4;PP_WriteProtected;No description;228;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h -0x13e0;MH_UnknownCmd;No description;224;MEMORY_HELPER;fsfw/src/fsfw/memory/MemoryHelper.h -0x13e1;MH_InvalidAddress;No description;225;MEMORY_HELPER;fsfw/src/fsfw/memory/MemoryHelper.h -0x13e2;MH_InvalidSize;No description;226;MEMORY_HELPER;fsfw/src/fsfw/memory/MemoryHelper.h -0x13e3;MH_StateMismatch;No description;227;MEMORY_HELPER;fsfw/src/fsfw/memory/MemoryHelper.h -0x38a1;SGP4_InvalidEccentricity;No description;161;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h -0x38a2;SGP4_InvalidMeanMotion;No description;162;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h -0x38a3;SGP4_InvalidPerturbationElements;No description;163;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h -0x38a4;SGP4_InvalidSemiLatusRectum;No description;164;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h -0x38a5;SGP4_InvalidEpochElements;No description;165;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h -0x38a6;SGP4_SatelliteHasDecayed;No description;166;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h -0x38b1;SGP4_TleTooOld;No description;177;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h -0x38b2;SGP4_TleNotInitialized;No description;178;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h -0x1801;FF_Full;No description;1;FIFO_CLASS;fsfw/src/fsfw/container/FIFOBase.h -0x1802;FF_Empty;No description;2;FIFO_CLASS;fsfw/src/fsfw/container/FIFOBase.h -0x1601;FMM_MapFull;No description;1;FIXED_MULTIMAP;fsfw/src/fsfw/container/FixedOrderedMultimap.h -0x1602;FMM_KeyDoesNotExist;No description;2;FIXED_MULTIMAP;fsfw/src/fsfw/container/FixedOrderedMultimap.h -0x3901;MUX_NotEnoughResources;No description;1;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h -0x3902;MUX_InsufficientMemory;No description;2;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h -0x3903;MUX_NoPrivilege;No description;3;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h -0x3904;MUX_WrongAttributeSetting;No description;4;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h -0x3905;MUX_MutexAlreadyLocked;No description;5;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h -0x3906;MUX_MutexNotFound;No description;6;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h -0x3907;MUX_MutexMaxLocks;No description;7;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h -0x3908;MUX_CurrThreadAlreadyOwnsMutex;No description;8;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h -0x3909;MUX_CurrThreadDoesNotOwnMutex;No description;9;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h -0x390a;MUX_MutexTimeout;No description;10;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h -0x390b;MUX_MutexInvalidId;No description;11;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h -0x390c;MUX_MutexDestroyedWhileWaiting;No description;12;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h -0x3a01;MQI_Empty;No description;1;MESSAGE_QUEUE_IF;fsfw/src/fsfw/ipc/MessageQueueIF.h -0x3a02;MQI_Full;No space left for more messages;2;MESSAGE_QUEUE_IF;fsfw/src/fsfw/ipc/MessageQueueIF.h -0x3a03;MQI_NoReplyPartner;Returned if a reply method was called without partner;3;MESSAGE_QUEUE_IF;fsfw/src/fsfw/ipc/MessageQueueIF.h -0x3a04;MQI_DestinationInvalid;Returned if the target destination is invalid.;4;MESSAGE_QUEUE_IF;fsfw/src/fsfw/ipc/MessageQueueIF.h -0x0f01;CM_UnknownCommand;No description;1;COMMAND_MESSAGE;fsfw/src/fsfw/ipc/CommandMessageIF.h +0x63a0;NVMB_KeyNotExists;Specified key does not exist in json file;160;NVM_PARAM_BASE;mission/memory/NvmParameterBase.h +0x2c01;CCS_BcIsSetVrCommand;No description;1;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2c02;CCS_BcIsUnlockCommand;No description;2;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2cb0;CCS_BcIllegalCommand;No description;176;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2cb1;CCS_BoardReadingNotFinished;No description;177;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2cf0;CCS_NsPositiveW;No description;240;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2cf1;CCS_NsNegativeW;No description;241;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2cf2;CCS_NsLockout;No description;242;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2cf3;CCS_FarmInLockout;No description;243;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2cf4;CCS_FarmInWait;No description;244;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2ce0;CCS_WrongSymbol;No description;224;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2ce1;CCS_DoubleStart;No description;225;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2ce2;CCS_StartSymbolMissed;No description;226;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2ce3;CCS_EndWithoutStart;No description;227;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2ce4;CCS_TooLarge;No description;228;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2ce5;CCS_TooShort;No description;229;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2ce6;CCS_WrongTfVersion;No description;230;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2ce7;CCS_WrongSpacecraftId;No description;231;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2ce8;CCS_NoValidFrameType;No description;232;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2ce9;CCS_CrcFailed;No description;233;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2cea;CCS_VcNotFound;No description;234;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2ceb;CCS_ForwardingFailed;No description;235;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2cec;CCS_ContentTooLarge;No description;236;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2ced;CCS_ResidualData;No description;237;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2cee;CCS_DataCorrupted;No description;238;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2cef;CCS_IllegalSegmentationFlag;No description;239;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2cd0;CCS_IllegalFlagCombination;No description;208;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2cd1;CCS_ShorterThanHeader;No description;209;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2cd2;CCS_TooShortBlockedPacket;No description;210;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2cd3;CCS_TooShortMapExtraction;No description;211;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x3b00;SPH_ConnBroken;No description;0;SEMAPHORE_IF;fsfw/src/fsfw/osal/common/TcpTmTcServer.h +0x2a01;IEC_NoConfigurationTable;No description;1;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a02;IEC_NoCpuTable;No description;2;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a03;IEC_InvalidWorkspaceAddress;No description;3;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a04;IEC_TooLittleWorkspace;No description;4;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a05;IEC_WorkspaceAllocation;No description;5;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a06;IEC_InterruptStackTooSmall;No description;6;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a07;IEC_ThreadExitted;No description;7;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a08;IEC_InconsistentMpInformation;No description;8;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a09;IEC_InvalidNode;No description;9;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a0a;IEC_NoMpci;No description;10;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a0b;IEC_BadPacket;No description;11;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a0c;IEC_OutOfPackets;No description;12;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a0d;IEC_OutOfGlobalObjects;No description;13;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a0e;IEC_OutOfProxies;No description;14;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a0f;IEC_InvalidGlobalId;No description;15;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a10;IEC_BadStackHook;No description;16;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a11;IEC_BadAttributes;No description;17;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a12;IEC_ImplementationKeyCreateInconsistency;No description;18;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a13;IEC_ImplementationBlockingOperationCancel;No description;19;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a14;IEC_MutexObtainFromBadState;No description;20;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a15;IEC_UnlimitedAndMaximumIs0;No description;21;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h 0x0e01;HM_InvalidMode;No description;1;HAS_MODES_IF;fsfw/src/fsfw/modes/HasModesIF.h 0x0e02;HM_TransNotAllowed;No description;2;HAS_MODES_IF;fsfw/src/fsfw/modes/HasModesIF.h 0x0e03;HM_InTransition;No description;3;HAS_MODES_IF;fsfw/src/fsfw/modes/HasModesIF.h 0x0e04;HM_InvalidSubmode;No description;4;HAS_MODES_IF;fsfw/src/fsfw/modes/HasModesIF.h -0x0c02;MS_InvalidEntry;No description;2;MODE_STORE_IF;fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h -0x0c03;MS_TooManyElements;No description;3;MODE_STORE_IF;fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h -0x0c04;MS_CantStoreEmpty;No description;4;MODE_STORE_IF;fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h -0x0b01;SB_ChildNotFound;No description;1;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h -0x0b02;SB_ChildInfoUpdated;No description;2;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h -0x0b03;SB_ChildDoesntHaveModes;No description;3;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h -0x0b04;SB_CouldNotInsertChild;No description;4;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h -0x0b05;SB_TableContainsInvalidObjectId;No description;5;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h -0x0d01;SS_SequenceAlreadyExists;No description;1;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h -0x0d02;SS_TableAlreadyExists;No description;2;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h -0x0d03;SS_TableDoesNotExist;No description;3;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h -0x0d04;SS_TableOrSequenceLengthInvalid;No description;4;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h -0x0d05;SS_SequenceDoesNotExist;No description;5;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h -0x0d06;SS_TableContainsInvalidObjectId;No description;6;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h -0x0d07;SS_FallbackSequenceDoesNotExist;No description;7;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h -0x0d08;SS_NoTargetTable;No description;8;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h -0x0d09;SS_SequenceOrTableTooLong;No description;9;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h -0x0d0b;SS_IsFallbackSequence;No description;11;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h -0x0d0c;SS_AccessDenied;No description;12;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h -0x0d0e;SS_TableInUse;No description;14;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h -0x0da1;SS_TargetTableNotReached;No description;161;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h -0x0da2;SS_TableCheckFailed;No description;162;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h -0x2501;EV_ListenerNotFound;No description;1;EVENT_MANAGER_IF;fsfw/src/fsfw/events/EventManagerIF.h +0x2e01;HPA_InvalidIdentifierId;No description;1;HAS_PARAMETERS_IF;fsfw/src/fsfw/parameters/HasParametersIF.h +0x2e02;HPA_InvalidDomainId;No description;2;HAS_PARAMETERS_IF;fsfw/src/fsfw/parameters/HasParametersIF.h +0x2e03;HPA_InvalidValue;No description;3;HAS_PARAMETERS_IF;fsfw/src/fsfw/parameters/HasParametersIF.h +0x2e05;HPA_ReadOnly;No description;5;HAS_PARAMETERS_IF;fsfw/src/fsfw/parameters/HasParametersIF.h +0x2d01;PAW_UnknownDatatype;No description;1;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h +0x2d02;PAW_DatatypeMissmatch;No description;2;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h +0x2d03;PAW_Readonly;No description;3;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h +0x2d04;PAW_TooBig;No description;4;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h +0x2d05;PAW_SourceNotSet;No description;5;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h +0x2d06;PAW_OutOfBounds;No description;6;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h +0x2d07;PAW_NotSet;No description;7;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h +0x2d08;PAW_ColumnOrRowsZero;No description;8;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h +0x3201;CF_ObjectHasNoFunctions;No description;1;COMMANDS_ACTIONS_IF;fsfw/src/fsfw/action/CommandsActionsIF.h +0x3202;CF_AlreadyCommanding;No description;2;COMMANDS_ACTIONS_IF;fsfw/src/fsfw/action/CommandsActionsIF.h +0x3301;HF_IsBusy;No description;1;HAS_ACTIONS_IF;fsfw/src/fsfw/action/HasActionsIF.h +0x3302;HF_InvalidParameters;No description;2;HAS_ACTIONS_IF;fsfw/src/fsfw/action/HasActionsIF.h +0x3303;HF_ExecutionFinished;No description;3;HAS_ACTIONS_IF;fsfw/src/fsfw/action/HasActionsIF.h +0x3304;HF_InvalidActionId;No description;4;HAS_ACTIONS_IF;fsfw/src/fsfw/action/HasActionsIF.h +0x0201;OM_InsertionFailed;No description;1;OBJECT_MANAGER_IF;fsfw/src/fsfw/objectmanager/ObjectManagerIF.h +0x0202;OM_NotFound;No description;2;OBJECT_MANAGER_IF;fsfw/src/fsfw/objectmanager/ObjectManagerIF.h +0x0203;OM_ChildInitFailed;No description;3;OBJECT_MANAGER_IF;fsfw/src/fsfw/objectmanager/ObjectManagerIF.h +0x0204;OM_InternalErrReporterUninit;No description;4;OBJECT_MANAGER_IF;fsfw/src/fsfw/objectmanager/ObjectManagerIF.h +0x2600;FDI_YourFault;No description;0;HANDLES_FAILURES_IF;fsfw/src/fsfw/fdir/ConfirmsFailuresIF.h +0x2601;FDI_MyFault;No description;1;HANDLES_FAILURES_IF;fsfw/src/fsfw/fdir/ConfirmsFailuresIF.h +0x2602;FDI_ConfirmLater;No description;2;HANDLES_FAILURES_IF;fsfw/src/fsfw/fdir/ConfirmsFailuresIF.h +0x2201;TMF_Busy;No description;1;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h +0x2202;TMF_LastPacketFound;No description;2;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h +0x2203;TMF_StopFetch;No description;3;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h +0x2204;TMF_Timeout;No description;4;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h +0x2205;TMF_TmChannelFull;No description;5;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h +0x2206;TMF_NotStored;No description;6;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h +0x2207;TMF_AllDeleted;No description;7;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h +0x2208;TMF_InvalidData;No description;8;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h +0x2209;TMF_NotReady;No description;9;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h +0x2101;TMB_Busy;No description;1;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x2102;TMB_Full;No description;2;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x2103;TMB_Empty;No description;3;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x2104;TMB_NullRequested;No description;4;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x2105;TMB_TooLarge;No description;5;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x2106;TMB_NotReady;No description;6;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x2107;TMB_DumpError;No description;7;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x2108;TMB_CrcError;No description;8;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x2109;TMB_Timeout;No description;9;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x210a;TMB_IdlePacketFound;No description;10;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x210b;TMB_TelecommandFound;No description;11;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x210c;TMB_NoPusATm;No description;12;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x210d;TMB_TooSmall;No description;13;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x210e;TMB_BlockNotFound;No description;14;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x210f;TMB_InvalidRequest;No description;15;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x1c01;TCD_PacketLost;No description;1;PACKET_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/TcDistributorBase.h +0x1c02;TCD_DestinationNotFound;No description;2;PACKET_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/TcDistributorBase.h +0x1c03;TCD_ServiceIdAlreadyExists;No description;3;PACKET_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/TcDistributorBase.h +0x1b00;TCC_NoDestinationFound;No description;0;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b01;TCC_InvalidCcsdsVersion;No description;1;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b02;TCC_InvalidApid;No description;2;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b03;TCC_InvalidPacketType;No description;3;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b04;TCC_InvalidSecHeaderField;No description;4;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b05;TCC_IncorrectPrimaryHeader;No description;5;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b07;TCC_IncompletePacket;No description;7;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b08;TCC_InvalidPusVersion;No description;8;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b09;TCC_IncorrectChecksum;No description;9;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b0a;TCC_IllegalPacketSubtype;No description;10;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b0b;TCC_IncorrectSecondaryHeader;No description;11;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h 0x04e1;RMP_CommandNoDescriptorsAvailable;No description;225;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h 0x04e2;RMP_CommandBufferFull;No description;226;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h 0x04e3;RMP_CommandChannelOutOfRange;No description;227;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h @@ -202,9 +226,95 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path 0x040a;RMP_ReplyCommandNotImplementedOrNotAuthorised;No description;10;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h 0x040b;RMP_ReplyRmwDataLengthError;No description;11;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h 0x040c;RMP_ReplyInvalidTargetLogicalAddress;No description;12;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h -0x1401;SE_BufferTooShort;No description;1;SERIALIZE_IF;fsfw/src/fsfw/serialize/SerializeIF.h -0x1402;SE_StreamTooShort;No description;2;SERIALIZE_IF;fsfw/src/fsfw/serialize/SerializeIF.h -0x1403;SE_TooManyElements;No description;3;SERIALIZE_IF;fsfw/src/fsfw/serialize/SerializeIF.h +0x2801;SM_DataTooLarge;No description;1;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h +0x2802;SM_DataStorageFull;No description;2;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h +0x2803;SM_IllegalStorageId;No description;3;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h +0x2804;SM_DataDoesNotExist;No description;4;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h +0x2805;SM_IllegalAddress;No description;5;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h +0x2806;SM_PoolTooLarge;No description;6;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h +0x38a1;SGP4_InvalidEccentricity;No description;161;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h +0x38a2;SGP4_InvalidMeanMotion;No description;162;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h +0x38a3;SGP4_InvalidPerturbationElements;No description;163;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h +0x38a4;SGP4_InvalidSemiLatusRectum;No description;164;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h +0x38a5;SGP4_InvalidEpochElements;No description;165;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h +0x38a6;SGP4_SatelliteHasDecayed;No description;166;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h +0x38b1;SGP4_TleTooOld;No description;177;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h +0x38b2;SGP4_TleNotInitialized;No description;178;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h +0x2401;MT_NoPacketFound;No description;1;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/DleParser.h +0x2402;MT_PossiblePacketLoss;No description;2;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/DleParser.h +0x2403;MT_NoMatch;No description;3;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h +0x2404;MT_Full;No description;4;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h +0x2405;MT_NewNodeCreated;No description;5;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h +0x3f01;DLEE_StreamTooShort;No description;1;DLE_ENCODER;fsfw/src/fsfw/globalfunctions/DleEncoder.h +0x3f02;DLEE_DecodingError;No description;2;DLE_ENCODER;fsfw/src/fsfw/globalfunctions/DleEncoder.h +0x2f01;ASC_TooLongForTargetType;No description;1;ASCII_CONVERTER;fsfw/src/fsfw/globalfunctions/AsciiConverter.h +0x2f02;ASC_InvalidCharacters;No description;2;ASCII_CONVERTER;fsfw/src/fsfw/globalfunctions/AsciiConverter.h +0x2f03;ASC_BufferTooSmall;No description;3;ASCII_CONVERTER;fsfw/src/fsfw/globalfunctions/AsciiConverter.h +0x0f01;CM_UnknownCommand;No description;1;COMMAND_MESSAGE;fsfw/src/fsfw/ipc/CommandMessageIF.h +0x3a01;MQI_Empty;No description;1;MESSAGE_QUEUE_IF;fsfw/src/fsfw/ipc/MessageQueueIF.h +0x3a02;MQI_Full;No space left for more messages;2;MESSAGE_QUEUE_IF;fsfw/src/fsfw/ipc/MessageQueueIF.h +0x3a03;MQI_NoReplyPartner;Returned if a reply method was called without partner;3;MESSAGE_QUEUE_IF;fsfw/src/fsfw/ipc/MessageQueueIF.h +0x3a04;MQI_DestinationInvalid;Returned if the target destination is invalid.;4;MESSAGE_QUEUE_IF;fsfw/src/fsfw/ipc/MessageQueueIF.h +0x3901;MUX_NotEnoughResources;No description;1;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h +0x3902;MUX_InsufficientMemory;No description;2;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h +0x3903;MUX_NoPrivilege;No description;3;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h +0x3904;MUX_WrongAttributeSetting;No description;4;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h +0x3905;MUX_MutexAlreadyLocked;No description;5;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h +0x3906;MUX_MutexNotFound;No description;6;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h +0x3907;MUX_MutexMaxLocks;No description;7;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h +0x3908;MUX_CurrThreadAlreadyOwnsMutex;No description;8;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h +0x3909;MUX_CurrThreadDoesNotOwnMutex;No description;9;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h +0x390a;MUX_MutexTimeout;No description;10;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h +0x390b;MUX_MutexInvalidId;No description;11;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h +0x390c;MUX_MutexDestroyedWhileWaiting;No description;12;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h +0x3b01;SPH_SemaphoreTimeout;No description;1;SEMAPHORE_IF;fsfw/src/fsfw/tasks/SemaphoreIF.h +0x3b02;SPH_SemaphoreNotOwned;No description;2;SEMAPHORE_IF;fsfw/src/fsfw/tasks/SemaphoreIF.h +0x3b03;SPH_SemaphoreInvalid;No description;3;SEMAPHORE_IF;fsfw/src/fsfw/tasks/SemaphoreIF.h +0x1e00;PUS_InvalidPusVersion;No description;0;PUS_IF;fsfw/src/fsfw/tmtcpacket/pus/PusIF.h +0x1e01;PUS_InvalidCrc16;No description;1;PUS_IF;fsfw/src/fsfw/tmtcpacket/pus/PusIF.h +0x3601;CFDP_InvalidTlvType;No description;1;CFDP;fsfw/src/fsfw/cfdp/definitions.h +0x3602;CFDP_InvalidDirectiveField;No description;2;CFDP;fsfw/src/fsfw/cfdp/definitions.h +0x3603;CFDP_InvalidPduDatafieldLen;No description;3;CFDP;fsfw/src/fsfw/cfdp/definitions.h +0x3604;CFDP_InvalidAckDirectiveFields;No description;4;CFDP;fsfw/src/fsfw/cfdp/definitions.h +0x3605;CFDP_MetadataCantParseOptions;No description;5;CFDP;fsfw/src/fsfw/cfdp/definitions.h +0x3606;CFDP_NakCantParseOptions;No description;6;CFDP;fsfw/src/fsfw/cfdp/definitions.h +0x3607;CFDP_FinishedCantParseFsResponses;No description;7;CFDP;fsfw/src/fsfw/cfdp/definitions.h +0x3608;CFDP_FilestoreRequiresSecondFile;No description;8;CFDP;fsfw/src/fsfw/cfdp/definitions.h +0x3609;CFDP_FilestoreResponseCantParseFsMessage;No description;9;CFDP;fsfw/src/fsfw/cfdp/definitions.h +0x360a;CFDP_InvalidPduFormat;No description;10;CFDP;fsfw/src/fsfw/cfdp/definitions.h +0x2901;TC_InvalidTargetState;No description;1;THERMAL_COMPONENT_IF;fsfw/src/fsfw/thermal/ThermalComponentIF.h +0x29f1;TC_AboveOperationalLimit;No description;241;THERMAL_COMPONENT_IF;fsfw/src/fsfw/thermal/ThermalComponentIF.h +0x29f2;TC_BelowOperationalLimit;No description;242;THERMAL_COMPONENT_IF;fsfw/src/fsfw/thermal/ThermalComponentIF.h +0x0c02;MS_InvalidEntry;No description;2;MODE_STORE_IF;fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h +0x0c03;MS_TooManyElements;No description;3;MODE_STORE_IF;fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h +0x0c04;MS_CantStoreEmpty;No description;4;MODE_STORE_IF;fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h +0x0d01;SS_SequenceAlreadyExists;No description;1;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0d02;SS_TableAlreadyExists;No description;2;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0d03;SS_TableDoesNotExist;No description;3;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0d04;SS_TableOrSequenceLengthInvalid;No description;4;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0d05;SS_SequenceDoesNotExist;No description;5;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0d06;SS_TableContainsInvalidObjectId;No description;6;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0d07;SS_FallbackSequenceDoesNotExist;No description;7;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0d08;SS_NoTargetTable;No description;8;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0d09;SS_SequenceOrTableTooLong;No description;9;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0d0b;SS_IsFallbackSequence;No description;11;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0d0c;SS_AccessDenied;No description;12;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0d0e;SS_TableInUse;No description;14;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0da1;SS_TargetTableNotReached;No description;161;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0da2;SS_TableCheckFailed;No description;162;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0b01;SB_ChildNotFound;No description;1;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h +0x0b02;SB_ChildInfoUpdated;No description;2;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h +0x0b03;SB_ChildDoesntHaveModes;No description;3;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h +0x0b04;SB_CouldNotInsertChild;No description;4;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h +0x0b05;SB_TableContainsInvalidObjectId;No description;5;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h +0x3e00;HKM_QueueOrDestinationInvalid;No description;0;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h +0x3e01;HKM_WrongHkPacketType;No description;1;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h +0x3e02;HKM_ReportingStatusUnchanged;No description;2;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h +0x3e03;HKM_PeriodicHelperInvalid;No description;3;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h +0x3e04;HKM_PoolobjectNotFound;No description;4;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h +0x3e05;HKM_DatasetNotFound;No description;5;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h +0x3c00;LPIF_PoolEntryNotFound;No description;0;LOCAL_POOL_OWNER_IF;fsfw/src/fsfw/datapoollocal/localPoolDefinitions.h +0x3c01;LPIF_PoolEntryTypeConflict;No description;1;LOCAL_POOL_OWNER_IF;fsfw/src/fsfw/datapoollocal/localPoolDefinitions.h 0x3da0;PVA_InvalidReadWriteMode;No description;160;POOL_VARIABLE_IF;fsfw/src/fsfw/datapool/PoolVariableIF.h 0x3da1;PVA_InvalidPoolEntry;No description;161;POOL_VARIABLE_IF;fsfw/src/fsfw/datapool/PoolVariableIF.h 0x0801;DPS_InvalidParameterDefinition;No description;1;DATA_SET_CLASS;fsfw/src/fsfw/datapool/DataSetIF.h @@ -213,20 +323,35 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path 0x0804;DPS_DataSetUninitialised;No description;4;DATA_SET_CLASS;fsfw/src/fsfw/datapool/DataSetIF.h 0x0805;DPS_DataSetFull;No description;5;DATA_SET_CLASS;fsfw/src/fsfw/datapool/DataSetIF.h 0x0806;DPS_PoolVarNull;No description;6;DATA_SET_CLASS;fsfw/src/fsfw/datapool/DataSetIF.h -0x1c01;TCD_PacketLost;No description;1;PACKET_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/TcDistributorBase.h -0x1c02;TCD_DestinationNotFound;No description;2;PACKET_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/TcDistributorBase.h -0x1c03;TCD_ServiceIdAlreadyExists;No description;3;PACKET_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/TcDistributorBase.h -0x1b00;TCC_NoDestinationFound;No description;0;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h -0x1b01;TCC_InvalidCcsdsVersion;No description;1;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h -0x1b02;TCC_InvalidApid;No description;2;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h -0x1b03;TCC_InvalidPacketType;No description;3;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h -0x1b04;TCC_InvalidSecHeaderField;No description;4;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h -0x1b05;TCC_IncorrectPrimaryHeader;No description;5;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h -0x1b07;TCC_IncompletePacket;No description;7;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h -0x1b08;TCC_InvalidPusVersion;No description;8;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h -0x1b09;TCC_IncorrectChecksum;No description;9;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h -0x1b0a;TCC_IllegalPacketSubtype;No description;10;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h -0x1b0b;TCC_IncorrectSecondaryHeader;No description;11;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h +0x1000;TIM_UnsupportedTimeFormat;No description;0;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h +0x1001;TIM_NotEnoughInformationForTargetFormat;No description;1;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h +0x1002;TIM_LengthMismatch;No description;2;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h +0x1003;TIM_InvalidTimeFormat;No description;3;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h +0x1004;TIM_InvalidDayOfYear;No description;4;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h +0x1005;TIM_TimeDoesNotFitFormat;No description;5;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h +0x3701;TSI_BadTimestamp;No description;1;TIME_STAMPER_IF;fsfw/src/fsfw/timemanager/TimeStampIF.h +0x1d01;ATC_ActivityStarted;No description;1;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h +0x1d02;ATC_InvalidSubservice;No description;2;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h +0x1d03;ATC_IllegalApplicationData;No description;3;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h +0x1d04;ATC_SendTmFailed;No description;4;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h +0x1d05;ATC_Timeout;No description;5;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h +0x4c00;SPPA_NoPacketFound;No description;0;SPACE_PACKET_PARSER;fsfw/src/fsfw/tmtcservices/SpacePacketParser.h +0x4c01;SPPA_SplitPacket;No description;1;SPACE_PACKET_PARSER;fsfw/src/fsfw/tmtcservices/SpacePacketParser.h +0x2001;CSB_ExecutionComplete;No description;1;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h +0x2002;CSB_NoStepMessage;No description;2;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h +0x2003;CSB_ObjectBusy;No description;3;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h +0x2004;CSB_Busy;No description;4;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h +0x2005;CSB_InvalidTc;No description;5;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h +0x2006;CSB_InvalidObject;No description;6;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h +0x2007;CSB_InvalidReply;No description;7;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h +0x1801;FF_Full;No description;1;FIFO_CLASS;fsfw/src/fsfw/container/FIFOBase.h +0x1802;FF_Empty;No description;2;FIFO_CLASS;fsfw/src/fsfw/container/FIFOBase.h +0x1601;FMM_MapFull;No description;1;FIXED_MULTIMAP;fsfw/src/fsfw/container/FixedOrderedMultimap.h +0x1602;FMM_KeyDoesNotExist;No description;2;FIXED_MULTIMAP;fsfw/src/fsfw/container/FixedOrderedMultimap.h +0x2501;EV_ListenerNotFound;No description;1;EVENT_MANAGER_IF;fsfw/src/fsfw/events/EventManagerIF.h +0x1701;HHI_ObjectNotHealthy;No description;1;HAS_HEALTH_IF;fsfw/src/fsfw/health/HasHealthIF.h +0x1702;HHI_InvalidHealthState;No description;2;HAS_HEALTH_IF;fsfw/src/fsfw/health/HasHealthIF.h +0x1703;HHI_IsExternallyControlled;No description;3;HAS_HEALTH_IF;fsfw/src/fsfw/health/HasHealthIF.h 0x3001;POS_InPowerTransition;No description;1;POWER_SWITCHER;fsfw/src/fsfw/power/PowerSwitcher.h 0x3002;POS_SwitchStateMismatch;No description;2;POWER_SWITCHER;fsfw/src/fsfw/power/PowerSwitcher.h 0x0501;PS_SwitchOn;No description;1;POWER_SWITCH_IF;fsfw/src/fsfw/power/PowerSwitchIF.h @@ -234,76 +359,23 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path 0x0502;PS_SwitchTimeout;No description;2;POWER_SWITCH_IF;fsfw/src/fsfw/power/PowerSwitchIF.h 0x0503;PS_FuseOn;No description;3;POWER_SWITCH_IF;fsfw/src/fsfw/power/PowerSwitchIF.h 0x0504;PS_FuseOff;No description;4;POWER_SWITCH_IF;fsfw/src/fsfw/power/PowerSwitchIF.h -0x3b00;SPH_ConnBroken;No description;0;SEMAPHORE_IF;fsfw/src/fsfw/osal/common/TcpTmTcServer.h -0x2a01;IEC_NoConfigurationTable;No description;1;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a02;IEC_NoCpuTable;No description;2;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a03;IEC_InvalidWorkspaceAddress;No description;3;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a04;IEC_TooLittleWorkspace;No description;4;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a05;IEC_WorkspaceAllocation;No description;5;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a06;IEC_InterruptStackTooSmall;No description;6;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a07;IEC_ThreadExitted;No description;7;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a08;IEC_InconsistentMpInformation;No description;8;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a09;IEC_InvalidNode;No description;9;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a0a;IEC_NoMpci;No description;10;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a0b;IEC_BadPacket;No description;11;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a0c;IEC_OutOfPackets;No description;12;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a0d;IEC_OutOfGlobalObjects;No description;13;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a0e;IEC_OutOfProxies;No description;14;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a0f;IEC_InvalidGlobalId;No description;15;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a10;IEC_BadStackHook;No description;16;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a11;IEC_BadAttributes;No description;17;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a12;IEC_ImplementationKeyCreateInconsistency;No description;18;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a13;IEC_ImplementationBlockingOperationCancel;No description;19;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a14;IEC_MutexObtainFromBadState;No description;20;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a15;IEC_UnlimitedAndMaximumIs0;No description;21;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2600;FDI_YourFault;No description;0;HANDLES_FAILURES_IF;fsfw/src/fsfw/fdir/ConfirmsFailuresIF.h -0x2601;FDI_MyFault;No description;1;HANDLES_FAILURES_IF;fsfw/src/fsfw/fdir/ConfirmsFailuresIF.h -0x2602;FDI_ConfirmLater;No description;2;HANDLES_FAILURES_IF;fsfw/src/fsfw/fdir/ConfirmsFailuresIF.h -0x1e00;PUS_InvalidPusVersion;No description;0;PUS_IF;fsfw/src/fsfw/tmtcpacket/pus/PusIF.h -0x1e01;PUS_InvalidCrc16;No description;1;PUS_IF;fsfw/src/fsfw/tmtcpacket/pus/PusIF.h -0x0201;OM_InsertionFailed;No description;1;OBJECT_MANAGER_IF;fsfw/src/fsfw/objectmanager/ObjectManagerIF.h -0x0202;OM_NotFound;No description;2;OBJECT_MANAGER_IF;fsfw/src/fsfw/objectmanager/ObjectManagerIF.h -0x0203;OM_ChildInitFailed;No description;3;OBJECT_MANAGER_IF;fsfw/src/fsfw/objectmanager/ObjectManagerIF.h -0x0204;OM_InternalErrReporterUninit;No description;4;OBJECT_MANAGER_IF;fsfw/src/fsfw/objectmanager/ObjectManagerIF.h -0x2201;TMF_Busy;No description;1;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h -0x2202;TMF_LastPacketFound;No description;2;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h -0x2203;TMF_StopFetch;No description;3;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h -0x2204;TMF_Timeout;No description;4;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h -0x2205;TMF_TmChannelFull;No description;5;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h -0x2206;TMF_NotStored;No description;6;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h -0x2207;TMF_AllDeleted;No description;7;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h -0x2208;TMF_InvalidData;No description;8;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h -0x2209;TMF_NotReady;No description;9;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h -0x2101;TMB_Busy;No description;1;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x2102;TMB_Full;No description;2;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x2103;TMB_Empty;No description;3;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x2104;TMB_NullRequested;No description;4;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x2105;TMB_TooLarge;No description;5;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x2106;TMB_NotReady;No description;6;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x2107;TMB_DumpError;No description;7;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x2108;TMB_CrcError;No description;8;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x2109;TMB_Timeout;No description;9;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x210a;TMB_IdlePacketFound;No description;10;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x210b;TMB_TelecommandFound;No description;11;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x210c;TMB_NoPusATm;No description;12;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x210d;TMB_TooSmall;No description;13;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x210e;TMB_BlockNotFound;No description;14;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x210f;TMB_InvalidRequest;No description;15;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x2d01;PAW_UnknownDatatype;No description;1;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h -0x2d02;PAW_DatatypeMissmatch;No description;2;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h -0x2d03;PAW_Readonly;No description;3;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h -0x2d04;PAW_TooBig;No description;4;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h -0x2d05;PAW_SourceNotSet;No description;5;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h -0x2d06;PAW_OutOfBounds;No description;6;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h -0x2d07;PAW_NotSet;No description;7;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h -0x2d08;PAW_ColumnOrRowsZero;No description;8;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h -0x2e01;HPA_InvalidIdentifierId;No description;1;HAS_PARAMETERS_IF;fsfw/src/fsfw/parameters/HasParametersIF.h -0x2e02;HPA_InvalidDomainId;No description;2;HAS_PARAMETERS_IF;fsfw/src/fsfw/parameters/HasParametersIF.h -0x2e03;HPA_InvalidValue;No description;3;HAS_PARAMETERS_IF;fsfw/src/fsfw/parameters/HasParametersIF.h -0x2e05;HPA_ReadOnly;No description;5;HAS_PARAMETERS_IF;fsfw/src/fsfw/parameters/HasParametersIF.h -0x3b01;SPH_SemaphoreTimeout;No description;1;SEMAPHORE_IF;fsfw/src/fsfw/tasks/SemaphoreIF.h -0x3b02;SPH_SemaphoreNotOwned;No description;2;SEMAPHORE_IF;fsfw/src/fsfw/tasks/SemaphoreIF.h -0x3b03;SPH_SemaphoreInvalid;No description;3;SEMAPHORE_IF;fsfw/src/fsfw/tasks/SemaphoreIF.h +0x4300;FILS_GenericFileError;No description;0;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h +0x4301;FILS_GenericDirError;No description;1;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h +0x4302;FILS_FilesystemInactive;No description;2;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h +0x4303;FILS_GenericRenameError;No description;3;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h +0x4304;FILS_IsBusy;No description;4;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h +0x4305;FILS_InvalidParameters;No description;5;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h +0x430a;FILS_FileDoesNotExist;No description;10;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h +0x430b;FILS_FileAlreadyExists;No description;11;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h +0x430c;FILS_NotAFile;No description;12;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h +0x430d;FILS_FileLocked;No description;13;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h +0x430e;FILS_PermissionDenied;No description;14;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h +0x4315;FILS_DirectoryDoesNotExist;No description;21;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h +0x4316;FILS_DirectoryAlreadyExists;No description;22;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h +0x4317;FILS_NotADirectory;No description;23;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h +0x4318;FILS_DirectoryNotEmpty;No description;24;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h +0x431e;FILS_SequencePacketMissingWrite;No description;30;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h +0x431f;FILS_SequencePacketMissingRead;No description;31;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h 0x1a01;TRC_NotEnoughSensors;No description;1;TRIPLE_REDUNDACY_CHECK;fsfw/src/fsfw/monitoring/TriplexMonitor.h 0x1a02;TRC_LowestValueOol;No description;2;TRIPLE_REDUNDACY_CHECK;fsfw/src/fsfw/monitoring/TriplexMonitor.h 0x1a03;TRC_HighestValueOol;No description;3;TRIPLE_REDUNDACY_CHECK;fsfw/src/fsfw/monitoring/TriplexMonitor.h @@ -322,74 +394,36 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path 0x31e2;LIM_WrongPid;No description;226;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h 0x31e3;LIM_WrongLimitId;No description;227;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h 0x31ee;LIM_MonitorNotFound;No description;238;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h -0x3601;CFDP_InvalidTlvType;No description;1;CFDP;fsfw/src/fsfw/cfdp/definitions.h -0x3602;CFDP_InvalidDirectiveField;No description;2;CFDP;fsfw/src/fsfw/cfdp/definitions.h -0x3603;CFDP_InvalidPduDatafieldLen;No description;3;CFDP;fsfw/src/fsfw/cfdp/definitions.h -0x3604;CFDP_InvalidAckDirectiveFields;No description;4;CFDP;fsfw/src/fsfw/cfdp/definitions.h -0x3605;CFDP_MetadataCantParseOptions;No description;5;CFDP;fsfw/src/fsfw/cfdp/definitions.h -0x3606;CFDP_NakCantParseOptions;No description;6;CFDP;fsfw/src/fsfw/cfdp/definitions.h -0x3607;CFDP_FinishedCantParseFsResponses;No description;7;CFDP;fsfw/src/fsfw/cfdp/definitions.h -0x3608;CFDP_FilestoreRequiresSecondFile;No description;8;CFDP;fsfw/src/fsfw/cfdp/definitions.h -0x3609;CFDP_FilestoreResponseCantParseFsMessage;No description;9;CFDP;fsfw/src/fsfw/cfdp/definitions.h -0x360a;CFDP_InvalidPduFormat;No description;10;CFDP;fsfw/src/fsfw/cfdp/definitions.h -0x4300;FILS_GenericFileError;No description;0;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x4301;FILS_GenericDirError;No description;1;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x4302;FILS_FilesystemInactive;No description;2;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x4303;FILS_GenericRenameError;No description;3;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x4304;FILS_IsBusy;No description;4;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x4305;FILS_InvalidParameters;No description;5;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x430a;FILS_FileDoesNotExist;No description;10;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x430b;FILS_FileAlreadyExists;No description;11;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x430c;FILS_NotAFile;No description;12;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x430d;FILS_FileLocked;No description;13;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x430e;FILS_PermissionDenied;No description;14;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x4315;FILS_DirectoryDoesNotExist;No description;21;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x4316;FILS_DirectoryAlreadyExists;No description;22;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x4317;FILS_NotADirectory;No description;23;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x4318;FILS_DirectoryNotEmpty;No description;24;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x431e;FILS_SequencePacketMissingWrite;No description;30;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x431f;FILS_SequencePacketMissingRead;No description;31;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x2c01;CCS_BcIsSetVrCommand;No description;1;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2c02;CCS_BcIsUnlockCommand;No description;2;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2cb0;CCS_BcIllegalCommand;No description;176;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2cb1;CCS_BoardReadingNotFinished;No description;177;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2cf0;CCS_NsPositiveW;No description;240;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2cf1;CCS_NsNegativeW;No description;241;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2cf2;CCS_NsLockout;No description;242;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2cf3;CCS_FarmInLockout;No description;243;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2cf4;CCS_FarmInWait;No description;244;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2ce0;CCS_WrongSymbol;No description;224;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2ce1;CCS_DoubleStart;No description;225;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2ce2;CCS_StartSymbolMissed;No description;226;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2ce3;CCS_EndWithoutStart;No description;227;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2ce4;CCS_TooLarge;No description;228;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2ce5;CCS_TooShort;No description;229;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2ce6;CCS_WrongTfVersion;No description;230;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2ce7;CCS_WrongSpacecraftId;No description;231;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2ce8;CCS_NoValidFrameType;No description;232;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2ce9;CCS_CrcFailed;No description;233;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2cea;CCS_VcNotFound;No description;234;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2ceb;CCS_ForwardingFailed;No description;235;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2cec;CCS_ContentTooLarge;No description;236;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2ced;CCS_ResidualData;No description;237;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2cee;CCS_DataCorrupted;No description;238;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2cef;CCS_IllegalSegmentationFlag;No description;239;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2cd0;CCS_IllegalFlagCombination;No description;208;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2cd1;CCS_ShorterThanHeader;No description;209;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2cd2;CCS_TooShortBlockedPacket;No description;210;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2cd3;CCS_TooShortMapExtraction;No description;211;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x4201;PUS11_InvalidTypeTimeWindow;No description;1;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h 0x4202;PUS11_InvalidTimeWindow;No description;2;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h 0x4203;PUS11_TimeshiftingNotPossible;No description;3;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h 0x4204;PUS11_InvalidRelativeTime;No description;4;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h 0x4205;PUS11_ContainedTcTooSmall;No description;5;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h 0x4206;PUS11_ContainedTcCrcMissmatch;No description;6;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h -0x3401;DC_NoReplyReceived;No description;1;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h -0x3402;DC_ProtocolError;No description;2;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h -0x3403;DC_Nullpointer;No description;3;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h -0x3404;DC_InvalidCookieType;No description;4;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h -0x3405;DC_NotActive;No description;5;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h -0x3406;DC_TooMuchData;No description;6;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h +0x0601;PP_DoItMyself;No description;1;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x0602;PP_PointsToVariable;No description;2;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x0603;PP_PointsToMemory;No description;3;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x0604;PP_ActivityCompleted;No description;4;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x0605;PP_PointsToVectorUint8;No description;5;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x0606;PP_PointsToVectorUint16;No description;6;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x0607;PP_PointsToVectorUint32;No description;7;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x0608;PP_PointsToVectorFloat;No description;8;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x06a0;PP_DumpNotSupported;No description;160;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x06e0;PP_InvalidSize;No description;224;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x06e1;PP_InvalidAddress;No description;225;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x06e2;PP_InvalidContent;No description;226;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x06e3;PP_UnalignedAccess;No description;227;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x06e4;PP_WriteProtected;No description;228;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x13e0;MH_UnknownCmd;No description;224;MEMORY_HELPER;fsfw/src/fsfw/memory/MemoryHelper.h +0x13e1;MH_InvalidAddress;No description;225;MEMORY_HELPER;fsfw/src/fsfw/memory/MemoryHelper.h +0x13e2;MH_InvalidSize;No description;226;MEMORY_HELPER;fsfw/src/fsfw/memory/MemoryHelper.h +0x13e3;MH_StateMismatch;No description;227;MEMORY_HELPER;fsfw/src/fsfw/memory/MemoryHelper.h +0x1201;AB_NeedSecondStep;No description;1;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h +0x1202;AB_NeedToReconfigure;No description;2;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h +0x1203;AB_ModeFallback;No description;3;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h +0x1204;AB_ChildNotCommandable;No description;4;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h +0x1205;AB_NeedToChangeHealth;No description;5;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h +0x12a1;AB_NotEnoughChildrenInCorrectState;No description;161;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h 0x03a0;DHB_InvalidChannel;No description;160;DEVICE_HANDLER_BASE;fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h 0x03b0;DHB_AperiodicReply;No description;176;DEVICE_HANDLER_BASE;fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h 0x03b1;DHB_IgnoreReplyData;No description;177;DEVICE_HANDLER_BASE;fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h @@ -399,12 +433,12 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path 0x03d0;DHB_NoSwitch;No description;208;DEVICE_HANDLER_BASE;fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h 0x03e0;DHB_ChildTimeout;No description;224;DEVICE_HANDLER_BASE;fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h 0x03e1;DHB_SwitchFailed;No description;225;DEVICE_HANDLER_BASE;fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h -0x1201;AB_NeedSecondStep;No description;1;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h -0x1202;AB_NeedToReconfigure;No description;2;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h -0x1203;AB_ModeFallback;No description;3;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h -0x1204;AB_ChildNotCommandable;No description;4;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h -0x1205;AB_NeedToChangeHealth;No description;5;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h -0x12a1;AB_NotEnoughChildrenInCorrectState;No description;161;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h +0x3401;DC_NoReplyReceived;No description;1;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h +0x3402;DC_ProtocolError;No description;2;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h +0x3403;DC_Nullpointer;No description;3;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h +0x3404;DC_InvalidCookieType;No description;4;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h +0x3405;DC_NotActive;No description;5;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h +0x3406;DC_TooMuchData;No description;6;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h 0x27a0;DHI_NoCommandData;No description;160;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h 0x27a1;DHI_CommandNotSupported;No description;161;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h 0x27a2;DHI_CommandAlreadySent;No description;162;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h @@ -426,54 +460,25 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path 0x27c3;DHI_DeviceReplyInvalid;No description;195;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h 0x27d0;DHI_InvalidCommandParameter;No description;208;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h 0x27d1;DHI_InvalidNumberOrLengthOfParameters;No description;209;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h -0x2401;MT_TooDetailedRequest;No description;1;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h -0x2402;MT_TooGeneralRequest;No description;2;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h -0x2403;MT_NoMatch;No description;3;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h -0x2404;MT_Full;No description;4;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h -0x2405;MT_NewNodeCreated;No description;5;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h -0x3f01;DLEE_NoPacketFound;No description;1;DLE_ENCODER;fsfw/src/fsfw/globalfunctions/DleParser.h -0x3f02;DLEE_PossiblePacketLoss;No description;2;DLE_ENCODER;fsfw/src/fsfw/globalfunctions/DleParser.h -0x2f01;ASC_TooLongForTargetType;No description;1;ASCII_CONVERTER;fsfw/src/fsfw/globalfunctions/AsciiConverter.h -0x2f02;ASC_InvalidCharacters;No description;2;ASCII_CONVERTER;fsfw/src/fsfw/globalfunctions/AsciiConverter.h -0x2f03;ASC_BufferTooSmall;No description;3;ASCII_CONVERTER;fsfw/src/fsfw/globalfunctions/AsciiConverter.h -0x1701;HHI_ObjectNotHealthy;No description;1;HAS_HEALTH_IF;fsfw/src/fsfw/health/HasHealthIF.h -0x1702;HHI_InvalidHealthState;No description;2;HAS_HEALTH_IF;fsfw/src/fsfw/health/HasHealthIF.h -0x1703;HHI_IsExternallyControlled;No description;3;HAS_HEALTH_IF;fsfw/src/fsfw/health/HasHealthIF.h -0x3201;CF_ObjectHasNoFunctions;No description;1;COMMANDS_ACTIONS_IF;fsfw/src/fsfw/action/CommandsActionsIF.h -0x3202;CF_AlreadyCommanding;No description;2;COMMANDS_ACTIONS_IF;fsfw/src/fsfw/action/CommandsActionsIF.h -0x3301;HF_IsBusy;No description;1;HAS_ACTIONS_IF;fsfw/src/fsfw/action/HasActionsIF.h -0x3302;HF_InvalidParameters;No description;2;HAS_ACTIONS_IF;fsfw/src/fsfw/action/HasActionsIF.h -0x3303;HF_ExecutionFinished;No description;3;HAS_ACTIONS_IF;fsfw/src/fsfw/action/HasActionsIF.h -0x3304;HF_InvalidActionId;No description;4;HAS_ACTIONS_IF;fsfw/src/fsfw/action/HasActionsIF.h -0x1000;TIM_UnsupportedTimeFormat;No description;0;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h -0x1001;TIM_NotEnoughInformationForTargetFormat;No description;1;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h -0x1002;TIM_LengthMismatch;No description;2;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h -0x1003;TIM_InvalidTimeFormat;No description;3;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h -0x1004;TIM_InvalidDayOfYear;No description;4;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h -0x1005;TIM_TimeDoesNotFitFormat;No description;5;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h -0x3701;TSI_BadTimestamp;No description;1;TIME_STAMPER_IF;fsfw/src/fsfw/timemanager/TimeStampIF.h -0x3c00;LPIF_PoolEntryNotFound;No description;0;LOCAL_POOL_OWNER_IF;fsfw/src/fsfw/datapoollocal/localPoolDefinitions.h -0x3c01;LPIF_PoolEntryTypeConflict;No description;1;LOCAL_POOL_OWNER_IF;fsfw/src/fsfw/datapoollocal/localPoolDefinitions.h -0x3e00;HKM_QueueOrDestinationInvalid;No description;0;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h -0x3e01;HKM_WrongHkPacketType;No description;1;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h -0x3e02;HKM_ReportingStatusUnchanged;No description;2;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h -0x3e03;HKM_PeriodicHelperInvalid;No description;3;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h -0x3e04;HKM_PoolobjectNotFound;No description;4;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h -0x3e05;HKM_DatasetNotFound;No description;5;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h -0x2901;TC_InvalidTargetState;No description;1;THERMAL_COMPONENT_IF;fsfw/src/fsfw/thermal/ThermalComponentIF.h -0x29f1;TC_AboveOperationalLimit;No description;241;THERMAL_COMPONENT_IF;fsfw/src/fsfw/thermal/ThermalComponentIF.h -0x29f2;TC_BelowOperationalLimit;No description;242;THERMAL_COMPONENT_IF;fsfw/src/fsfw/thermal/ThermalComponentIF.h -0x2001;CSB_ExecutionComplete;No description;1;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h -0x2002;CSB_NoStepMessage;No description;2;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h -0x2003;CSB_ObjectBusy;No description;3;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h -0x2004;CSB_Busy;No description;4;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h -0x2005;CSB_InvalidTc;No description;5;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h -0x2006;CSB_InvalidObject;No description;6;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h -0x2007;CSB_InvalidReply;No description;7;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h -0x4c00;SPPA_NoPacketFound;No description;0;SPACE_PACKET_PARSER;fsfw/src/fsfw/tmtcservices/SpacePacketParser.h -0x4c01;SPPA_SplitPacket;No description;1;SPACE_PACKET_PARSER;fsfw/src/fsfw/tmtcservices/SpacePacketParser.h -0x1d01;ATC_ActivityStarted;No description;1;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h -0x1d02;ATC_InvalidSubservice;No description;2;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h -0x1d03;ATC_IllegalApplicationData;No description;3;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h -0x1d04;ATC_SendTmFailed;No description;4;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h -0x1d05;ATC_Timeout;No description;5;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h +0x1401;SE_BufferTooShort;No description;1;SERIALIZE_IF;fsfw/src/fsfw/serialize/SerializeIF.h +0x1402;SE_StreamTooShort;No description;2;SERIALIZE_IF;fsfw/src/fsfw/serialize/SerializeIF.h +0x1403;SE_TooManyElements;No description;3;SERIALIZE_IF;fsfw/src/fsfw/serialize/SerializeIF.h +0x4500;HSPI_HalTimeoutRetval;No description;0;HAL_SPI;fsfw/src/fsfw_hal/stm32h7/spi/spiDefinitions.h +0x4501;HSPI_HalBusyRetval;No description;1;HAL_SPI;fsfw/src/fsfw_hal/stm32h7/spi/spiDefinitions.h +0x4502;HSPI_HalErrorRetval;No description;2;HAL_SPI;fsfw/src/fsfw_hal/stm32h7/spi/spiDefinitions.h +0x4601;HURT_UartReadFailure;No description;1;HAL_UART;fsfw/src/fsfw_hal/linux/serial/SerialComIF.h +0x4602;HURT_UartReadSizeMissmatch;No description;2;HAL_UART;fsfw/src/fsfw_hal/linux/serial/SerialComIF.h +0x4603;HURT_UartRxBufferTooSmall;No description;3;HAL_UART;fsfw/src/fsfw_hal/linux/serial/SerialComIF.h +0x4801;HGIO_UnknownGpioId;No description;1;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h +0x4802;HGIO_DriveGpioFailure;No description;2;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h +0x4803;HGIO_GpioTypeFailure;No description;3;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h +0x4804;HGIO_GpioInvalidInstance;No description;4;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h +0x4805;HGIO_GpioDuplicateDetected;No description;5;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h +0x4806;HGIO_GpioInitFailed;No description;6;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h +0x4807;HGIO_GpioGetValueFailed;No description;7;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h +0x4400;UXOS_ExecutionFinished;Execution of the current command has finished;0;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h +0x4401;UXOS_CommandPending;Command is pending. This will also be returned if the user tries to load another command but a command is still pending;1;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h +0x4402;UXOS_BytesRead;Some bytes have been read from the executing process;2;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h +0x4403;UXOS_CommandError;Command execution failed;3;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h +0x4404;UXOS_NoCommandLoadedOrPending;;4;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h +0x4406;UXOS_PcloseCallError;No description;6;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h diff --git a/generators/bsp_q7s_events.csv b/generators/bsp_q7s_events.csv index c1b0559d..b2c6c28f 100644 --- a/generators/bsp_q7s_events.csv +++ b/generators/bsp_q7s_events.csv @@ -271,8 +271,8 @@ Event ID (dec); Event ID (hex); Name; Severity; Description; File Path 14301;0x37dd;FILE_TOO_LARGE;LOW;File in store too large. P1: Detected file size P2: Allowed file size;mission/persistentTmStoreDefs.h 14302;0x37de;BUSY_DUMPING_EVENT;INFO;No description;mission/persistentTmStoreDefs.h 14303;0x37df;DUMP_WAS_CANCELLED;LOW;Dump was cancelled. P1: Object ID of store.;mission/persistentTmStoreDefs.h -14305;0x37e1;DUMP_OK_STORE_DONE;INFO;P1: Start time as UNIX seconds. P2: End time as UNIX seconds.;mission/persistentTmStoreDefs.h -14306;0x37e2;DUMP_NOK_STORE_DONE;INFO;P1: Start time as UNIX seconds. P2: End time as UNIX seconds.;mission/persistentTmStoreDefs.h -14307;0x37e3;DUMP_MISC_STORE_DONE;INFO;P1: Start time as UNIX seconds. P2: End time as UNIX seconds.;mission/persistentTmStoreDefs.h -14308;0x37e4;DUMP_HK_STORE_DONE;INFO;P1: Start time as UNIX seconds. P2: End time as UNIX seconds.;mission/persistentTmStoreDefs.h -14309;0x37e5;DUMP_CFDP_STORE_DONE;INFO;P1: Start time as UNIX seconds. P2: End time as UNIX seconds.;mission/persistentTmStoreDefs.h +14305;0x37e1;DUMP_OK_STORE_DONE;INFO;P1: Number of dumped packets. P2: Total dumped bytes.;mission/persistentTmStoreDefs.h +14306;0x37e2;DUMP_NOK_STORE_DONE;INFO;P1: Number of dumped packets. P2: Total dumped bytes.;mission/persistentTmStoreDefs.h +14307;0x37e3;DUMP_MISC_STORE_DONE;INFO;P1: Number of dumped packets. P2: Total dumped bytes.;mission/persistentTmStoreDefs.h +14308;0x37e4;DUMP_HK_STORE_DONE;INFO;P1: Number of dumped packets. P2: Total dumped bytes.;mission/persistentTmStoreDefs.h +14309;0x37e5;DUMP_CFDP_STORE_DONE;INFO;P1: Number of dumped packets. P2: Total dumped bytes.;mission/persistentTmStoreDefs.h diff --git a/generators/bsp_q7s_returnvalues.csv b/generators/bsp_q7s_returnvalues.csv index 55cd3697..fde6c972 100644 --- a/generators/bsp_q7s_returnvalues.csv +++ b/generators/bsp_q7s_returnvalues.csv @@ -1,7 +1,10 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path 0x0000;OK;System-wide code for ok.;0;HasReturnvaluesIF;fsfw/returnvalues/returnvalue.h 0x0001;Failed;Unspecified system-wide code for failed.;1;HasReturnvaluesIF;fsfw/returnvalues/returnvalue.h -0x63a0;NVMB_KeyNotExists;Specified key does not exist in json file;160;NVM_PARAM_BASE;mission/memory/NvmParameterBase.h +0x7000;PTM_DumpDone;No description;0;PERSISTENT_TM_STORE;mission/tmtc/PersistentTmStore.h +0x7001;PTM_BusyDumping;No description;1;PERSISTENT_TM_STORE;mission/tmtc/PersistentTmStore.h +0x60a0;CCSDS_CommandNotImplemented;Received action message with unknown action id;160;CCSDS_HANDLER;mission/tmtc/CcsdsIpCoreHandler.h +0x7100;TMS_IsBusy;No description;0;TM_SINK;mission/tmtc/DirectTmSinkIF.h 0x5100;IMTQ_InvalidCommandCode;No description;0;IMTQ_HANDLER;mission/devices/devicedefinitions/imtqHelpers.h 0x5101;IMTQ_MgmMeasurementLowLevelError;No description;1;IMTQ_HANDLER;mission/devices/devicedefinitions/imtqHelpers.h 0x5102;IMTQ_ActuateCmdLowLevelError;No description;2;IMTQ_HANDLER;mission/devices/devicedefinitions/imtqHelpers.h @@ -22,12 +25,23 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path 0x52b7;RWHA_SpiReadTimeout;Timeout when reading reply;183;RW_HANDLER;mission/devices/devicedefinitions/rwHelpers.h 0x58a0;SUSS_ErrorUnlockMutex;No description;160;SUS_HANDLER;mission/devices/LegacySusHandler.h 0x58a1;SUSS_ErrorLockMutex;No description;161;SUS_HANDLER;mission/devices/LegacySusHandler.h -0x66a0;SADPL_InvalidSpeed;Action Message with invalid speed was received. Valid speeds must be in the range of [-65000, 1000] or [1000, 65000];160;SA_DEPL_HANDLER;mission/devices/RwHandler.h -0x66a1;SADPL_InvalidRampTime;Action Message with invalid ramp time was received.;161;SA_DEPL_HANDLER;mission/devices/RwHandler.h -0x66a2;SADPL_SetSpeedCommandInvalidLength;Received set speed command has invalid length. Should be 6.;162;SA_DEPL_HANDLER;mission/devices/RwHandler.h -0x66a3;SADPL_ExecutionFailed;Command execution failed;163;SA_DEPL_HANDLER;mission/devices/RwHandler.h -0x66a4;SADPL_CrcError;Reaction wheel reply has invalid crc;164;SA_DEPL_HANDLER;mission/devices/RwHandler.h -0x66a5;SADPL_ValueNotRead;No description;165;SA_DEPL_HANDLER;mission/devices/RwHandler.h +0x5d00;GOMS_PacketTooLong;No description;0;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h +0x5d01;GOMS_InvalidTableId;No description;1;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h +0x5d02;GOMS_InvalidAddress;No description;2;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h +0x5d03;GOMS_InvalidParamSize;No description;3;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h +0x5d04;GOMS_InvalidPayloadSize;No description;4;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h +0x5d05;GOMS_UnknownReplyId;No description;5;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h +0x5da0;GOMS_InvalidSpeed;Action Message with invalid speed was received. Valid speeds must be in the range of [-65000, 1000] or [1000, 65000];160;GOM_SPACE_HANDLER;mission/devices/RwHandler.h +0x5da1;GOMS_InvalidRampTime;Action Message with invalid ramp time was received.;161;GOM_SPACE_HANDLER;mission/devices/RwHandler.h +0x5da2;GOMS_SetSpeedCommandInvalidLength;Received set speed command has invalid length. Should be 6.;162;GOM_SPACE_HANDLER;mission/devices/RwHandler.h +0x5da3;GOMS_ExecutionFailed;Command execution failed;163;GOM_SPACE_HANDLER;mission/devices/RwHandler.h +0x5da4;GOMS_CrcError;Reaction wheel reply has invalid crc;164;GOM_SPACE_HANDLER;mission/devices/RwHandler.h +0x5da5;GOMS_ValueNotRead;No description;165;GOM_SPACE_HANDLER;mission/devices/RwHandler.h +0x4fa1;HEATER_CommandNotSupported;No description;161;HEATER_HANDLER;mission/devices/HeaterHandler.h +0x4fa2;HEATER_InitFailed;No description;162;HEATER_HANDLER;mission/devices/HeaterHandler.h +0x4fa3;HEATER_InvalidSwitchNr;No description;163;HEATER_HANDLER;mission/devices/HeaterHandler.h +0x4fa4;HEATER_MainSwitchSetTimeout;No description;164;HEATER_HANDLER;mission/devices/HeaterHandler.h +0x4fa5;HEATER_CommandAlreadyWaiting;No description;165;HEATER_HANDLER;mission/devices/HeaterHandler.h 0x50a0;SYRLINKS_CrcFailure;No description;160;SYRLINKS_HANDLER;mission/devices/SyrlinksHandler.h 0x50a1;SYRLINKS_UartFraminOrParityErrorAck;No description;161;SYRLINKS_HANDLER;mission/devices/SyrlinksHandler.h 0x50a2;SYRLINKS_BadCharacterAck;No description;162;SYRLINKS_HANDLER;mission/devices/SyrlinksHandler.h @@ -37,23 +51,13 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path 0x50a6;SYRLINKS_BadCrcAck;No description;166;SYRLINKS_HANDLER;mission/devices/SyrlinksHandler.h 0x50a7;SYRLINKS_ReplyWrongSize;No description;167;SYRLINKS_HANDLER;mission/devices/SyrlinksHandler.h 0x50a8;SYRLINKS_MissingStartFrameCharacter;No description;168;SYRLINKS_HANDLER;mission/devices/SyrlinksHandler.h -0x5d00;GOMS_PacketTooLong;No description;0;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h -0x5d01;GOMS_InvalidTableId;No description;1;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h -0x5d02;GOMS_InvalidAddress;No description;2;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h -0x5d03;GOMS_InvalidParamSize;No description;3;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h -0x5d04;GOMS_InvalidPayloadSize;No description;4;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h -0x5d05;GOMS_UnknownReplyId;No description;5;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h -0x4fa1;HEATER_CommandNotSupported;No description;161;HEATER_HANDLER;mission/devices/HeaterHandler.h -0x4fa2;HEATER_InitFailed;No description;162;HEATER_HANDLER;mission/devices/HeaterHandler.h -0x4fa3;HEATER_InvalidSwitchNr;No description;163;HEATER_HANDLER;mission/devices/HeaterHandler.h -0x4fa4;HEATER_MainSwitchSetTimeout;No description;164;HEATER_HANDLER;mission/devices/HeaterHandler.h -0x4fa5;HEATER_CommandAlreadyWaiting;No description;165;HEATER_HANDLER;mission/devices/HeaterHandler.h -0x60a0;CCSDS_CommandNotImplemented;Received action message with unknown action id;160;CCSDS_HANDLER;mission/tmtc/CcsdsIpCoreHandler.h -0x7100;TMS_IsBusy;No description;0;TM_SINK;mission/tmtc/DirectTmSinkIF.h -0x7000;PTM_DumpDone;No description;0;PERSISTENT_TM_STORE;mission/tmtc/PersistentTmStore.h -0x7001;PTM_BusyDumping;No description;1;PERSISTENT_TM_STORE;mission/tmtc/PersistentTmStore.h -0x6b01;ACSSAF_SafectrlMekfInputInvalid;No description;1;ACS_SAFE;mission/controller/acs/control/SafeCtrl.h +0x66a0;SADPL_CommandNotSupported;No description;160;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h +0x66a1;SADPL_DeploymentAlreadyExecuting;No description;161;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h +0x66a2;SADPL_MainSwitchTimeoutFailure;No description;162;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h +0x66a3;SADPL_SwitchingDeplSa1Failed;No description;163;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h +0x66a4;SADPL_SwitchingDeplSa2Failed;No description;164;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h 0x6c01;ACSPTG_PtgctrlMekfInputInvalid;No description;1;ACS_PTG;mission/controller/acs/control/PtgCtrl.h +0x6b01;ACSSAF_SafectrlMekfInputInvalid;No description;1;ACS_SAFE;mission/controller/acs/control/SafeCtrl.h 0x6d01;ACSDTB_DetumbleNoSensordata;No description;1;ACS_DETUMBLE;mission/controller/acs/control/Detumble.h 0x6a02;ACSMEKF_MekfUninitialized;No description;2;ACS_MEKF;mission/controller/acs/MultiplicativeKalmanFilter.h 0x6a03;ACSMEKF_MekfNoGyrData;No description;3;ACS_MEKF;mission/controller/acs/MultiplicativeKalmanFilter.h @@ -63,105 +67,125 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path 0x6a07;ACSMEKF_MekfInitialized;No description;7;ACS_MEKF;mission/controller/acs/MultiplicativeKalmanFilter.h 0x6a08;ACSMEKF_MekfRunning;No description;8;ACS_MEKF;mission/controller/acs/MultiplicativeKalmanFilter.h 0x6900;ACSCTRL_FileDeletionFailed;No description;0;ACS_CTRL;mission/controller/AcsController.h -0x4500;HSPI_OpeningFileFailed;No description;0;HAL_SPI;fsfw/src/fsfw_hal/linux/spi/SpiComIF.h -0x4501;HSPI_FullDuplexTransferFailed;No description;1;HAL_SPI;fsfw/src/fsfw_hal/linux/spi/SpiComIF.h -0x4502;HSPI_HalfDuplexTransferFailed;No description;2;HAL_SPI;fsfw/src/fsfw_hal/linux/spi/SpiComIF.h -0x4801;HGIO_UnknownGpioId;No description;1;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h -0x4802;HGIO_DriveGpioFailure;No description;2;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h -0x4803;HGIO_GpioTypeFailure;No description;3;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h -0x4804;HGIO_GpioInvalidInstance;No description;4;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h -0x4805;HGIO_GpioDuplicateDetected;No description;5;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h -0x4806;HGIO_GpioInitFailed;No description;6;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h -0x4807;HGIO_GpioGetValueFailed;No description;7;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h -0x4601;HURT_UartReadFailure;No description;1;HAL_UART;fsfw/src/fsfw_hal/linux/serial/SerialComIF.h -0x4602;HURT_UartReadSizeMissmatch;No description;2;HAL_UART;fsfw/src/fsfw_hal/linux/serial/SerialComIF.h -0x4603;HURT_UartRxBufferTooSmall;No description;3;HAL_UART;fsfw/src/fsfw_hal/linux/serial/SerialComIF.h -0x4400;UXOS_ExecutionFinished;Execution of the current command has finished;0;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h -0x4401;UXOS_CommandPending;Command is pending. This will also be returned if the user tries to load another command but a command is still pending;1;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h -0x4402;UXOS_BytesRead;Some bytes have been read from the executing process;2;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h -0x4403;UXOS_CommandError;Command execution failed;3;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h -0x4404;UXOS_NoCommandLoadedOrPending;;4;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h -0x4406;UXOS_PcloseCallError;No description;6;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h -0x2801;SM_DataTooLarge;No description;1;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h -0x2802;SM_DataStorageFull;No description;2;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h -0x2803;SM_IllegalStorageId;No description;3;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h -0x2804;SM_DataDoesNotExist;No description;4;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h -0x2805;SM_IllegalAddress;No description;5;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h -0x2806;SM_PoolTooLarge;No description;6;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h -0x0601;PP_DoItMyself;No description;1;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h -0x0602;PP_PointsToVariable;No description;2;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h -0x0603;PP_PointsToMemory;No description;3;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h -0x0604;PP_ActivityCompleted;No description;4;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h -0x0605;PP_PointsToVectorUint8;No description;5;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h -0x0606;PP_PointsToVectorUint16;No description;6;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h -0x0607;PP_PointsToVectorUint32;No description;7;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h -0x0608;PP_PointsToVectorFloat;No description;8;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h -0x06a0;PP_DumpNotSupported;No description;160;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h -0x06e0;PP_InvalidSize;No description;224;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h -0x06e1;PP_InvalidAddress;No description;225;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h -0x06e2;PP_InvalidContent;No description;226;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h -0x06e3;PP_UnalignedAccess;No description;227;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h -0x06e4;PP_WriteProtected;No description;228;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h -0x13e0;MH_UnknownCmd;No description;224;MEMORY_HELPER;fsfw/src/fsfw/memory/MemoryHelper.h -0x13e1;MH_InvalidAddress;No description;225;MEMORY_HELPER;fsfw/src/fsfw/memory/MemoryHelper.h -0x13e2;MH_InvalidSize;No description;226;MEMORY_HELPER;fsfw/src/fsfw/memory/MemoryHelper.h -0x13e3;MH_StateMismatch;No description;227;MEMORY_HELPER;fsfw/src/fsfw/memory/MemoryHelper.h -0x38a1;SGP4_InvalidEccentricity;No description;161;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h -0x38a2;SGP4_InvalidMeanMotion;No description;162;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h -0x38a3;SGP4_InvalidPerturbationElements;No description;163;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h -0x38a4;SGP4_InvalidSemiLatusRectum;No description;164;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h -0x38a5;SGP4_InvalidEpochElements;No description;165;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h -0x38a6;SGP4_SatelliteHasDecayed;No description;166;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h -0x38b1;SGP4_TleTooOld;No description;177;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h -0x38b2;SGP4_TleNotInitialized;No description;178;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h -0x1801;FF_Full;No description;1;FIFO_CLASS;fsfw/src/fsfw/container/FIFOBase.h -0x1802;FF_Empty;No description;2;FIFO_CLASS;fsfw/src/fsfw/container/FIFOBase.h -0x1601;FMM_MapFull;No description;1;FIXED_MULTIMAP;fsfw/src/fsfw/container/FixedOrderedMultimap.h -0x1602;FMM_KeyDoesNotExist;No description;2;FIXED_MULTIMAP;fsfw/src/fsfw/container/FixedOrderedMultimap.h -0x3901;MUX_NotEnoughResources;No description;1;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h -0x3902;MUX_InsufficientMemory;No description;2;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h -0x3903;MUX_NoPrivilege;No description;3;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h -0x3904;MUX_WrongAttributeSetting;No description;4;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h -0x3905;MUX_MutexAlreadyLocked;No description;5;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h -0x3906;MUX_MutexNotFound;No description;6;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h -0x3907;MUX_MutexMaxLocks;No description;7;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h -0x3908;MUX_CurrThreadAlreadyOwnsMutex;No description;8;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h -0x3909;MUX_CurrThreadDoesNotOwnMutex;No description;9;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h -0x390a;MUX_MutexTimeout;No description;10;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h -0x390b;MUX_MutexInvalidId;No description;11;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h -0x390c;MUX_MutexDestroyedWhileWaiting;No description;12;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h -0x3a01;MQI_Empty;No description;1;MESSAGE_QUEUE_IF;fsfw/src/fsfw/ipc/MessageQueueIF.h -0x3a02;MQI_Full;No space left for more messages;2;MESSAGE_QUEUE_IF;fsfw/src/fsfw/ipc/MessageQueueIF.h -0x3a03;MQI_NoReplyPartner;Returned if a reply method was called without partner;3;MESSAGE_QUEUE_IF;fsfw/src/fsfw/ipc/MessageQueueIF.h -0x3a04;MQI_DestinationInvalid;Returned if the target destination is invalid.;4;MESSAGE_QUEUE_IF;fsfw/src/fsfw/ipc/MessageQueueIF.h -0x0f01;CM_UnknownCommand;No description;1;COMMAND_MESSAGE;fsfw/src/fsfw/ipc/CommandMessageIF.h +0x63a0;NVMB_KeyNotExists;Specified key does not exist in json file;160;NVM_PARAM_BASE;mission/memory/NvmParameterBase.h +0x2c01;CCS_BcIsSetVrCommand;No description;1;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2c02;CCS_BcIsUnlockCommand;No description;2;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2cb0;CCS_BcIllegalCommand;No description;176;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2cb1;CCS_BoardReadingNotFinished;No description;177;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2cf0;CCS_NsPositiveW;No description;240;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2cf1;CCS_NsNegativeW;No description;241;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2cf2;CCS_NsLockout;No description;242;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2cf3;CCS_FarmInLockout;No description;243;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2cf4;CCS_FarmInWait;No description;244;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2ce0;CCS_WrongSymbol;No description;224;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2ce1;CCS_DoubleStart;No description;225;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2ce2;CCS_StartSymbolMissed;No description;226;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2ce3;CCS_EndWithoutStart;No description;227;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2ce4;CCS_TooLarge;No description;228;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2ce5;CCS_TooShort;No description;229;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2ce6;CCS_WrongTfVersion;No description;230;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2ce7;CCS_WrongSpacecraftId;No description;231;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2ce8;CCS_NoValidFrameType;No description;232;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2ce9;CCS_CrcFailed;No description;233;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2cea;CCS_VcNotFound;No description;234;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2ceb;CCS_ForwardingFailed;No description;235;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2cec;CCS_ContentTooLarge;No description;236;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2ced;CCS_ResidualData;No description;237;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2cee;CCS_DataCorrupted;No description;238;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2cef;CCS_IllegalSegmentationFlag;No description;239;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2cd0;CCS_IllegalFlagCombination;No description;208;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2cd1;CCS_ShorterThanHeader;No description;209;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2cd2;CCS_TooShortBlockedPacket;No description;210;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2cd3;CCS_TooShortMapExtraction;No description;211;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x3b00;SPH_ConnBroken;No description;0;SEMAPHORE_IF;fsfw/src/fsfw/osal/common/TcpTmTcServer.h +0x2a01;IEC_NoConfigurationTable;No description;1;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a02;IEC_NoCpuTable;No description;2;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a03;IEC_InvalidWorkspaceAddress;No description;3;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a04;IEC_TooLittleWorkspace;No description;4;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a05;IEC_WorkspaceAllocation;No description;5;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a06;IEC_InterruptStackTooSmall;No description;6;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a07;IEC_ThreadExitted;No description;7;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a08;IEC_InconsistentMpInformation;No description;8;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a09;IEC_InvalidNode;No description;9;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a0a;IEC_NoMpci;No description;10;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a0b;IEC_BadPacket;No description;11;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a0c;IEC_OutOfPackets;No description;12;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a0d;IEC_OutOfGlobalObjects;No description;13;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a0e;IEC_OutOfProxies;No description;14;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a0f;IEC_InvalidGlobalId;No description;15;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a10;IEC_BadStackHook;No description;16;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a11;IEC_BadAttributes;No description;17;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a12;IEC_ImplementationKeyCreateInconsistency;No description;18;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a13;IEC_ImplementationBlockingOperationCancel;No description;19;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a14;IEC_MutexObtainFromBadState;No description;20;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a15;IEC_UnlimitedAndMaximumIs0;No description;21;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h 0x0e01;HM_InvalidMode;No description;1;HAS_MODES_IF;fsfw/src/fsfw/modes/HasModesIF.h 0x0e02;HM_TransNotAllowed;No description;2;HAS_MODES_IF;fsfw/src/fsfw/modes/HasModesIF.h 0x0e03;HM_InTransition;No description;3;HAS_MODES_IF;fsfw/src/fsfw/modes/HasModesIF.h 0x0e04;HM_InvalidSubmode;No description;4;HAS_MODES_IF;fsfw/src/fsfw/modes/HasModesIF.h -0x0c02;MS_InvalidEntry;No description;2;MODE_STORE_IF;fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h -0x0c03;MS_TooManyElements;No description;3;MODE_STORE_IF;fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h -0x0c04;MS_CantStoreEmpty;No description;4;MODE_STORE_IF;fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h -0x0b01;SB_ChildNotFound;No description;1;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h -0x0b02;SB_ChildInfoUpdated;No description;2;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h -0x0b03;SB_ChildDoesntHaveModes;No description;3;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h -0x0b04;SB_CouldNotInsertChild;No description;4;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h -0x0b05;SB_TableContainsInvalidObjectId;No description;5;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h -0x0d01;SS_SequenceAlreadyExists;No description;1;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h -0x0d02;SS_TableAlreadyExists;No description;2;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h -0x0d03;SS_TableDoesNotExist;No description;3;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h -0x0d04;SS_TableOrSequenceLengthInvalid;No description;4;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h -0x0d05;SS_SequenceDoesNotExist;No description;5;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h -0x0d06;SS_TableContainsInvalidObjectId;No description;6;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h -0x0d07;SS_FallbackSequenceDoesNotExist;No description;7;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h -0x0d08;SS_NoTargetTable;No description;8;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h -0x0d09;SS_SequenceOrTableTooLong;No description;9;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h -0x0d0b;SS_IsFallbackSequence;No description;11;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h -0x0d0c;SS_AccessDenied;No description;12;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h -0x0d0e;SS_TableInUse;No description;14;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h -0x0da1;SS_TargetTableNotReached;No description;161;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h -0x0da2;SS_TableCheckFailed;No description;162;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h -0x2501;EV_ListenerNotFound;No description;1;EVENT_MANAGER_IF;fsfw/src/fsfw/events/EventManagerIF.h +0x2e01;HPA_InvalidIdentifierId;No description;1;HAS_PARAMETERS_IF;fsfw/src/fsfw/parameters/HasParametersIF.h +0x2e02;HPA_InvalidDomainId;No description;2;HAS_PARAMETERS_IF;fsfw/src/fsfw/parameters/HasParametersIF.h +0x2e03;HPA_InvalidValue;No description;3;HAS_PARAMETERS_IF;fsfw/src/fsfw/parameters/HasParametersIF.h +0x2e05;HPA_ReadOnly;No description;5;HAS_PARAMETERS_IF;fsfw/src/fsfw/parameters/HasParametersIF.h +0x2d01;PAW_UnknownDatatype;No description;1;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h +0x2d02;PAW_DatatypeMissmatch;No description;2;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h +0x2d03;PAW_Readonly;No description;3;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h +0x2d04;PAW_TooBig;No description;4;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h +0x2d05;PAW_SourceNotSet;No description;5;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h +0x2d06;PAW_OutOfBounds;No description;6;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h +0x2d07;PAW_NotSet;No description;7;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h +0x2d08;PAW_ColumnOrRowsZero;No description;8;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h +0x3201;CF_ObjectHasNoFunctions;No description;1;COMMANDS_ACTIONS_IF;fsfw/src/fsfw/action/CommandsActionsIF.h +0x3202;CF_AlreadyCommanding;No description;2;COMMANDS_ACTIONS_IF;fsfw/src/fsfw/action/CommandsActionsIF.h +0x3301;HF_IsBusy;No description;1;HAS_ACTIONS_IF;fsfw/src/fsfw/action/HasActionsIF.h +0x3302;HF_InvalidParameters;No description;2;HAS_ACTIONS_IF;fsfw/src/fsfw/action/HasActionsIF.h +0x3303;HF_ExecutionFinished;No description;3;HAS_ACTIONS_IF;fsfw/src/fsfw/action/HasActionsIF.h +0x3304;HF_InvalidActionId;No description;4;HAS_ACTIONS_IF;fsfw/src/fsfw/action/HasActionsIF.h +0x0201;OM_InsertionFailed;No description;1;OBJECT_MANAGER_IF;fsfw/src/fsfw/objectmanager/ObjectManagerIF.h +0x0202;OM_NotFound;No description;2;OBJECT_MANAGER_IF;fsfw/src/fsfw/objectmanager/ObjectManagerIF.h +0x0203;OM_ChildInitFailed;No description;3;OBJECT_MANAGER_IF;fsfw/src/fsfw/objectmanager/ObjectManagerIF.h +0x0204;OM_InternalErrReporterUninit;No description;4;OBJECT_MANAGER_IF;fsfw/src/fsfw/objectmanager/ObjectManagerIF.h +0x2600;FDI_YourFault;No description;0;HANDLES_FAILURES_IF;fsfw/src/fsfw/fdir/ConfirmsFailuresIF.h +0x2601;FDI_MyFault;No description;1;HANDLES_FAILURES_IF;fsfw/src/fsfw/fdir/ConfirmsFailuresIF.h +0x2602;FDI_ConfirmLater;No description;2;HANDLES_FAILURES_IF;fsfw/src/fsfw/fdir/ConfirmsFailuresIF.h +0x2201;TMF_Busy;No description;1;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h +0x2202;TMF_LastPacketFound;No description;2;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h +0x2203;TMF_StopFetch;No description;3;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h +0x2204;TMF_Timeout;No description;4;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h +0x2205;TMF_TmChannelFull;No description;5;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h +0x2206;TMF_NotStored;No description;6;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h +0x2207;TMF_AllDeleted;No description;7;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h +0x2208;TMF_InvalidData;No description;8;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h +0x2209;TMF_NotReady;No description;9;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h +0x2101;TMB_Busy;No description;1;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x2102;TMB_Full;No description;2;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x2103;TMB_Empty;No description;3;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x2104;TMB_NullRequested;No description;4;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x2105;TMB_TooLarge;No description;5;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x2106;TMB_NotReady;No description;6;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x2107;TMB_DumpError;No description;7;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x2108;TMB_CrcError;No description;8;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x2109;TMB_Timeout;No description;9;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x210a;TMB_IdlePacketFound;No description;10;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x210b;TMB_TelecommandFound;No description;11;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x210c;TMB_NoPusATm;No description;12;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x210d;TMB_TooSmall;No description;13;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x210e;TMB_BlockNotFound;No description;14;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x210f;TMB_InvalidRequest;No description;15;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x1c01;TCD_PacketLost;No description;1;PACKET_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/TcDistributorBase.h +0x1c02;TCD_DestinationNotFound;No description;2;PACKET_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/TcDistributorBase.h +0x1c03;TCD_ServiceIdAlreadyExists;No description;3;PACKET_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/TcDistributorBase.h +0x1b00;TCC_NoDestinationFound;No description;0;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b01;TCC_InvalidCcsdsVersion;No description;1;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b02;TCC_InvalidApid;No description;2;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b03;TCC_InvalidPacketType;No description;3;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b04;TCC_InvalidSecHeaderField;No description;4;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b05;TCC_IncorrectPrimaryHeader;No description;5;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b07;TCC_IncompletePacket;No description;7;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b08;TCC_InvalidPusVersion;No description;8;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b09;TCC_IncorrectChecksum;No description;9;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b0a;TCC_IllegalPacketSubtype;No description;10;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b0b;TCC_IncorrectSecondaryHeader;No description;11;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h 0x04e1;RMP_CommandNoDescriptorsAvailable;No description;225;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h 0x04e2;RMP_CommandBufferFull;No description;226;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h 0x04e3;RMP_CommandChannelOutOfRange;No description;227;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h @@ -202,9 +226,95 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path 0x040a;RMP_ReplyCommandNotImplementedOrNotAuthorised;No description;10;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h 0x040b;RMP_ReplyRmwDataLengthError;No description;11;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h 0x040c;RMP_ReplyInvalidTargetLogicalAddress;No description;12;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h -0x1401;SE_BufferTooShort;No description;1;SERIALIZE_IF;fsfw/src/fsfw/serialize/SerializeIF.h -0x1402;SE_StreamTooShort;No description;2;SERIALIZE_IF;fsfw/src/fsfw/serialize/SerializeIF.h -0x1403;SE_TooManyElements;No description;3;SERIALIZE_IF;fsfw/src/fsfw/serialize/SerializeIF.h +0x2801;SM_DataTooLarge;No description;1;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h +0x2802;SM_DataStorageFull;No description;2;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h +0x2803;SM_IllegalStorageId;No description;3;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h +0x2804;SM_DataDoesNotExist;No description;4;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h +0x2805;SM_IllegalAddress;No description;5;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h +0x2806;SM_PoolTooLarge;No description;6;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h +0x38a1;SGP4_InvalidEccentricity;No description;161;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h +0x38a2;SGP4_InvalidMeanMotion;No description;162;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h +0x38a3;SGP4_InvalidPerturbationElements;No description;163;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h +0x38a4;SGP4_InvalidSemiLatusRectum;No description;164;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h +0x38a5;SGP4_InvalidEpochElements;No description;165;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h +0x38a6;SGP4_SatelliteHasDecayed;No description;166;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h +0x38b1;SGP4_TleTooOld;No description;177;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h +0x38b2;SGP4_TleNotInitialized;No description;178;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h +0x2401;MT_NoPacketFound;No description;1;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/DleParser.h +0x2402;MT_PossiblePacketLoss;No description;2;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/DleParser.h +0x2403;MT_NoMatch;No description;3;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h +0x2404;MT_Full;No description;4;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h +0x2405;MT_NewNodeCreated;No description;5;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h +0x3f01;DLEE_StreamTooShort;No description;1;DLE_ENCODER;fsfw/src/fsfw/globalfunctions/DleEncoder.h +0x3f02;DLEE_DecodingError;No description;2;DLE_ENCODER;fsfw/src/fsfw/globalfunctions/DleEncoder.h +0x2f01;ASC_TooLongForTargetType;No description;1;ASCII_CONVERTER;fsfw/src/fsfw/globalfunctions/AsciiConverter.h +0x2f02;ASC_InvalidCharacters;No description;2;ASCII_CONVERTER;fsfw/src/fsfw/globalfunctions/AsciiConverter.h +0x2f03;ASC_BufferTooSmall;No description;3;ASCII_CONVERTER;fsfw/src/fsfw/globalfunctions/AsciiConverter.h +0x0f01;CM_UnknownCommand;No description;1;COMMAND_MESSAGE;fsfw/src/fsfw/ipc/CommandMessageIF.h +0x3a01;MQI_Empty;No description;1;MESSAGE_QUEUE_IF;fsfw/src/fsfw/ipc/MessageQueueIF.h +0x3a02;MQI_Full;No space left for more messages;2;MESSAGE_QUEUE_IF;fsfw/src/fsfw/ipc/MessageQueueIF.h +0x3a03;MQI_NoReplyPartner;Returned if a reply method was called without partner;3;MESSAGE_QUEUE_IF;fsfw/src/fsfw/ipc/MessageQueueIF.h +0x3a04;MQI_DestinationInvalid;Returned if the target destination is invalid.;4;MESSAGE_QUEUE_IF;fsfw/src/fsfw/ipc/MessageQueueIF.h +0x3901;MUX_NotEnoughResources;No description;1;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h +0x3902;MUX_InsufficientMemory;No description;2;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h +0x3903;MUX_NoPrivilege;No description;3;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h +0x3904;MUX_WrongAttributeSetting;No description;4;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h +0x3905;MUX_MutexAlreadyLocked;No description;5;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h +0x3906;MUX_MutexNotFound;No description;6;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h +0x3907;MUX_MutexMaxLocks;No description;7;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h +0x3908;MUX_CurrThreadAlreadyOwnsMutex;No description;8;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h +0x3909;MUX_CurrThreadDoesNotOwnMutex;No description;9;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h +0x390a;MUX_MutexTimeout;No description;10;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h +0x390b;MUX_MutexInvalidId;No description;11;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h +0x390c;MUX_MutexDestroyedWhileWaiting;No description;12;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h +0x3b01;SPH_SemaphoreTimeout;No description;1;SEMAPHORE_IF;fsfw/src/fsfw/tasks/SemaphoreIF.h +0x3b02;SPH_SemaphoreNotOwned;No description;2;SEMAPHORE_IF;fsfw/src/fsfw/tasks/SemaphoreIF.h +0x3b03;SPH_SemaphoreInvalid;No description;3;SEMAPHORE_IF;fsfw/src/fsfw/tasks/SemaphoreIF.h +0x1e00;PUS_InvalidPusVersion;No description;0;PUS_IF;fsfw/src/fsfw/tmtcpacket/pus/PusIF.h +0x1e01;PUS_InvalidCrc16;No description;1;PUS_IF;fsfw/src/fsfw/tmtcpacket/pus/PusIF.h +0x3601;CFDP_InvalidTlvType;No description;1;CFDP;fsfw/src/fsfw/cfdp/definitions.h +0x3602;CFDP_InvalidDirectiveField;No description;2;CFDP;fsfw/src/fsfw/cfdp/definitions.h +0x3603;CFDP_InvalidPduDatafieldLen;No description;3;CFDP;fsfw/src/fsfw/cfdp/definitions.h +0x3604;CFDP_InvalidAckDirectiveFields;No description;4;CFDP;fsfw/src/fsfw/cfdp/definitions.h +0x3605;CFDP_MetadataCantParseOptions;No description;5;CFDP;fsfw/src/fsfw/cfdp/definitions.h +0x3606;CFDP_NakCantParseOptions;No description;6;CFDP;fsfw/src/fsfw/cfdp/definitions.h +0x3607;CFDP_FinishedCantParseFsResponses;No description;7;CFDP;fsfw/src/fsfw/cfdp/definitions.h +0x3608;CFDP_FilestoreRequiresSecondFile;No description;8;CFDP;fsfw/src/fsfw/cfdp/definitions.h +0x3609;CFDP_FilestoreResponseCantParseFsMessage;No description;9;CFDP;fsfw/src/fsfw/cfdp/definitions.h +0x360a;CFDP_InvalidPduFormat;No description;10;CFDP;fsfw/src/fsfw/cfdp/definitions.h +0x2901;TC_InvalidTargetState;No description;1;THERMAL_COMPONENT_IF;fsfw/src/fsfw/thermal/ThermalComponentIF.h +0x29f1;TC_AboveOperationalLimit;No description;241;THERMAL_COMPONENT_IF;fsfw/src/fsfw/thermal/ThermalComponentIF.h +0x29f2;TC_BelowOperationalLimit;No description;242;THERMAL_COMPONENT_IF;fsfw/src/fsfw/thermal/ThermalComponentIF.h +0x0c02;MS_InvalidEntry;No description;2;MODE_STORE_IF;fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h +0x0c03;MS_TooManyElements;No description;3;MODE_STORE_IF;fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h +0x0c04;MS_CantStoreEmpty;No description;4;MODE_STORE_IF;fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h +0x0d01;SS_SequenceAlreadyExists;No description;1;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0d02;SS_TableAlreadyExists;No description;2;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0d03;SS_TableDoesNotExist;No description;3;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0d04;SS_TableOrSequenceLengthInvalid;No description;4;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0d05;SS_SequenceDoesNotExist;No description;5;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0d06;SS_TableContainsInvalidObjectId;No description;6;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0d07;SS_FallbackSequenceDoesNotExist;No description;7;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0d08;SS_NoTargetTable;No description;8;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0d09;SS_SequenceOrTableTooLong;No description;9;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0d0b;SS_IsFallbackSequence;No description;11;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0d0c;SS_AccessDenied;No description;12;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0d0e;SS_TableInUse;No description;14;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0da1;SS_TargetTableNotReached;No description;161;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0da2;SS_TableCheckFailed;No description;162;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0b01;SB_ChildNotFound;No description;1;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h +0x0b02;SB_ChildInfoUpdated;No description;2;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h +0x0b03;SB_ChildDoesntHaveModes;No description;3;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h +0x0b04;SB_CouldNotInsertChild;No description;4;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h +0x0b05;SB_TableContainsInvalidObjectId;No description;5;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h +0x3e00;HKM_QueueOrDestinationInvalid;No description;0;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h +0x3e01;HKM_WrongHkPacketType;No description;1;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h +0x3e02;HKM_ReportingStatusUnchanged;No description;2;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h +0x3e03;HKM_PeriodicHelperInvalid;No description;3;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h +0x3e04;HKM_PoolobjectNotFound;No description;4;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h +0x3e05;HKM_DatasetNotFound;No description;5;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h +0x3c00;LPIF_PoolEntryNotFound;No description;0;LOCAL_POOL_OWNER_IF;fsfw/src/fsfw/datapoollocal/localPoolDefinitions.h +0x3c01;LPIF_PoolEntryTypeConflict;No description;1;LOCAL_POOL_OWNER_IF;fsfw/src/fsfw/datapoollocal/localPoolDefinitions.h 0x3da0;PVA_InvalidReadWriteMode;No description;160;POOL_VARIABLE_IF;fsfw/src/fsfw/datapool/PoolVariableIF.h 0x3da1;PVA_InvalidPoolEntry;No description;161;POOL_VARIABLE_IF;fsfw/src/fsfw/datapool/PoolVariableIF.h 0x0801;DPS_InvalidParameterDefinition;No description;1;DATA_SET_CLASS;fsfw/src/fsfw/datapool/DataSetIF.h @@ -213,20 +323,35 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path 0x0804;DPS_DataSetUninitialised;No description;4;DATA_SET_CLASS;fsfw/src/fsfw/datapool/DataSetIF.h 0x0805;DPS_DataSetFull;No description;5;DATA_SET_CLASS;fsfw/src/fsfw/datapool/DataSetIF.h 0x0806;DPS_PoolVarNull;No description;6;DATA_SET_CLASS;fsfw/src/fsfw/datapool/DataSetIF.h -0x1c01;TCD_PacketLost;No description;1;PACKET_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/TcDistributorBase.h -0x1c02;TCD_DestinationNotFound;No description;2;PACKET_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/TcDistributorBase.h -0x1c03;TCD_ServiceIdAlreadyExists;No description;3;PACKET_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/TcDistributorBase.h -0x1b00;TCC_NoDestinationFound;No description;0;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h -0x1b01;TCC_InvalidCcsdsVersion;No description;1;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h -0x1b02;TCC_InvalidApid;No description;2;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h -0x1b03;TCC_InvalidPacketType;No description;3;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h -0x1b04;TCC_InvalidSecHeaderField;No description;4;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h -0x1b05;TCC_IncorrectPrimaryHeader;No description;5;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h -0x1b07;TCC_IncompletePacket;No description;7;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h -0x1b08;TCC_InvalidPusVersion;No description;8;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h -0x1b09;TCC_IncorrectChecksum;No description;9;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h -0x1b0a;TCC_IllegalPacketSubtype;No description;10;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h -0x1b0b;TCC_IncorrectSecondaryHeader;No description;11;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h +0x1000;TIM_UnsupportedTimeFormat;No description;0;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h +0x1001;TIM_NotEnoughInformationForTargetFormat;No description;1;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h +0x1002;TIM_LengthMismatch;No description;2;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h +0x1003;TIM_InvalidTimeFormat;No description;3;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h +0x1004;TIM_InvalidDayOfYear;No description;4;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h +0x1005;TIM_TimeDoesNotFitFormat;No description;5;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h +0x3701;TSI_BadTimestamp;No description;1;TIME_STAMPER_IF;fsfw/src/fsfw/timemanager/TimeStampIF.h +0x1d01;ATC_ActivityStarted;No description;1;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h +0x1d02;ATC_InvalidSubservice;No description;2;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h +0x1d03;ATC_IllegalApplicationData;No description;3;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h +0x1d04;ATC_SendTmFailed;No description;4;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h +0x1d05;ATC_Timeout;No description;5;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h +0x4c00;SPPA_NoPacketFound;No description;0;SPACE_PACKET_PARSER;fsfw/src/fsfw/tmtcservices/SpacePacketParser.h +0x4c01;SPPA_SplitPacket;No description;1;SPACE_PACKET_PARSER;fsfw/src/fsfw/tmtcservices/SpacePacketParser.h +0x2001;CSB_ExecutionComplete;No description;1;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h +0x2002;CSB_NoStepMessage;No description;2;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h +0x2003;CSB_ObjectBusy;No description;3;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h +0x2004;CSB_Busy;No description;4;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h +0x2005;CSB_InvalidTc;No description;5;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h +0x2006;CSB_InvalidObject;No description;6;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h +0x2007;CSB_InvalidReply;No description;7;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h +0x1801;FF_Full;No description;1;FIFO_CLASS;fsfw/src/fsfw/container/FIFOBase.h +0x1802;FF_Empty;No description;2;FIFO_CLASS;fsfw/src/fsfw/container/FIFOBase.h +0x1601;FMM_MapFull;No description;1;FIXED_MULTIMAP;fsfw/src/fsfw/container/FixedOrderedMultimap.h +0x1602;FMM_KeyDoesNotExist;No description;2;FIXED_MULTIMAP;fsfw/src/fsfw/container/FixedOrderedMultimap.h +0x2501;EV_ListenerNotFound;No description;1;EVENT_MANAGER_IF;fsfw/src/fsfw/events/EventManagerIF.h +0x1701;HHI_ObjectNotHealthy;No description;1;HAS_HEALTH_IF;fsfw/src/fsfw/health/HasHealthIF.h +0x1702;HHI_InvalidHealthState;No description;2;HAS_HEALTH_IF;fsfw/src/fsfw/health/HasHealthIF.h +0x1703;HHI_IsExternallyControlled;No description;3;HAS_HEALTH_IF;fsfw/src/fsfw/health/HasHealthIF.h 0x3001;POS_InPowerTransition;No description;1;POWER_SWITCHER;fsfw/src/fsfw/power/PowerSwitcher.h 0x3002;POS_SwitchStateMismatch;No description;2;POWER_SWITCHER;fsfw/src/fsfw/power/PowerSwitcher.h 0x0501;PS_SwitchOn;No description;1;POWER_SWITCH_IF;fsfw/src/fsfw/power/PowerSwitchIF.h @@ -234,76 +359,23 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path 0x0502;PS_SwitchTimeout;No description;2;POWER_SWITCH_IF;fsfw/src/fsfw/power/PowerSwitchIF.h 0x0503;PS_FuseOn;No description;3;POWER_SWITCH_IF;fsfw/src/fsfw/power/PowerSwitchIF.h 0x0504;PS_FuseOff;No description;4;POWER_SWITCH_IF;fsfw/src/fsfw/power/PowerSwitchIF.h -0x3b00;SPH_ConnBroken;No description;0;SEMAPHORE_IF;fsfw/src/fsfw/osal/common/TcpTmTcServer.h -0x2a01;IEC_NoConfigurationTable;No description;1;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a02;IEC_NoCpuTable;No description;2;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a03;IEC_InvalidWorkspaceAddress;No description;3;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a04;IEC_TooLittleWorkspace;No description;4;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a05;IEC_WorkspaceAllocation;No description;5;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a06;IEC_InterruptStackTooSmall;No description;6;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a07;IEC_ThreadExitted;No description;7;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a08;IEC_InconsistentMpInformation;No description;8;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a09;IEC_InvalidNode;No description;9;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a0a;IEC_NoMpci;No description;10;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a0b;IEC_BadPacket;No description;11;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a0c;IEC_OutOfPackets;No description;12;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a0d;IEC_OutOfGlobalObjects;No description;13;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a0e;IEC_OutOfProxies;No description;14;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a0f;IEC_InvalidGlobalId;No description;15;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a10;IEC_BadStackHook;No description;16;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a11;IEC_BadAttributes;No description;17;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a12;IEC_ImplementationKeyCreateInconsistency;No description;18;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a13;IEC_ImplementationBlockingOperationCancel;No description;19;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a14;IEC_MutexObtainFromBadState;No description;20;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a15;IEC_UnlimitedAndMaximumIs0;No description;21;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2600;FDI_YourFault;No description;0;HANDLES_FAILURES_IF;fsfw/src/fsfw/fdir/ConfirmsFailuresIF.h -0x2601;FDI_MyFault;No description;1;HANDLES_FAILURES_IF;fsfw/src/fsfw/fdir/ConfirmsFailuresIF.h -0x2602;FDI_ConfirmLater;No description;2;HANDLES_FAILURES_IF;fsfw/src/fsfw/fdir/ConfirmsFailuresIF.h -0x1e00;PUS_InvalidPusVersion;No description;0;PUS_IF;fsfw/src/fsfw/tmtcpacket/pus/PusIF.h -0x1e01;PUS_InvalidCrc16;No description;1;PUS_IF;fsfw/src/fsfw/tmtcpacket/pus/PusIF.h -0x0201;OM_InsertionFailed;No description;1;OBJECT_MANAGER_IF;fsfw/src/fsfw/objectmanager/ObjectManagerIF.h -0x0202;OM_NotFound;No description;2;OBJECT_MANAGER_IF;fsfw/src/fsfw/objectmanager/ObjectManagerIF.h -0x0203;OM_ChildInitFailed;No description;3;OBJECT_MANAGER_IF;fsfw/src/fsfw/objectmanager/ObjectManagerIF.h -0x0204;OM_InternalErrReporterUninit;No description;4;OBJECT_MANAGER_IF;fsfw/src/fsfw/objectmanager/ObjectManagerIF.h -0x2201;TMF_Busy;No description;1;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h -0x2202;TMF_LastPacketFound;No description;2;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h -0x2203;TMF_StopFetch;No description;3;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h -0x2204;TMF_Timeout;No description;4;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h -0x2205;TMF_TmChannelFull;No description;5;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h -0x2206;TMF_NotStored;No description;6;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h -0x2207;TMF_AllDeleted;No description;7;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h -0x2208;TMF_InvalidData;No description;8;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h -0x2209;TMF_NotReady;No description;9;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h -0x2101;TMB_Busy;No description;1;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x2102;TMB_Full;No description;2;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x2103;TMB_Empty;No description;3;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x2104;TMB_NullRequested;No description;4;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x2105;TMB_TooLarge;No description;5;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x2106;TMB_NotReady;No description;6;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x2107;TMB_DumpError;No description;7;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x2108;TMB_CrcError;No description;8;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x2109;TMB_Timeout;No description;9;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x210a;TMB_IdlePacketFound;No description;10;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x210b;TMB_TelecommandFound;No description;11;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x210c;TMB_NoPusATm;No description;12;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x210d;TMB_TooSmall;No description;13;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x210e;TMB_BlockNotFound;No description;14;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x210f;TMB_InvalidRequest;No description;15;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x2d01;PAW_UnknownDatatype;No description;1;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h -0x2d02;PAW_DatatypeMissmatch;No description;2;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h -0x2d03;PAW_Readonly;No description;3;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h -0x2d04;PAW_TooBig;No description;4;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h -0x2d05;PAW_SourceNotSet;No description;5;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h -0x2d06;PAW_OutOfBounds;No description;6;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h -0x2d07;PAW_NotSet;No description;7;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h -0x2d08;PAW_ColumnOrRowsZero;No description;8;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h -0x2e01;HPA_InvalidIdentifierId;No description;1;HAS_PARAMETERS_IF;fsfw/src/fsfw/parameters/HasParametersIF.h -0x2e02;HPA_InvalidDomainId;No description;2;HAS_PARAMETERS_IF;fsfw/src/fsfw/parameters/HasParametersIF.h -0x2e03;HPA_InvalidValue;No description;3;HAS_PARAMETERS_IF;fsfw/src/fsfw/parameters/HasParametersIF.h -0x2e05;HPA_ReadOnly;No description;5;HAS_PARAMETERS_IF;fsfw/src/fsfw/parameters/HasParametersIF.h -0x3b01;SPH_SemaphoreTimeout;No description;1;SEMAPHORE_IF;fsfw/src/fsfw/tasks/SemaphoreIF.h -0x3b02;SPH_SemaphoreNotOwned;No description;2;SEMAPHORE_IF;fsfw/src/fsfw/tasks/SemaphoreIF.h -0x3b03;SPH_SemaphoreInvalid;No description;3;SEMAPHORE_IF;fsfw/src/fsfw/tasks/SemaphoreIF.h +0x4300;FILS_GenericFileError;No description;0;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h +0x4301;FILS_GenericDirError;No description;1;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h +0x4302;FILS_FilesystemInactive;No description;2;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h +0x4303;FILS_GenericRenameError;No description;3;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h +0x4304;FILS_IsBusy;No description;4;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h +0x4305;FILS_InvalidParameters;No description;5;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h +0x430a;FILS_FileDoesNotExist;No description;10;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h +0x430b;FILS_FileAlreadyExists;No description;11;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h +0x430c;FILS_NotAFile;No description;12;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h +0x430d;FILS_FileLocked;No description;13;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h +0x430e;FILS_PermissionDenied;No description;14;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h +0x4315;FILS_DirectoryDoesNotExist;No description;21;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h +0x4316;FILS_DirectoryAlreadyExists;No description;22;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h +0x4317;FILS_NotADirectory;No description;23;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h +0x4318;FILS_DirectoryNotEmpty;No description;24;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h +0x431e;FILS_SequencePacketMissingWrite;No description;30;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h +0x431f;FILS_SequencePacketMissingRead;No description;31;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h 0x1a01;TRC_NotEnoughSensors;No description;1;TRIPLE_REDUNDACY_CHECK;fsfw/src/fsfw/monitoring/TriplexMonitor.h 0x1a02;TRC_LowestValueOol;No description;2;TRIPLE_REDUNDACY_CHECK;fsfw/src/fsfw/monitoring/TriplexMonitor.h 0x1a03;TRC_HighestValueOol;No description;3;TRIPLE_REDUNDACY_CHECK;fsfw/src/fsfw/monitoring/TriplexMonitor.h @@ -322,74 +394,36 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path 0x31e2;LIM_WrongPid;No description;226;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h 0x31e3;LIM_WrongLimitId;No description;227;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h 0x31ee;LIM_MonitorNotFound;No description;238;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h -0x3601;CFDP_InvalidTlvType;No description;1;CFDP;fsfw/src/fsfw/cfdp/definitions.h -0x3602;CFDP_InvalidDirectiveField;No description;2;CFDP;fsfw/src/fsfw/cfdp/definitions.h -0x3603;CFDP_InvalidPduDatafieldLen;No description;3;CFDP;fsfw/src/fsfw/cfdp/definitions.h -0x3604;CFDP_InvalidAckDirectiveFields;No description;4;CFDP;fsfw/src/fsfw/cfdp/definitions.h -0x3605;CFDP_MetadataCantParseOptions;No description;5;CFDP;fsfw/src/fsfw/cfdp/definitions.h -0x3606;CFDP_NakCantParseOptions;No description;6;CFDP;fsfw/src/fsfw/cfdp/definitions.h -0x3607;CFDP_FinishedCantParseFsResponses;No description;7;CFDP;fsfw/src/fsfw/cfdp/definitions.h -0x3608;CFDP_FilestoreRequiresSecondFile;No description;8;CFDP;fsfw/src/fsfw/cfdp/definitions.h -0x3609;CFDP_FilestoreResponseCantParseFsMessage;No description;9;CFDP;fsfw/src/fsfw/cfdp/definitions.h -0x360a;CFDP_InvalidPduFormat;No description;10;CFDP;fsfw/src/fsfw/cfdp/definitions.h -0x4300;FILS_GenericFileError;No description;0;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x4301;FILS_GenericDirError;No description;1;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x4302;FILS_FilesystemInactive;No description;2;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x4303;FILS_GenericRenameError;No description;3;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x4304;FILS_IsBusy;No description;4;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x4305;FILS_InvalidParameters;No description;5;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x430a;FILS_FileDoesNotExist;No description;10;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x430b;FILS_FileAlreadyExists;No description;11;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x430c;FILS_NotAFile;No description;12;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x430d;FILS_FileLocked;No description;13;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x430e;FILS_PermissionDenied;No description;14;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x4315;FILS_DirectoryDoesNotExist;No description;21;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x4316;FILS_DirectoryAlreadyExists;No description;22;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x4317;FILS_NotADirectory;No description;23;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x4318;FILS_DirectoryNotEmpty;No description;24;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x431e;FILS_SequencePacketMissingWrite;No description;30;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x431f;FILS_SequencePacketMissingRead;No description;31;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x2c01;CCS_BcIsSetVrCommand;No description;1;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2c02;CCS_BcIsUnlockCommand;No description;2;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2cb0;CCS_BcIllegalCommand;No description;176;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2cb1;CCS_BoardReadingNotFinished;No description;177;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2cf0;CCS_NsPositiveW;No description;240;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2cf1;CCS_NsNegativeW;No description;241;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2cf2;CCS_NsLockout;No description;242;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2cf3;CCS_FarmInLockout;No description;243;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2cf4;CCS_FarmInWait;No description;244;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2ce0;CCS_WrongSymbol;No description;224;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2ce1;CCS_DoubleStart;No description;225;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2ce2;CCS_StartSymbolMissed;No description;226;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2ce3;CCS_EndWithoutStart;No description;227;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2ce4;CCS_TooLarge;No description;228;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2ce5;CCS_TooShort;No description;229;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2ce6;CCS_WrongTfVersion;No description;230;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2ce7;CCS_WrongSpacecraftId;No description;231;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2ce8;CCS_NoValidFrameType;No description;232;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2ce9;CCS_CrcFailed;No description;233;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2cea;CCS_VcNotFound;No description;234;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2ceb;CCS_ForwardingFailed;No description;235;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2cec;CCS_ContentTooLarge;No description;236;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2ced;CCS_ResidualData;No description;237;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2cee;CCS_DataCorrupted;No description;238;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2cef;CCS_IllegalSegmentationFlag;No description;239;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2cd0;CCS_IllegalFlagCombination;No description;208;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2cd1;CCS_ShorterThanHeader;No description;209;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2cd2;CCS_TooShortBlockedPacket;No description;210;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2cd3;CCS_TooShortMapExtraction;No description;211;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x4201;PUS11_InvalidTypeTimeWindow;No description;1;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h 0x4202;PUS11_InvalidTimeWindow;No description;2;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h 0x4203;PUS11_TimeshiftingNotPossible;No description;3;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h 0x4204;PUS11_InvalidRelativeTime;No description;4;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h 0x4205;PUS11_ContainedTcTooSmall;No description;5;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h 0x4206;PUS11_ContainedTcCrcMissmatch;No description;6;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h -0x3401;DC_NoReplyReceived;No description;1;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h -0x3402;DC_ProtocolError;No description;2;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h -0x3403;DC_Nullpointer;No description;3;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h -0x3404;DC_InvalidCookieType;No description;4;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h -0x3405;DC_NotActive;No description;5;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h -0x3406;DC_TooMuchData;No description;6;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h +0x0601;PP_DoItMyself;No description;1;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x0602;PP_PointsToVariable;No description;2;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x0603;PP_PointsToMemory;No description;3;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x0604;PP_ActivityCompleted;No description;4;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x0605;PP_PointsToVectorUint8;No description;5;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x0606;PP_PointsToVectorUint16;No description;6;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x0607;PP_PointsToVectorUint32;No description;7;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x0608;PP_PointsToVectorFloat;No description;8;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x06a0;PP_DumpNotSupported;No description;160;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x06e0;PP_InvalidSize;No description;224;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x06e1;PP_InvalidAddress;No description;225;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x06e2;PP_InvalidContent;No description;226;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x06e3;PP_UnalignedAccess;No description;227;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x06e4;PP_WriteProtected;No description;228;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x13e0;MH_UnknownCmd;No description;224;MEMORY_HELPER;fsfw/src/fsfw/memory/MemoryHelper.h +0x13e1;MH_InvalidAddress;No description;225;MEMORY_HELPER;fsfw/src/fsfw/memory/MemoryHelper.h +0x13e2;MH_InvalidSize;No description;226;MEMORY_HELPER;fsfw/src/fsfw/memory/MemoryHelper.h +0x13e3;MH_StateMismatch;No description;227;MEMORY_HELPER;fsfw/src/fsfw/memory/MemoryHelper.h +0x1201;AB_NeedSecondStep;No description;1;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h +0x1202;AB_NeedToReconfigure;No description;2;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h +0x1203;AB_ModeFallback;No description;3;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h +0x1204;AB_ChildNotCommandable;No description;4;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h +0x1205;AB_NeedToChangeHealth;No description;5;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h +0x12a1;AB_NotEnoughChildrenInCorrectState;No description;161;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h 0x03a0;DHB_InvalidChannel;No description;160;DEVICE_HANDLER_BASE;fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h 0x03b0;DHB_AperiodicReply;No description;176;DEVICE_HANDLER_BASE;fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h 0x03b1;DHB_IgnoreReplyData;No description;177;DEVICE_HANDLER_BASE;fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h @@ -399,12 +433,12 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path 0x03d0;DHB_NoSwitch;No description;208;DEVICE_HANDLER_BASE;fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h 0x03e0;DHB_ChildTimeout;No description;224;DEVICE_HANDLER_BASE;fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h 0x03e1;DHB_SwitchFailed;No description;225;DEVICE_HANDLER_BASE;fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h -0x1201;AB_NeedSecondStep;No description;1;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h -0x1202;AB_NeedToReconfigure;No description;2;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h -0x1203;AB_ModeFallback;No description;3;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h -0x1204;AB_ChildNotCommandable;No description;4;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h -0x1205;AB_NeedToChangeHealth;No description;5;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h -0x12a1;AB_NotEnoughChildrenInCorrectState;No description;161;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h +0x3401;DC_NoReplyReceived;No description;1;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h +0x3402;DC_ProtocolError;No description;2;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h +0x3403;DC_Nullpointer;No description;3;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h +0x3404;DC_InvalidCookieType;No description;4;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h +0x3405;DC_NotActive;No description;5;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h +0x3406;DC_TooMuchData;No description;6;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h 0x27a0;DHI_NoCommandData;No description;160;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h 0x27a1;DHI_CommandNotSupported;No description;161;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h 0x27a2;DHI_CommandAlreadySent;No description;162;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h @@ -426,59 +460,28 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path 0x27c3;DHI_DeviceReplyInvalid;No description;195;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h 0x27d0;DHI_InvalidCommandParameter;No description;208;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h 0x27d1;DHI_InvalidNumberOrLengthOfParameters;No description;209;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h -0x2401;MT_TooDetailedRequest;No description;1;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h -0x2402;MT_TooGeneralRequest;No description;2;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h -0x2403;MT_NoMatch;No description;3;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h -0x2404;MT_Full;No description;4;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h -0x2405;MT_NewNodeCreated;No description;5;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h -0x3f01;DLEE_NoPacketFound;No description;1;DLE_ENCODER;fsfw/src/fsfw/globalfunctions/DleParser.h -0x3f02;DLEE_PossiblePacketLoss;No description;2;DLE_ENCODER;fsfw/src/fsfw/globalfunctions/DleParser.h -0x2f01;ASC_TooLongForTargetType;No description;1;ASCII_CONVERTER;fsfw/src/fsfw/globalfunctions/AsciiConverter.h -0x2f02;ASC_InvalidCharacters;No description;2;ASCII_CONVERTER;fsfw/src/fsfw/globalfunctions/AsciiConverter.h -0x2f03;ASC_BufferTooSmall;No description;3;ASCII_CONVERTER;fsfw/src/fsfw/globalfunctions/AsciiConverter.h -0x1701;HHI_ObjectNotHealthy;No description;1;HAS_HEALTH_IF;fsfw/src/fsfw/health/HasHealthIF.h -0x1702;HHI_InvalidHealthState;No description;2;HAS_HEALTH_IF;fsfw/src/fsfw/health/HasHealthIF.h -0x1703;HHI_IsExternallyControlled;No description;3;HAS_HEALTH_IF;fsfw/src/fsfw/health/HasHealthIF.h -0x3201;CF_ObjectHasNoFunctions;No description;1;COMMANDS_ACTIONS_IF;fsfw/src/fsfw/action/CommandsActionsIF.h -0x3202;CF_AlreadyCommanding;No description;2;COMMANDS_ACTIONS_IF;fsfw/src/fsfw/action/CommandsActionsIF.h -0x3301;HF_IsBusy;No description;1;HAS_ACTIONS_IF;fsfw/src/fsfw/action/HasActionsIF.h -0x3302;HF_InvalidParameters;No description;2;HAS_ACTIONS_IF;fsfw/src/fsfw/action/HasActionsIF.h -0x3303;HF_ExecutionFinished;No description;3;HAS_ACTIONS_IF;fsfw/src/fsfw/action/HasActionsIF.h -0x3304;HF_InvalidActionId;No description;4;HAS_ACTIONS_IF;fsfw/src/fsfw/action/HasActionsIF.h -0x1000;TIM_UnsupportedTimeFormat;No description;0;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h -0x1001;TIM_NotEnoughInformationForTargetFormat;No description;1;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h -0x1002;TIM_LengthMismatch;No description;2;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h -0x1003;TIM_InvalidTimeFormat;No description;3;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h -0x1004;TIM_InvalidDayOfYear;No description;4;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h -0x1005;TIM_TimeDoesNotFitFormat;No description;5;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h -0x3701;TSI_BadTimestamp;No description;1;TIME_STAMPER_IF;fsfw/src/fsfw/timemanager/TimeStampIF.h -0x3c00;LPIF_PoolEntryNotFound;No description;0;LOCAL_POOL_OWNER_IF;fsfw/src/fsfw/datapoollocal/localPoolDefinitions.h -0x3c01;LPIF_PoolEntryTypeConflict;No description;1;LOCAL_POOL_OWNER_IF;fsfw/src/fsfw/datapoollocal/localPoolDefinitions.h -0x3e00;HKM_QueueOrDestinationInvalid;No description;0;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h -0x3e01;HKM_WrongHkPacketType;No description;1;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h -0x3e02;HKM_ReportingStatusUnchanged;No description;2;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h -0x3e03;HKM_PeriodicHelperInvalid;No description;3;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h -0x3e04;HKM_PoolobjectNotFound;No description;4;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h -0x3e05;HKM_DatasetNotFound;No description;5;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h -0x2901;TC_InvalidTargetState;No description;1;THERMAL_COMPONENT_IF;fsfw/src/fsfw/thermal/ThermalComponentIF.h -0x29f1;TC_AboveOperationalLimit;No description;241;THERMAL_COMPONENT_IF;fsfw/src/fsfw/thermal/ThermalComponentIF.h -0x29f2;TC_BelowOperationalLimit;No description;242;THERMAL_COMPONENT_IF;fsfw/src/fsfw/thermal/ThermalComponentIF.h -0x2001;CSB_ExecutionComplete;No description;1;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h -0x2002;CSB_NoStepMessage;No description;2;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h -0x2003;CSB_ObjectBusy;No description;3;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h -0x2004;CSB_Busy;No description;4;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h -0x2005;CSB_InvalidTc;No description;5;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h -0x2006;CSB_InvalidObject;No description;6;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h -0x2007;CSB_InvalidReply;No description;7;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h -0x4c00;SPPA_NoPacketFound;No description;0;SPACE_PACKET_PARSER;fsfw/src/fsfw/tmtcservices/SpacePacketParser.h -0x4c01;SPPA_SplitPacket;No description;1;SPACE_PACKET_PARSER;fsfw/src/fsfw/tmtcservices/SpacePacketParser.h -0x1d01;ATC_ActivityStarted;No description;1;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h -0x1d02;ATC_InvalidSubservice;No description;2;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h -0x1d03;ATC_IllegalApplicationData;No description;3;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h -0x1d04;ATC_SendTmFailed;No description;4;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h -0x1d05;ATC_Timeout;No description;5;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h -0x7300;SCBU_KeyNotFound;No description;0;SCRATCH_BUFFER;bsp_q7s/memory/scratchApi.h -0x6f00;LPH_SdNotReady;No description;0;LOCAL_PARAM_HANDLER;bsp_q7s/memory/LocalParameterHandler.h +0x1401;SE_BufferTooShort;No description;1;SERIALIZE_IF;fsfw/src/fsfw/serialize/SerializeIF.h +0x1402;SE_StreamTooShort;No description;2;SERIALIZE_IF;fsfw/src/fsfw/serialize/SerializeIF.h +0x1403;SE_TooManyElements;No description;3;SERIALIZE_IF;fsfw/src/fsfw/serialize/SerializeIF.h +0x4500;HSPI_HalTimeoutRetval;No description;0;HAL_SPI;fsfw/src/fsfw_hal/stm32h7/spi/spiDefinitions.h +0x4501;HSPI_HalBusyRetval;No description;1;HAL_SPI;fsfw/src/fsfw_hal/stm32h7/spi/spiDefinitions.h +0x4502;HSPI_HalErrorRetval;No description;2;HAL_SPI;fsfw/src/fsfw_hal/stm32h7/spi/spiDefinitions.h +0x4601;HURT_UartReadFailure;No description;1;HAL_UART;fsfw/src/fsfw_hal/linux/serial/SerialComIF.h +0x4602;HURT_UartReadSizeMissmatch;No description;2;HAL_UART;fsfw/src/fsfw_hal/linux/serial/SerialComIF.h +0x4603;HURT_UartRxBufferTooSmall;No description;3;HAL_UART;fsfw/src/fsfw_hal/linux/serial/SerialComIF.h +0x4801;HGIO_UnknownGpioId;No description;1;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h +0x4802;HGIO_DriveGpioFailure;No description;2;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h +0x4803;HGIO_GpioTypeFailure;No description;3;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h +0x4804;HGIO_GpioInvalidInstance;No description;4;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h +0x4805;HGIO_GpioDuplicateDetected;No description;5;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h +0x4806;HGIO_GpioInitFailed;No description;6;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h +0x4807;HGIO_GpioGetValueFailed;No description;7;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h +0x4400;UXOS_ExecutionFinished;Execution of the current command has finished;0;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h +0x4401;UXOS_CommandPending;Command is pending. This will also be returned if the user tries to load another command but a command is still pending;1;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h +0x4402;UXOS_BytesRead;Some bytes have been read from the executing process;2;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h +0x4403;UXOS_CommandError;Command execution failed;3;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h +0x4404;UXOS_NoCommandLoadedOrPending;;4;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h +0x4406;UXOS_PcloseCallError;No description;6;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h 0x64a0;FSHLP_SdNotMounted;SD card specified with path string not mounted;160;FILE_SYSTEM_HELPER;bsp_q7s/fs/FilesystemHelper.h 0x64a1;FSHLP_FileNotExists;Specified file does not exist on filesystem;161;FILE_SYSTEM_HELPER;bsp_q7s/fs/FilesystemHelper.h 0x6e00;SDMA_OpOngoing;No description;0;SD_CARD_MANAGER;bsp_q7s/fs/SdCardManager.h @@ -491,9 +494,8 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path 0x6e0d;SDMA_UnmountError;No description;13;SD_CARD_MANAGER;bsp_q7s/fs/SdCardManager.h 0x6e0e;SDMA_SystemCallError;No description;14;SD_CARD_MANAGER;bsp_q7s/fs/SdCardManager.h 0x6e0f;SDMA_PopenCallError;No description;15;SD_CARD_MANAGER;bsp_q7s/fs/SdCardManager.h -0x65a0;PLMPHLP_FileClosedAccidentally;File accidentally close;160;PLOC_MPSOC_HELPER;linux/devices/ploc/PlocMPSoCHelper.h -0x5ea0;PLMEMDUMP_MramAddressTooHigh;The capacity of the MRAM amounts to 512 kB. Thus the maximum address must not be higher than 0x7d000.;160;PLOC_MEMORY_DUMPER;linux/devices/ploc/PlocMemoryDumper.h -0x5ea1;PLMEMDUMP_MramInvalidAddressCombination;The specified end address is lower than the start address;161;PLOC_MEMORY_DUMPER;linux/devices/ploc/PlocMemoryDumper.h +0x6f00;LPH_SdNotReady;No description;0;LOCAL_PARAM_HANDLER;bsp_q7s/memory/LocalParameterHandler.h +0x7300;SCBU_KeyNotFound;No description;0;SCRATCH_BUFFER;bsp_q7s/memory/scratchApi.h 0x57a0;PLSPVhLP_FileClosedAccidentally;File accidentally close;160;PLOC_SUPV_HELPER;linux/devices/ploc/PlocSupvUartMan.h 0x57a1;PLSPVhLP_ProcessTerminated;Process has been terminated by command;161;PLOC_SUPV_HELPER;linux/devices/ploc/PlocSupvUartMan.h 0x57a2;PLSPVhLP_PathNotExists;Received command with invalid pathname;162;PLOC_SUPV_HELPER;linux/devices/ploc/PlocSupvUartMan.h @@ -504,16 +506,46 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path 0x5703;PLSPVhLP_PossiblePacketLossConsecutiveStart;No description;3;PLOC_SUPV_HELPER;linux/devices/ploc/PlocSupvUartMan.h 0x5704;PLSPVhLP_PossiblePacketLossConsecutiveEnd;No description;4;PLOC_SUPV_HELPER;linux/devices/ploc/PlocSupvUartMan.h 0x5705;PLSPVhLP_HdlcError;No description;5;PLOC_SUPV_HELPER;linux/devices/ploc/PlocSupvUartMan.h -0x67a0;MPSOCRTVIF_CrcFailure;Space Packet received from PLOC has invalid CRC;160;MPSOC_RETURN_VALUES_IF;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h -0x67a1;MPSOCRTVIF_ReceivedAckFailure;Received ACK failure reply from PLOC;161;MPSOC_RETURN_VALUES_IF;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h -0x67a2;MPSOCRTVIF_ReceivedExeFailure;Received execution failure reply from PLOC;162;MPSOC_RETURN_VALUES_IF;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h -0x67a3;MPSOCRTVIF_InvalidApid;Received space packet with invalid APID from PLOC;163;MPSOC_RETURN_VALUES_IF;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h -0x67a4;MPSOCRTVIF_InvalidLength;Received command with invalid length;164;MPSOC_RETURN_VALUES_IF;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h -0x67a5;MPSOCRTVIF_FilenameTooLong;Filename of file in OBC filesystem is too long;165;MPSOC_RETURN_VALUES_IF;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h -0x67a6;MPSOCRTVIF_MpsocHelperExecuting;MPSoC helper is currently executing a command;166;MPSOC_RETURN_VALUES_IF;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h -0x67a7;MPSOCRTVIF_MpsocFilenameTooLong;Filename of MPSoC file is to long (max. 256 bytes);167;MPSOC_RETURN_VALUES_IF;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h -0x67a8;MPSOCRTVIF_InvalidParameter;Command has invalid parameter;168;MPSOC_RETURN_VALUES_IF;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h -0x67a9;MPSOCRTVIF_NameTooLong;Received command has file string with invalid length;169;MPSOC_RETURN_VALUES_IF;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h +0x65a0;PLMPHLP_FileClosedAccidentally;File accidentally close;160;PLOC_MPSOC_HELPER;linux/devices/ploc/PlocMPSoCHelper.h +0x5ea0;PLMEMDUMP_MramAddressTooHigh;The capacity of the MRAM amounts to 512 kB. Thus the maximum address must not be higher than 0x7d000.;160;PLOC_MEMORY_DUMPER;linux/devices/ploc/PlocMemoryDumper.h +0x5ea1;PLMEMDUMP_MramInvalidAddressCombination;The specified end address is lower than the start address;161;PLOC_MEMORY_DUMPER;linux/devices/ploc/PlocMemoryDumper.h +0x53a0;STRH_TemperatureReqFailed;Status in temperature reply signals error;160;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h +0x53a1;STRH_PingFailed;Ping command failed;161;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h +0x53a2;STRH_VersionReqFailed;Status in version reply signals error;162;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h +0x6201;JSONBASE_JsonFileNotExists;Specified json file does not exist;1;ARCSEC_JSON_BASE;linux/devices/startracker/ArcsecJsonParamBase.h +0x6202;JSONBASE_SetNotExists;Requested set does not exist in json file;2;ARCSEC_JSON_BASE;linux/devices/startracker/ArcsecJsonParamBase.h +0x6203;JSONBASE_ParamNotExists;Requested parameter does not exist in json file;3;ARCSEC_JSON_BASE;linux/devices/startracker/ArcsecJsonParamBase.h +0x53a3;STRH_InterfaceReqFailed;Status in interface reply signals error;163;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h +0x53a4;STRH_PowerReqFailed;Status in power reply signals error;164;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h +0x53a5;STRH_SetParamFailed;Status of reply to parameter set command signals error;165;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h +0x53a6;STRH_ActionFailed;Status of reply to action command signals error;166;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h +0x53a7;STRH_FilePathTooLong;Received invalid path string. Exceeds allowed length;167;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h +0x53a8;STRH_FilenameTooLong;Name of file received with command is too long;168;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h +0x53a9;STRH_InvalidProgram;Received version reply with invalid program ID;169;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h +0x53aa;STRH_ReplyError;Status field reply signals error;170;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h +0x53ab;STRH_CommandTooShort;Received command which is too short (some data is missing for proper execution);171;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h +0x53ac;STRH_InvalidLength;Received command with invalid length (too few or too many parameters);172;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h +0x53ad;STRH_RegionMismatch;Region mismatch between send and received data;173;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h +0x53ae;STRH_AddressMismatch;Address mismatch between send and received data;174;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h +0x53af;STRH_LengthMismatch;Length field mismatch between send and received data;175;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h +0x53b0;STRH_FileNotExists;Specified file does not exist;176;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h +0x53b1;STRH_InvalidType;Download blob pixel command has invalid type field;177;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h +0x53b2;STRH_InvalidId;Received FPGA action command with invalid ID;178;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h +0x53b3;STRH_ReplyTooShort;Received reply is too short;179;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h +0x53b4;STRH_CrcFailure;Received reply with invalid CRC;180;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h +0x53b5;STRH_StrHelperExecuting;Star tracker handler currently executing a command and using the communication interface;181;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h +0x53b6;STRH_StartrackerAlreadyBooted;Star tracker is already in firmware mode;182;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h +0x53b7;STRH_StartrackerRunningFirmware;Star tracker is in firmware mode but must be in bootloader mode to execute this command;183;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h +0x53b8;STRH_StartrackerRunningBootloader;Star tracker is in bootloader mode but must be in firmware mode to execute this command;184;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h +0x5ca0;STRHLP_SdNotMounted;SD card specified in path string not mounted;160;STR_HELPER;linux/devices/startracker/StrHelper.h +0x5ca1;STRHLP_FileNotExists;Specified file does not exist on filesystem;161;STR_HELPER;linux/devices/startracker/StrHelper.h +0x5ca2;STRHLP_PathNotExists;Specified path does not exist;162;STR_HELPER;linux/devices/startracker/StrHelper.h +0x5ca3;STRHLP_FileCreationFailed;Failed to create download image or read flash file;163;STR_HELPER;linux/devices/startracker/StrHelper.h +0x5ca4;STRHLP_RegionMismatch;Region in flash write/read reply does not match expected region;164;STR_HELPER;linux/devices/startracker/StrHelper.h +0x5ca5;STRHLP_AddressMismatch;Address in flash write/read reply does not match expected address;165;STR_HELPER;linux/devices/startracker/StrHelper.h +0x5ca6;STRHLP_LengthMismatch;Length in flash write/read reply does not match expected length;166;STR_HELPER;linux/devices/startracker/StrHelper.h +0x5ca7;STRHLP_StatusError;Status field in reply signals error;167;STR_HELPER;linux/devices/startracker/StrHelper.h +0x5ca8;STRHLP_InvalidTypeId;Reply has invalid type ID (should be of action reply type);168;STR_HELPER;linux/devices/startracker/StrHelper.h 0x68a0;SPVRTVIF_CrcFailure;Space Packet received from PLOC supervisor has invalid CRC;160;SUPV_RETURN_VALUES_IF;linux/devices/devicedefinitions/PlocSupervisorDefinitions.h 0x68a1;SPVRTVIF_InvalidServiceId;No description;161;SUPV_RETURN_VALUES_IF;linux/devices/devicedefinitions/PlocSupervisorDefinitions.h 0x68a2;SPVRTVIF_ReceivedAckFailure;Received ACK failure reply from PLOC supervisor;162;SUPV_RETURN_VALUES_IF;linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -538,47 +570,21 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path 0x68b5;SPVRTVIF_SupvHelperExecuting;Supervisor helper task ist currently executing a command (wait until helper tas has finished or interrupt by sending the terminate command);181;SUPV_RETURN_VALUES_IF;linux/devices/devicedefinitions/PlocSupervisorDefinitions.h 0x68c0;SPVRTVIF_BufTooSmall;No description;192;SUPV_RETURN_VALUES_IF;linux/devices/devicedefinitions/PlocSupervisorDefinitions.h 0x68c1;SPVRTVIF_NoReplyTimeout;No description;193;SUPV_RETURN_VALUES_IF;linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +0x67a0;MPSOCRTVIF_CrcFailure;Space Packet received from PLOC has invalid CRC;160;MPSOC_RETURN_VALUES_IF;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h +0x67a1;MPSOCRTVIF_ReceivedAckFailure;Received ACK failure reply from PLOC;161;MPSOC_RETURN_VALUES_IF;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h +0x67a2;MPSOCRTVIF_ReceivedExeFailure;Received execution failure reply from PLOC;162;MPSOC_RETURN_VALUES_IF;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h +0x67a3;MPSOCRTVIF_InvalidApid;Received space packet with invalid APID from PLOC;163;MPSOC_RETURN_VALUES_IF;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h +0x67a4;MPSOCRTVIF_InvalidLength;Received command with invalid length;164;MPSOC_RETURN_VALUES_IF;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h +0x67a5;MPSOCRTVIF_FilenameTooLong;Filename of file in OBC filesystem is too long;165;MPSOC_RETURN_VALUES_IF;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h +0x67a6;MPSOCRTVIF_MpsocHelperExecuting;MPSoC helper is currently executing a command;166;MPSOC_RETURN_VALUES_IF;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h +0x67a7;MPSOCRTVIF_MpsocFilenameTooLong;Filename of MPSoC file is to long (max. 256 bytes);167;MPSOC_RETURN_VALUES_IF;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h +0x67a8;MPSOCRTVIF_InvalidParameter;Command has invalid parameter;168;MPSOC_RETURN_VALUES_IF;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h +0x67a9;MPSOCRTVIF_NameTooLong;Received command has file string with invalid length;169;MPSOC_RETURN_VALUES_IF;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h 0x54e0;DWLPWRON_InvalidMode;Received command has invalid JESD mode (valid modes are 0 - 5);224;DWLPWRON_CMD;linux/devices/devicedefinitions/PlocMPSoCDefinitions.h 0x54e1;DWLPWRON_InvalidLaneRate;Received command has invalid lane rate (valid lane rate are 0 - 9);225;DWLPWRON_CMD;linux/devices/devicedefinitions/PlocMPSoCDefinitions.h -0x6201;JSONBASE_JsonFileNotExists;Specified json file does not exist;1;ARCSEC_JSON_BASE;linux/devices/startracker/ArcsecJsonParamBase.h -0x6202;JSONBASE_SetNotExists;Requested set does not exist in json file;2;ARCSEC_JSON_BASE;linux/devices/startracker/ArcsecJsonParamBase.h -0x6203;JSONBASE_ParamNotExists;Requested parameter does not exist in json file;3;ARCSEC_JSON_BASE;linux/devices/startracker/ArcsecJsonParamBase.h -0x53a0;STRH_TemperatureReqFailed;Status in temperature reply signals error;160;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h -0x53a1;STRH_PingFailed;Ping command failed;161;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h -0x53a2;STRH_VersionReqFailed;Status in version reply signals error;162;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h -0x5ca0;STRHLP_SdNotMounted;SD card specified in path string not mounted;160;STR_HELPER;linux/devices/startracker/StrHelper.h -0x5ca1;STRHLP_FileNotExists;Specified file does not exist on filesystem;161;STR_HELPER;linux/devices/startracker/StrHelper.h -0x5ca2;STRHLP_PathNotExists;Specified path does not exist;162;STR_HELPER;linux/devices/startracker/StrHelper.h -0x5ca3;STRHLP_FileCreationFailed;Failed to create download image or read flash file;163;STR_HELPER;linux/devices/startracker/StrHelper.h -0x5ca4;STRHLP_RegionMismatch;Region in flash write/read reply does not match expected region;164;STR_HELPER;linux/devices/startracker/StrHelper.h -0x5ca5;STRHLP_AddressMismatch;Address in flash write/read reply does not match expected address;165;STR_HELPER;linux/devices/startracker/StrHelper.h -0x5ca6;STRHLP_LengthMismatch;Length in flash write/read reply does not match expected length;166;STR_HELPER;linux/devices/startracker/StrHelper.h -0x5ca7;STRHLP_StatusError;Status field in reply signals error;167;STR_HELPER;linux/devices/startracker/StrHelper.h -0x5ca8;STRHLP_InvalidTypeId;Reply has invalid type ID (should be of action reply type);168;STR_HELPER;linux/devices/startracker/StrHelper.h -0x53a3;STRH_InterfaceReqFailed;Status in interface reply signals error;163;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h -0x53a4;STRH_PowerReqFailed;Status in power reply signals error;164;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h -0x53a5;STRH_SetParamFailed;Status of reply to parameter set command signals error;165;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h -0x53a6;STRH_ActionFailed;Status of reply to action command signals error;166;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h -0x53a7;STRH_FilePathTooLong;Received invalid path string. Exceeds allowed length;167;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h -0x53a8;STRH_FilenameTooLong;Name of file received with command is too long;168;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h -0x53a9;STRH_InvalidProgram;Received version reply with invalid program ID;169;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h -0x53aa;STRH_ReplyError;Status field reply signals error;170;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h -0x53ab;STRH_CommandTooShort;Received command which is too short (some data is missing for proper execution);171;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h -0x53ac;STRH_InvalidLength;Received command with invalid length (too few or too many parameters);172;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h -0x53ad;STRH_RegionMismatch;Region mismatch between send and received data;173;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h -0x53ae;STRH_AddressMismatch;Address mismatch between send and received data;174;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h -0x53af;STRH_LengthMismatch;Length field mismatch between send and received data;175;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h -0x53b0;STRH_FileNotExists;Specified file does not exist;176;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h -0x53b1;STRH_InvalidType;Download blob pixel command has invalid type field;177;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h -0x53b2;STRH_InvalidId;Received FPGA action command with invalid ID;178;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h -0x53b3;STRH_ReplyTooShort;Received reply is too short;179;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h -0x53b4;STRH_CrcFailure;Received reply with invalid CRC;180;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h -0x53b5;STRH_StrHelperExecuting;Star tracker handler currently executing a command and using the communication interface;181;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h -0x53b6;STRH_StartrackerAlreadyBooted;Star tracker is already in firmware mode;182;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h -0x53b7;STRH_StartrackerRunningFirmware;Star tracker is in firmware mode but must be in bootloader mode to execute this command;183;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h -0x53b8;STRH_StartrackerRunningBootloader;Star tracker is in bootloader mode but must be in firmware mode to execute this command;184;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h -0x5300;STRH_NoReplyAvailable;No description;0;STR_HANDLER;linux/devices/ImtqPollingTask.h -0x5302;STRH_InvalidCrc;No description;2;STR_HANDLER;linux/devices/ScexHelper.h +0x5400;DWLPWRON_NoReplyAvailable;No description;0;DWLPWRON_CMD;linux/devices/ImtqPollingTask.h +0x5402;DWLPWRON_InvalidCrc;No description;2;DWLPWRON_CMD;linux/devices/ScexHelper.h +0x59a0;IPCI_PapbBusy;No description;160;CCSDS_IP_CORE_BRIDGE;linux/ipcore/PapbVcInterface.h 0x5aa0;PTME_UnknownVcId;No description;160;PTME;linux/ipcore/Ptme.h 0x5fa0;PDEC_AbandonedCltuRetval;No description;160;PDEC_HANDLER;linux/ipcore/PdecHandler.h 0x5fa1;PDEC_FrameDirtyRetval;No description;161;PDEC_HANDLER;linux/ipcore/PdecHandler.h @@ -599,4 +605,3 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path 0x61a1;RS_BadBitRate;Bad bitrate has been commanded (e.g. 0);161;RATE_SETTER;linux/ipcore/PtmeConfig.h 0x61a2;RS_ClkInversionFailed;Failed to invert clock and thus change the time the data is updated with respect to the tx clock;162;RATE_SETTER;linux/ipcore/PtmeConfig.h 0x61a3;RS_TxManipulatorConfigFailed;Failed to change configuration bit of tx clock manipulator;163;RATE_SETTER;linux/ipcore/PtmeConfig.h -0x59a0;IPCI_PapbBusy;No description;160;CCSDS_IP_CORE_BRIDGE;linux/ipcore/PapbVcInterface.h diff --git a/generators/events/translateEvents.cpp b/generators/events/translateEvents.cpp index b48b3958..94d829fe 100644 --- a/generators/events/translateEvents.cpp +++ b/generators/events/translateEvents.cpp @@ -1,7 +1,7 @@ /** * @brief Auto-generated event translation file. Contains 277 translations. * @details - * Generated on: 2023-03-10 21:01:11 + * Generated on: 2023-03-11 15:01:05 */ #include "translateEvents.h" diff --git a/generators/objects/translateObjects.cpp b/generators/objects/translateObjects.cpp index 5e772262..212322bc 100644 --- a/generators/objects/translateObjects.cpp +++ b/generators/objects/translateObjects.cpp @@ -2,7 +2,7 @@ * @brief Auto-generated object translation file. * @details * Contains 173 translations. - * Generated on: 2023-03-10 21:01:11 + * Generated on: 2023-03-11 15:01:05 */ #include "translateObjects.h" diff --git a/linux/fsfwconfig/events/translateEvents.cpp b/linux/fsfwconfig/events/translateEvents.cpp index b48b3958..94d829fe 100644 --- a/linux/fsfwconfig/events/translateEvents.cpp +++ b/linux/fsfwconfig/events/translateEvents.cpp @@ -1,7 +1,7 @@ /** * @brief Auto-generated event translation file. Contains 277 translations. * @details - * Generated on: 2023-03-10 21:01:11 + * Generated on: 2023-03-11 15:01:05 */ #include "translateEvents.h" diff --git a/linux/fsfwconfig/objects/translateObjects.cpp b/linux/fsfwconfig/objects/translateObjects.cpp index 5e772262..212322bc 100644 --- a/linux/fsfwconfig/objects/translateObjects.cpp +++ b/linux/fsfwconfig/objects/translateObjects.cpp @@ -2,7 +2,7 @@ * @brief Auto-generated object translation file. * @details * Contains 173 translations. - * Generated on: 2023-03-10 21:01:11 + * Generated on: 2023-03-11 15:01:05 */ #include "translateObjects.h" diff --git a/tmtc b/tmtc index 4686550e..f4e90914 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 4686550eb9455175227559dc36902469255e36b7 +Subproject commit f4e9091484cd76db03aee00d39579ef13a92f3d3 From 7fd2fbc4816515456cb40cb37c0a6d91e19b6a45 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Sat, 11 Mar 2023 15:09:31 +0100 Subject: [PATCH 107/112] prep v1.37.0 --- CHANGELOG.md | 4 ++++ CMakeLists.txt | 2 +- tmtc | 2 +- 3 files changed, 6 insertions(+), 2 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index dbe2bc50..ad8e5e37 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -16,6 +16,10 @@ will consitute of a breaking change warranting a new major release: # [unreleased] +# [v1.37.0] 2023-03-11 + +eive-tmtc: v2.18.0 + ## Added - `SensorProcessing` now includes an FDIR for GPS altitude. If the measured GPS altitude is out diff --git a/CMakeLists.txt b/CMakeLists.txt index 7cd09271..cb5b5b28 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -10,7 +10,7 @@ cmake_minimum_required(VERSION 3.13) set(OBSW_VERSION_MAJOR 1) -set(OBSW_VERSION_MINOR 36) +set(OBSW_VERSION_MINOR 37) set(OBSW_VERSION_REVISION 0) # set(CMAKE_VERBOSE TRUE) diff --git a/tmtc b/tmtc index f4e90914..65ada579 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit f4e9091484cd76db03aee00d39579ef13a92f3d3 +Subproject commit 65ada579d3b3e4ef37538941e41275f1da8ee76b From eb861c9f01660898ee53b3f2423dc81302fd94af Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Sat, 11 Mar 2023 15:24:43 +0100 Subject: [PATCH 108/112] bump eive-tmtc to v2.18.1 --- CHANGELOG.md | 2 +- mission/tmtc/PersistentLogTmStoreTask.cpp | 3 ++- tmtc | 2 +- 3 files changed, 4 insertions(+), 3 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index ad8e5e37..69d8cf6a 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -18,7 +18,7 @@ will consitute of a breaking change warranting a new major release: # [v1.37.0] 2023-03-11 -eive-tmtc: v2.18.0 +eive-tmtc: v2.18.1 ## Added diff --git a/mission/tmtc/PersistentLogTmStoreTask.cpp b/mission/tmtc/PersistentLogTmStoreTask.cpp index aac51c55..dc17ec58 100644 --- a/mission/tmtc/PersistentLogTmStoreTask.cpp +++ b/mission/tmtc/PersistentLogTmStoreTask.cpp @@ -6,7 +6,8 @@ PersistentLogTmStoreTask::PersistentLogTmStoreTask(object_id_t objectId, StorageManagerIF& ipcStore, LogStores stores, VirtualChannel& channel, SdCardMountedIF& sdcMan) - : TmStoreTaskBase(objectId, ipcStore, channel, sdcMan), stores(stores), + : TmStoreTaskBase(objectId, ipcStore, channel, sdcMan), + stores(stores), okStoreContext(persTmStore::DUMP_OK_STORE_DONE), notOkStoreContext(persTmStore::DUMP_NOK_STORE_DONE), miscStoreContext(persTmStore::DUMP_MISC_STORE_DONE) {} diff --git a/tmtc b/tmtc index 65ada579..a40c881b 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 65ada579d3b3e4ef37538941e41275f1da8ee76b +Subproject commit a40c881b9fc292fe598204280db38720a784b71f From a83136515c9614e082166aeb252e1bab96b1132f Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Sun, 12 Mar 2023 20:51:33 +0100 Subject: [PATCH 109/112] command to execute shell command --- CHANGELOG.md | 4 ++++ bsp_q7s/core/CoreController.cpp | 31 ++++++++++++++++++++++++++++++- bsp_q7s/core/CoreController.h | 11 +++++++++++ fsfw | 2 +- 4 files changed, 46 insertions(+), 2 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 69d8cf6a..3606d6eb 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -16,6 +16,10 @@ will consitute of a breaking change warranting a new major release: # [unreleased] +## Added + +- Added `EXECUTE_SHELL_CMD` action command for `CoreController` to execute arbitrary Linux commands. + # [v1.37.0] 2023-03-11 eive-tmtc: v2.18.1 diff --git a/bsp_q7s/core/CoreController.cpp b/bsp_q7s/core/CoreController.cpp index 5c4710d4..702264ab 100644 --- a/bsp_q7s/core/CoreController.cpp +++ b/bsp_q7s/core/CoreController.cpp @@ -32,7 +32,9 @@ xsc::Chip CoreController::CURRENT_CHIP = xsc::Chip::NO_CHIP; xsc::Copy CoreController::CURRENT_COPY = xsc::Copy::NO_COPY; CoreController::CoreController(object_id_t objectId) - : ExtendedControllerBase(objectId, 5), opDivider5(5), opDivider10(10), hkSet(this) { + : ExtendedControllerBase(objectId, 5), cmdExecutor(4096), cmdReplyBuf(4096, true), cmdRepliesSizes(128), + opDivider5(5), opDivider10(10), hkSet(this) { + cmdExecutor.setRingBuffer(&cmdReplyBuf, &cmdRepliesSizes); try { sdcMan = SdCardManager::instance(); if (sdcMan == nullptr) { @@ -100,6 +102,19 @@ void CoreController::performControlOperation() { sdStateMachine(); performMountedSdCardOperations(); readHkData(); + if(shellCmdIsExecuting) { + bool replyReceived = false; + // TODO: We could read the data in the ring buffer and send it as an action data reply. + if(cmdExecutor.check(replyReceived) == CommandExecutor::EXECUTION_FINISHED) { + actionHelper.finish(true, successRecipient, EXECUTE_SHELL_CMD); + shellCmdIsExecuting = false; + cmdReplyBuf.clear(); + while(not cmdRepliesSizes.empty()) { + cmdRepliesSizes.pop(); + } + successRecipient = MessageQueueIF::NO_QUEUE; + } + } opDivider5.checkAndIncrement(); opDivider10.checkAndIncrement(); } @@ -301,6 +316,20 @@ ReturnValue_t CoreController::executeAction(ActionId_t actionId, MessageQueueId_ // Warning: This function will never return, because it reboots the system return actionReboot(data, size); } + case(EXECUTE_SHELL_CMD): { + std::string cmd = std::string(cmd, size); + if(cmdExecutor.getCurrentState() == CommandExecutor::States::PENDING or shellCmdIsExecuting) { + return HasActionsIF::IS_BUSY; + } + cmdExecutor.load(cmd, false, false); + ReturnValue_t result = cmdExecutor.execute(); + if(result != returnvalue::OK) { + return result; + } + shellCmdIsExecuting = true; + successRecipient = commandedBy; + return returnvalue::OK; + } default: { return HasActionsIF::INVALID_ACTION_ID; } diff --git a/bsp_q7s/core/CoreController.h b/bsp_q7s/core/CoreController.h index c5e23d48..fa07ec59 100644 --- a/bsp_q7s/core/CoreController.h +++ b/bsp_q7s/core/CoreController.h @@ -1,6 +1,8 @@ #ifndef BSP_Q7S_CORE_CORECONTROLLER_H_ #define BSP_Q7S_CORE_CORECONTROLLER_H_ +#include +#include #include #include @@ -98,6 +100,8 @@ class CoreController : public ExtendedControllerBase { //! Reboot using the reboot command static constexpr ActionId_t REBOOT_OBC = 34; + static constexpr ActionId_t EXECUTE_SHELL_CMD = 40; + static constexpr uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::CORE; static constexpr Event ALLOC_FAILURE = event::makeEvent(SUBSYSTEM_ID, 0, severity::MEDIUM); @@ -227,6 +231,13 @@ class CoreController : public ExtendedControllerBase { } sdCommandingInfo; RebootFile rebootFile = {}; + + CommandExecutor cmdExecutor; + SimpleRingBuffer cmdReplyBuf; + DynamicFIFO cmdRepliesSizes; + bool shellCmdIsExecuting = false; + MessageQueueId_t successRecipient = MessageQueueIF::NO_QUEUE; + std::string currMntPrefix; bool timeFileInitDone = false; bool performOneShotSdCardOpsSwitch = false; diff --git a/fsfw b/fsfw index 4d6f6e6b..9a8d775e 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit 4d6f6e6b23b5c0486dad6be8abba7681114a05fe +Subproject commit 9a8d775eb1a8788ad844215bf2a42d9f707767c0 From eb66d7585c68068848bf626ae987bada1cb7adb2 Mon Sep 17 00:00:00 2001 From: meggert Date: Mon, 13 Mar 2023 10:01:08 +0100 Subject: [PATCH 110/112] fixed ptgCtrl after acs submode to mode changes --- mission/controller/AcsController.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/mission/controller/AcsController.cpp b/mission/controller/AcsController.cpp index 8d1bd369..b4e7c5d3 100644 --- a/mission/controller/AcsController.cpp +++ b/mission/controller/AcsController.cpp @@ -304,7 +304,7 @@ void AcsController::performPointingCtrl() { // Variables required for setting actuators double torquePtgRws[4] = {0, 0, 0, 0}, rwTrqNs[4] = {0, 0, 0, 0}, torqueRws[4] = {0, 0, 0, 0}, mgtDpDes[3] = {0, 0, 0}; - switch (submode) { + switch (mode) { case acs::PTG_IDLE: guidance.targetQuatPtgSun(susDataProcessed.sunIjkModel.value, targetQuat, targetSatRotRate); guidance.comparePtg(mekfData.quatMekf.value, mekfData.satRotRateMekf.value, targetQuat, @@ -416,6 +416,9 @@ void AcsController::performPointingCtrl() { &(sensorValues.rw3Set.currSpeed.value), &(sensorValues.rw4Set.currSpeed.value), mgtDpDes); enableAntiStiction = acsParameters.inertialModeControllerParameters.enableAntiStiction; break; + default: + sif::error << "AcsController: Invalid mode for performPointingCtrl"; + break; } actuatorCmd.cmdSpeedToRws( From b1fa3fd01636210a38f54feef44dcf9feebe2d26 Mon Sep 17 00:00:00 2001 From: meggert Date: Mon, 13 Mar 2023 10:03:40 +0100 Subject: [PATCH 111/112] fixed max speed limitation done before calculation to right unit scale --- mission/controller/acs/ActuatorCmd.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/mission/controller/acs/ActuatorCmd.cpp b/mission/controller/acs/ActuatorCmd.cpp index f32ce241..457cacce 100644 --- a/mission/controller/acs/ActuatorCmd.cpp +++ b/mission/controller/acs/ActuatorCmd.cpp @@ -42,14 +42,14 @@ void ActuatorCmd::cmdSpeedToRws(int32_t speedRw0, int32_t speedRw1, int32_t spee deltaSpeedInt[i] = std::round(deltaSpeed[i]); } VectorOperations::add(speedRws, deltaSpeedInt, rwCmdSpeed, 4); + VectorOperations::mulScalar(rwCmdSpeed, 10, rwCmdSpeed, 4); for (uint8_t i = 0; i < 4; i++) { if (rwCmdSpeed[i] > maxRwSpeed) { rwCmdSpeed[i] = maxRwSpeed; } else if (rwCmdSpeed[i] < -maxRwSpeed) { rwCmdSpeed[i] = -maxRwSpeed; } - } - VectorOperations::mulScalar(rwCmdSpeed, 10, rwCmdSpeed, 4); + } } void ActuatorCmd::cmdDipolMtq(const double *dipolMoment, int16_t *dipolMomentActuator, From f71fe274f4e81febf670e171cf658825b670d357 Mon Sep 17 00:00:00 2001 From: meggert Date: Mon, 13 Mar 2023 10:05:54 +0100 Subject: [PATCH 112/112] changelog --- CHANGELOG.md | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/CHANGELOG.md b/CHANGELOG.md index 69d8cf6a..dd1f57a2 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -16,6 +16,11 @@ will consitute of a breaking change warranting a new major release: # [unreleased] +## Fixed + +- Pointing control of the `AcsController` was still expecting submodes instead of modes. +- Limitation of RW speeds was done before converting them to the correct unit scale. + # [v1.37.0] 2023-03-11 eive-tmtc: v2.18.1